From 1c3207945a4feefc79b33157b7eaff7a8a7556cc Mon Sep 17 00:00:00 2001 From: 1heart Date: Tue, 12 Apr 2022 11:37:42 -0700 Subject: [PATCH 01/69] Randomly initialize eyehandcal optimization problem using seed --- .../scripts/collect_data_and_cal.py | 25 +++++++++++++------ 1 file changed, 17 insertions(+), 8 deletions(-) diff --git a/perception/sandbox/eyehandcal/scripts/collect_data_and_cal.py b/perception/sandbox/eyehandcal/scripts/collect_data_and_cal.py index a994d133a7..1185430ce5 100755 --- a/perception/sandbox/eyehandcal/scripts/collect_data_and_cal.py +++ b/perception/sandbox/eyehandcal/scripts/collect_data_and_cal.py @@ -118,6 +118,7 @@ def extract_obs_data_std(data, camera_index): import argparse parser=argparse.ArgumentParser() + parser.add_argument('--seed', default=0, type=int, help="random seed for initializing solution") parser.add_argument('--ip', default='100.96.135.68', help="robot ip address") parser.add_argument('--datafile', default='caldata.pkl', help="file to either load or save camera data") parser.add_argument('--overwrite', default=False, action='store_true', help="overwrite existing datafile, if it exists") @@ -131,6 +132,10 @@ def extract_obs_data_std(data, camera_index): args=parser.parse_args() print(f"Config: {args}") + np.random.seed(args.seed) + torch.manual_seed(args.seed) + torch.cuda.manual_seed_all(args.seed) + if os.path.exists(args.datafile) and not args.overwrite: print(f"Warning: datafile {args.datafile} already exists. Loading data instead of collecting data...") data = pickle.load(open(args.datafile, 'rb')) @@ -176,14 +181,18 @@ def extract_obs_data_std(data, camera_index): print(f'Solve camera {i} pose') obs_data_std, K = extract_obs_data_std(corner_data, i) print('number of images with keypoint', len(obs_data_std)) - param=torch.zeros(9, dtype=torch.float64, requires_grad=True) - L = lambda param: mean_loss(obs_data_std, param, K) - try: - param_star=find_parameter(param, obs_data_std, K) - except: - continue - - print('found param loss (mean pixel err)', L(param_star).item()) + loss = 9999 + while loss > 1.0: + param=torch.randn(9, dtype=torch.float64, requires_grad=True) + L = lambda param: mean_loss(obs_data_std, param, K) + try: + param_star=find_parameter(param, obs_data_std, K) + except Exception as e: + print(e) + continue + + loss = L(param_star).item() + print('found param loss (mean pixel err)', loss) params.append(param_star) with torch.no_grad(): From 964a422bd16689cd13de5cece2e09c01efbf8daf Mon Sep 17 00:00:00 2001 From: 1heart Date: Tue, 12 Apr 2022 13:17:42 -0700 Subject: [PATCH 02/69] WIP run_grasp overall architecture --- perception/sandbox/polygrasp/.envrc | 1 + perception/sandbox/polygrasp/README.md | 0 .../sandbox/polygrasp/scripts/run_grasp.py | 51 +++++++++++++++++++ perception/sandbox/polygrasp/setup.py | 19 +++++++ .../polygrasp/src/polygrasp/__init__.py | 0 .../polygrasp/src/polygrasp/grasp_server.py | 0 .../src/polygrasp/robot_interface.py | 4 ++ 7 files changed, 75 insertions(+) create mode 100644 perception/sandbox/polygrasp/.envrc create mode 100644 perception/sandbox/polygrasp/README.md create mode 100644 perception/sandbox/polygrasp/scripts/run_grasp.py create mode 100644 perception/sandbox/polygrasp/setup.py create mode 100644 perception/sandbox/polygrasp/src/polygrasp/__init__.py create mode 100644 perception/sandbox/polygrasp/src/polygrasp/grasp_server.py create mode 100644 perception/sandbox/polygrasp/src/polygrasp/robot_interface.py diff --git a/perception/sandbox/polygrasp/.envrc b/perception/sandbox/polygrasp/.envrc new file mode 100644 index 0000000000..f0916362be --- /dev/null +++ b/perception/sandbox/polygrasp/.envrc @@ -0,0 +1 @@ +layout_miniconda polygrasp diff --git a/perception/sandbox/polygrasp/README.md b/perception/sandbox/polygrasp/README.md new file mode 100644 index 0000000000..e69de29bb2 diff --git a/perception/sandbox/polygrasp/scripts/run_grasp.py b/perception/sandbox/polygrasp/scripts/run_grasp.py new file mode 100644 index 0000000000..42b11273dd --- /dev/null +++ b/perception/sandbox/polygrasp/scripts/run_grasp.py @@ -0,0 +1,51 @@ +""" +Connects to robot, camera(s), gripper, and grasp server. +Runs grasps generated from grasp server. +""" + +import random +import json + + +if __name__ == "__main__": + # Initialize robot & gripper + robot = RobotInterface() + gripper = GripperInterface() + robot.init_gripper(gripper) + + # Initialize cameras + cameras = RealsenseAPI() + camera_intrinsics = cameras.get_intrinsics() + camera_extrinsics = json.load("/path/to/calibration.json") + + # Connect to grasp candidate selection and pointcloud processor + pcd_client = PointCloudClient(camera_intrinsics, camera_extrinsics) + grasp_suggester = GraspInterface() + + num_iters = 1 + for i in range(num_iters): + # Get RGBD & pointcloud + rgbd = cameras.get_rgbd() + scene_pcd = pcd_client.get_pcd(rgbd) + + # Get grasps per object + obj_to_pcd = pcd_client.segment_pcd(scene_pcd) + obj_to_grasps = {obj: grasp_suggester.get_grasps(pcd) for obj, pcd in obj_to_pcd.items()} + + # Pick a random object to grasp + curr_obj, curr_grasps = random.choice(list(obj_to_grasps.items())) + print(f"Picking object with ID {curr_obj}") + + # Choose a grasp for this object + # TODO: scene-aware motion planning for grasps + des_ee_pos, des_ee_ori = robot.select_grasp(curr_grasps, scene_pcd) + + # Execute grasp + traj, success = robot.grasp(ee_pos=des_ee_pos, ee_ori=des_ee_ori) + print(f"Grasp success: {success}") + + if success: + print(f"Moving end-effector up and down") + curr_pose, curr_ori = robot.get_ee_pose() + robot.move_to_ee_pose(torch.Tensor([0, 0, 0.1]), delta=True) + robot.move_to_ee_pose(torch.Tensor([0, 0, -0.1]), delta=True) diff --git a/perception/sandbox/polygrasp/setup.py b/perception/sandbox/polygrasp/setup.py new file mode 100644 index 0000000000..7400dac802 --- /dev/null +++ b/perception/sandbox/polygrasp/setup.py @@ -0,0 +1,19 @@ +from setuptools import setup, find_packages + +""" +Wrapper package defining the interface for grasping primitives in Fairo. +""" + +__author__ = "Yixin Lin" +__copyright__ = "2022, Meta" + + +setup( + name="polygrasp", + author="Yixin Lin", + author_email="yixinlin@fb.com", + version="0.1", + packages=find_packages(where="src"), + package_dir={"": "src"}, + scripts=["scripts/run_grasp.py"], +) diff --git a/perception/sandbox/polygrasp/src/polygrasp/__init__.py b/perception/sandbox/polygrasp/src/polygrasp/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_server.py b/perception/sandbox/polygrasp/src/polygrasp/grasp_server.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py new file mode 100644 index 0000000000..4e73d9f210 --- /dev/null +++ b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py @@ -0,0 +1,4 @@ +"""polymetis.RobotInterface combined with GripperInterface, with an additional `grasp` method.""" + +import polymetis + From 01607b4ac8d6dc3121c9cff3ce1bfc387ec9bfa6 Mon Sep 17 00:00:00 2001 From: 1heart Date: Tue, 12 Apr 2022 14:58:37 -0700 Subject: [PATCH 03/69] Minor np.zeros-->np.empty --- .../realsense_wrapper/realsense_d435.py | 2 +- perception/sandbox/eyehandcal/.envrc | 1 - .../scripts/collect_data_and_cal.py | 6 +++--- perception/sandbox/polygrasp/README.md | 19 +++++++++++++++++++ .../sandbox/polygrasp/scripts/run_grasp.py | 19 ++++++++++++++----- perception/sandbox/polygrasp/setup.py | 7 +++++++ .../src/polygrasp/robot_interface.py | 9 +++++++++ 7 files changed, 53 insertions(+), 10 deletions(-) delete mode 100644 perception/sandbox/eyehandcal/.envrc diff --git a/perception/realsense_driver/python/realsense_wrapper/realsense_d435.py b/perception/realsense_driver/python/realsense_wrapper/realsense_d435.py index 471356ad80..21acfc1fcf 100644 --- a/perception/realsense_driver/python/realsense_wrapper/realsense_d435.py +++ b/perception/realsense_driver/python/realsense_wrapper/realsense_d435.py @@ -61,7 +61,7 @@ def get_rgbd(self): framesets = self._get_frames() num_cams = self.get_num_cameras() - rgbd = np.zeros([num_cams, self.height, self.width, 4], dtype=np.uint16) + rgbd = np.empty([num_cams, self.height, self.width, 4], dtype=np.uint16) for i, frameset in enumerate(framesets): color_frame = frameset.get_color_frame() diff --git a/perception/sandbox/eyehandcal/.envrc b/perception/sandbox/eyehandcal/.envrc deleted file mode 100644 index ea148ff778..0000000000 --- a/perception/sandbox/eyehandcal/.envrc +++ /dev/null @@ -1 +0,0 @@ -layout_miniconda eyehandcal diff --git a/perception/sandbox/eyehandcal/scripts/collect_data_and_cal.py b/perception/sandbox/eyehandcal/scripts/collect_data_and_cal.py index 1185430ce5..4f7df80bb1 100755 --- a/perception/sandbox/eyehandcal/scripts/collect_data_and_cal.py +++ b/perception/sandbox/eyehandcal/scripts/collect_data_and_cal.py @@ -37,12 +37,12 @@ def realsense_images(max_pixel_diff=200): for i in range(30*5): - rs.get_images() + rs.get_rgbd() count=0 while True: - imgs0 = rs.get_images() + imgs0 = rs.get_rgbd()[:, :, :, :3] for i in range(30): - imgs1 = rs.get_images() + imgs1 = rs.get_rgbd()[:, :, :, :3] pixel_diff=[] for i in range(num_cameras): pixel_diff.append(np.abs(imgs0[i].astype(np.int32)-imgs1[i].astype(np.int32)).reshape(-1)) diff --git a/perception/sandbox/polygrasp/README.md b/perception/sandbox/polygrasp/README.md index e69de29bb2..020f332ef2 100644 --- a/perception/sandbox/polygrasp/README.md +++ b/perception/sandbox/polygrasp/README.md @@ -0,0 +1,19 @@ +# Polygrasp + +## Installation + +```bash +pip install ../../realsense_driver +pip install -e . +``` + +## Development + +### Recompiling grasping gRPC server + +```bash +# from root directory +python -m grpc_tools.protoc -I . --python_out=. --grpc_python_out=. farsighted_mpc/grasp_rpc/graspnet_policy.proto +``` + +Note that it's important to point the arguments of `-I`, `--python_out`, `grpc_python_out` to `.` so that the `.proto` argument uses the full directory structure instead of attempting to import the `_pb2` file without relative imports, as described in [this comment](https://github.com/grpc/grpc/issues/9575#issuecomment-293934506). diff --git a/perception/sandbox/polygrasp/scripts/run_grasp.py b/perception/sandbox/polygrasp/scripts/run_grasp.py index 42b11273dd..03480d221f 100644 --- a/perception/sandbox/polygrasp/scripts/run_grasp.py +++ b/perception/sandbox/polygrasp/scripts/run_grasp.py @@ -1,3 +1,4 @@ +#!/usr/bin/env python """ Connects to robot, camera(s), gripper, and grasp server. Runs grasps generated from grasp server. @@ -6,17 +7,22 @@ import random import json +import hydra +import torch -if __name__ == "__main__": +from realsense_wrapper import RealsenseAPI + + +@hydra.main(config_path="../conf", config_name="run_grasp") +def main(cfg): # Initialize robot & gripper - robot = RobotInterface() - gripper = GripperInterface() - robot.init_gripper(gripper) + robot = hydra.utils.instantiate(cfg.robot) # Initialize cameras cameras = RealsenseAPI() camera_intrinsics = cameras.get_intrinsics() - camera_extrinsics = json.load("/path/to/calibration.json") + import pdb; pdb.set_trace() + camera_extrinsics = json.load(hydra.utils.to_absolute_path(cfg.camera_extrinsics_path)) # Connect to grasp candidate selection and pointcloud processor pcd_client = PointCloudClient(camera_intrinsics, camera_extrinsics) @@ -49,3 +55,6 @@ curr_pose, curr_ori = robot.get_ee_pose() robot.move_to_ee_pose(torch.Tensor([0, 0, 0.1]), delta=True) robot.move_to_ee_pose(torch.Tensor([0, 0, -0.1]), delta=True) + +if __name__ == "__main__": + main() diff --git a/perception/sandbox/polygrasp/setup.py b/perception/sandbox/polygrasp/setup.py index 7400dac802..5dd457f262 100644 --- a/perception/sandbox/polygrasp/setup.py +++ b/perception/sandbox/polygrasp/setup.py @@ -8,6 +8,12 @@ __copyright__ = "2022, Meta" +install_requires = [ + "grpcio-tools", + "realsense_wrapper", +] + + setup( name="polygrasp", author="Yixin Lin", @@ -16,4 +22,5 @@ packages=find_packages(where="src"), package_dir={"": "src"}, scripts=["scripts/run_grasp.py"], + install_requires=install_requires, ) diff --git a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py index 4e73d9f210..86a672148c 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py +++ b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py @@ -2,3 +2,12 @@ import polymetis +class GraspingRobotInterface(polymetis.RobotInterface): + def __init__(self, gripper: polymetis.GripperInterface, *args, **kwargs): + self.gripper = gripper + + def select_grasp(self): + raise NotImplementedError + + def grasp(self): + raise NotImplementedError From d6617bf4781d2e36c4242168ef9303311cd2f7be Mon Sep 17 00:00:00 2001 From: 1heart Date: Tue, 12 Apr 2022 15:07:30 -0700 Subject: [PATCH 04/69] Fix for eyehandcal after realsense_wrapper changes --- perception/sandbox/eyehandcal/src/eyehandcal/utils.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/perception/sandbox/eyehandcal/src/eyehandcal/utils.py b/perception/sandbox/eyehandcal/src/eyehandcal/utils.py index 8eec46fe85..cfbed9dd96 100644 --- a/perception/sandbox/eyehandcal/src/eyehandcal/utils.py +++ b/perception/sandbox/eyehandcal/src/eyehandcal/utils.py @@ -20,7 +20,7 @@ def detect_corners(data, target_idx=9): for i,d in enumerate(data): d['corners'] = [] for j, img in enumerate(d['imgs']): - result=cv2.aruco.detectMarkers(img, dictionary=aruco_dict, parameters=aruco_param) + result=cv2.aruco.detectMarkers(img.astype(np.uint8), dictionary=aruco_dict, parameters=aruco_param) corners, idx, rej = result if idx is not None and target_idx in idx: corner_i = idx.squeeze(axis=1).tolist().index(target_idx) From a7d423a678e0bbf73bcb814324e384afffe294ad Mon Sep 17 00:00:00 2001 From: 1heart Date: Tue, 12 Apr 2022 15:11:26 -0700 Subject: [PATCH 05/69] Add calibration.json to git --- perception/sandbox/eyehandcal/calibration.json | 1 + 1 file changed, 1 insertion(+) create mode 100644 perception/sandbox/eyehandcal/calibration.json diff --git a/perception/sandbox/eyehandcal/calibration.json b/perception/sandbox/eyehandcal/calibration.json new file mode 100644 index 0000000000..f04ca720b0 --- /dev/null +++ b/perception/sandbox/eyehandcal/calibration.json @@ -0,0 +1 @@ +[{"camera_base_ori": [[0.26409044817941857, 0.825273138571934, -0.4991798092191058], [0.9525163207711836, -0.14183692424830754, 0.2694344921948697], [0.15155492022669972, -0.5466319910793817, -0.8235439104769516]], "camera_base_pos": [1.1291315251953709, -0.2753188179094922, 0.5569095587922862], "p_marker_ee": [0.015322587564300124, -0.038835170426504806, 0.026367184321188546]}, {"camera_base_ori": [[-0.18867848441225005, 0.7704958715146015, -0.6088813854100419], [0.9809375354448933, 0.1772251307844472, -0.07970448277063993], [0.046497108245525984, -0.6123131265924243, -0.7892468903501708]], "camera_base_pos": [1.1557640304457628, 0.014638761756131623, 0.5888482354657805], "p_marker_ee": [0.0163895039251977, -0.04061809460390124, 0.025997698827580684]}, {"camera_base_ori": [[0.14824094137531774, 0.8257732465467157, -0.5441720027600243], [0.9853957807889722, -0.07671859985098213, 0.15201780040572893], [0.08378411844407617, -0.5587600573811629, -0.8250863104984515]], "camera_base_pos": [1.1854638003698477, -0.12587317688777955, 0.5886276100325791], "p_marker_ee": [0.016426117187848647, -0.03989797101227346, 0.026216040109795787]}] \ No newline at end of file From 316b9f020bca672b24b1d243a2a14c148a563285 Mon Sep 17 00:00:00 2001 From: 1heart Date: Tue, 12 Apr 2022 15:12:28 -0700 Subject: [PATCH 06/69] Add grasp_server proto init --- perception/sandbox/polygrasp/README.md | 2 +- .../src/polygrasp/grasp_server.proto | 24 ++++ .../src/polygrasp/grasp_server_pb2.py | 60 +++++++++ .../src/polygrasp/grasp_server_pb2_grpc.py | 127 ++++++++++++++++++ 4 files changed, 212 insertions(+), 1 deletion(-) create mode 100644 perception/sandbox/polygrasp/src/polygrasp/grasp_server.proto create mode 100644 perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2.py create mode 100644 perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2_grpc.py diff --git a/perception/sandbox/polygrasp/README.md b/perception/sandbox/polygrasp/README.md index 020f332ef2..76ef66188f 100644 --- a/perception/sandbox/polygrasp/README.md +++ b/perception/sandbox/polygrasp/README.md @@ -13,7 +13,7 @@ pip install -e . ```bash # from root directory -python -m grpc_tools.protoc -I . --python_out=. --grpc_python_out=. farsighted_mpc/grasp_rpc/graspnet_policy.proto +python -m grpc_tools.protoc -I . --python_out=. --grpc_python_out=. src/polygrasp/grasp_server.proto ``` Note that it's important to point the arguments of `-I`, `--python_out`, `grpc_python_out` to `.` so that the `.proto` argument uses the full directory structure instead of attempting to import the `_pb2` file without relative imports, as described in [this comment](https://github.com/grpc/grpc/issues/9575#issuecomment-293934506). diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_server.proto b/perception/sandbox/polygrasp/src/polygrasp/grasp_server.proto new file mode 100644 index 0000000000..d61e760484 --- /dev/null +++ b/perception/sandbox/polygrasp/src/polygrasp/grasp_server.proto @@ -0,0 +1,24 @@ +syntax = "proto3"; + +package polygrasp; + +service GraspServer { + rpc GetGrasps(stream PointCloud) returns (stream GraspGroup) {} +} + +service PointCloudServer { + rpc GetPointcloud(stream Image) returns (stream PointCloud) {} +} + +message Image { + bytes rgbd = 1; +} + +message PointCloud { + bytes pcd = 1; + bytes color = 2; +} + +message GraspGroup { + bytes grasp_group_array = 1; +} diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2.py b/perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2.py new file mode 100644 index 0000000000..64a9539f12 --- /dev/null +++ b/perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2.py @@ -0,0 +1,60 @@ +# -*- coding: utf-8 -*- +# Generated by the protocol buffer compiler. DO NOT EDIT! +# source: src/polygrasp/grasp_server.proto +"""Generated protocol buffer code.""" +from google.protobuf import descriptor as _descriptor +from google.protobuf import descriptor_pool as _descriptor_pool +from google.protobuf import message as _message +from google.protobuf import reflection as _reflection +from google.protobuf import symbol_database as _symbol_database +# @@protoc_insertion_point(imports) + +_sym_db = _symbol_database.Default() + + + + +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n src/polygrasp/grasp_server.proto\x12\tpolygrasp\"\x15\n\x05Image\x12\x0c\n\x04rgbd\x18\x01 \x01(\x0c\"(\n\nPointCloud\x12\x0b\n\x03pcd\x18\x01 \x01(\x0c\x12\r\n\x05\x63olor\x18\x02 \x01(\x0c\"\'\n\nGraspGroup\x12\x19\n\x11grasp_group_array\x18\x01 \x01(\x0c\x32N\n\x0bGraspServer\x12?\n\tGetGrasps\x12\x15.polygrasp.PointCloud\x1a\x15.polygrasp.GraspGroup\"\x00(\x01\x30\x01\x32R\n\x10PointCloudServer\x12>\n\rGetPointcloud\x12\x10.polygrasp.Image\x1a\x15.polygrasp.PointCloud\"\x00(\x01\x30\x01\x62\x06proto3') + + + +_IMAGE = DESCRIPTOR.message_types_by_name['Image'] +_POINTCLOUD = DESCRIPTOR.message_types_by_name['PointCloud'] +_GRASPGROUP = DESCRIPTOR.message_types_by_name['GraspGroup'] +Image = _reflection.GeneratedProtocolMessageType('Image', (_message.Message,), { + 'DESCRIPTOR' : _IMAGE, + '__module__' : 'src.polygrasp.grasp_server_pb2' + # @@protoc_insertion_point(class_scope:polygrasp.Image) + }) +_sym_db.RegisterMessage(Image) + +PointCloud = _reflection.GeneratedProtocolMessageType('PointCloud', (_message.Message,), { + 'DESCRIPTOR' : _POINTCLOUD, + '__module__' : 'src.polygrasp.grasp_server_pb2' + # @@protoc_insertion_point(class_scope:polygrasp.PointCloud) + }) +_sym_db.RegisterMessage(PointCloud) + +GraspGroup = _reflection.GeneratedProtocolMessageType('GraspGroup', (_message.Message,), { + 'DESCRIPTOR' : _GRASPGROUP, + '__module__' : 'src.polygrasp.grasp_server_pb2' + # @@protoc_insertion_point(class_scope:polygrasp.GraspGroup) + }) +_sym_db.RegisterMessage(GraspGroup) + +_GRASPSERVER = DESCRIPTOR.services_by_name['GraspServer'] +_POINTCLOUDSERVER = DESCRIPTOR.services_by_name['PointCloudServer'] +if _descriptor._USE_C_DESCRIPTORS == False: + + DESCRIPTOR._options = None + _IMAGE._serialized_start=47 + _IMAGE._serialized_end=68 + _POINTCLOUD._serialized_start=70 + _POINTCLOUD._serialized_end=110 + _GRASPGROUP._serialized_start=112 + _GRASPGROUP._serialized_end=151 + _GRASPSERVER._serialized_start=153 + _GRASPSERVER._serialized_end=231 + _POINTCLOUDSERVER._serialized_start=233 + _POINTCLOUDSERVER._serialized_end=315 +# @@protoc_insertion_point(module_scope) diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2_grpc.py b/perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2_grpc.py new file mode 100644 index 0000000000..4dcd6ca73b --- /dev/null +++ b/perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2_grpc.py @@ -0,0 +1,127 @@ +# Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! +"""Client and server classes corresponding to protobuf-defined services.""" +import grpc + +from src.polygrasp import grasp_server_pb2 as src_dot_polygrasp_dot_grasp__server__pb2 + + +class GraspServerStub(object): + """Missing associated documentation comment in .proto file.""" + + def __init__(self, channel): + """Constructor. + + Args: + channel: A grpc.Channel. + """ + self.GetGrasps = channel.stream_stream( + '/polygrasp.GraspServer/GetGrasps', + request_serializer=src_dot_polygrasp_dot_grasp__server__pb2.PointCloud.SerializeToString, + response_deserializer=src_dot_polygrasp_dot_grasp__server__pb2.GraspGroup.FromString, + ) + + +class GraspServerServicer(object): + """Missing associated documentation comment in .proto file.""" + + def GetGrasps(self, request_iterator, context): + """Missing associated documentation comment in .proto file.""" + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + + +def add_GraspServerServicer_to_server(servicer, server): + rpc_method_handlers = { + 'GetGrasps': grpc.stream_stream_rpc_method_handler( + servicer.GetGrasps, + request_deserializer=src_dot_polygrasp_dot_grasp__server__pb2.PointCloud.FromString, + response_serializer=src_dot_polygrasp_dot_grasp__server__pb2.GraspGroup.SerializeToString, + ), + } + generic_handler = grpc.method_handlers_generic_handler( + 'polygrasp.GraspServer', rpc_method_handlers) + server.add_generic_rpc_handlers((generic_handler,)) + + + # This class is part of an EXPERIMENTAL API. +class GraspServer(object): + """Missing associated documentation comment in .proto file.""" + + @staticmethod + def GetGrasps(request_iterator, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.stream_stream(request_iterator, target, '/polygrasp.GraspServer/GetGrasps', + src_dot_polygrasp_dot_grasp__server__pb2.PointCloud.SerializeToString, + src_dot_polygrasp_dot_grasp__server__pb2.GraspGroup.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + + +class PointCloudServerStub(object): + """Missing associated documentation comment in .proto file.""" + + def __init__(self, channel): + """Constructor. + + Args: + channel: A grpc.Channel. + """ + self.GetPointcloud = channel.stream_stream( + '/polygrasp.PointCloudServer/GetPointcloud', + request_serializer=src_dot_polygrasp_dot_grasp__server__pb2.Image.SerializeToString, + response_deserializer=src_dot_polygrasp_dot_grasp__server__pb2.PointCloud.FromString, + ) + + +class PointCloudServerServicer(object): + """Missing associated documentation comment in .proto file.""" + + def GetPointcloud(self, request_iterator, context): + """Missing associated documentation comment in .proto file.""" + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + + +def add_PointCloudServerServicer_to_server(servicer, server): + rpc_method_handlers = { + 'GetPointcloud': grpc.stream_stream_rpc_method_handler( + servicer.GetPointcloud, + request_deserializer=src_dot_polygrasp_dot_grasp__server__pb2.Image.FromString, + response_serializer=src_dot_polygrasp_dot_grasp__server__pb2.PointCloud.SerializeToString, + ), + } + generic_handler = grpc.method_handlers_generic_handler( + 'polygrasp.PointCloudServer', rpc_method_handlers) + server.add_generic_rpc_handlers((generic_handler,)) + + + # This class is part of an EXPERIMENTAL API. +class PointCloudServer(object): + """Missing associated documentation comment in .proto file.""" + + @staticmethod + def GetPointcloud(request_iterator, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.stream_stream(request_iterator, target, '/polygrasp.PointCloudServer/GetPointcloud', + src_dot_polygrasp_dot_grasp__server__pb2.Image.SerializeToString, + src_dot_polygrasp_dot_grasp__server__pb2.PointCloud.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) From 7d5e86db5ed2b671666e875c2e9424bcd7509b76 Mon Sep 17 00:00:00 2001 From: 1heart Date: Tue, 12 Apr 2022 16:26:20 -0700 Subject: [PATCH 07/69] WIP server/client architecture --- perception/sandbox/polygrasp/README.md | 2 +- .../sandbox/polygrasp/conf/run_grasp.yaml | 8 +++ .../sandbox/polygrasp/scripts/run_grasp.py | 7 +- .../polygrasp/src/polygrasp/grasp_rpc.py | 39 +++++++++++ .../src/polygrasp/grasp_server_pb2.py | 60 ---------------- .../polygrasp/src/polygrasp/pointcloud_rpc.py | 44 ++++++++++++ .../{grasp_server.proto => polygrasp.proto} | 6 ++ .../polygrasp/src/polygrasp/polygrasp_pb2.py | 70 +++++++++++++++++++ ...rver_pb2_grpc.py => polygrasp_pb2_grpc.py} | 59 ++++++++++++---- .../polygrasp/{grasp_server.py => utils.py} | 0 10 files changed, 219 insertions(+), 76 deletions(-) create mode 100644 perception/sandbox/polygrasp/conf/run_grasp.yaml create mode 100644 perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py delete mode 100644 perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2.py create mode 100644 perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py rename perception/sandbox/polygrasp/src/polygrasp/{grasp_server.proto => polygrasp.proto} (74%) create mode 100644 perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2.py rename perception/sandbox/polygrasp/src/polygrasp/{grasp_server_pb2_grpc.py => polygrasp_pb2_grpc.py} (58%) rename perception/sandbox/polygrasp/src/polygrasp/{grasp_server.py => utils.py} (100%) diff --git a/perception/sandbox/polygrasp/README.md b/perception/sandbox/polygrasp/README.md index 76ef66188f..b5007ef86a 100644 --- a/perception/sandbox/polygrasp/README.md +++ b/perception/sandbox/polygrasp/README.md @@ -13,7 +13,7 @@ pip install -e . ```bash # from root directory -python -m grpc_tools.protoc -I . --python_out=. --grpc_python_out=. src/polygrasp/grasp_server.proto +python -m grpc_tools.protoc -I src --python_out=src --grpc_python_out=src polygrasp/polygrasp.proto ``` Note that it's important to point the arguments of `-I`, `--python_out`, `grpc_python_out` to `.` so that the `.proto` argument uses the full directory structure instead of attempting to import the `_pb2` file without relative imports, as described in [this comment](https://github.com/grpc/grpc/issues/9575#issuecomment-293934506). diff --git a/perception/sandbox/polygrasp/conf/run_grasp.yaml b/perception/sandbox/polygrasp/conf/run_grasp.yaml new file mode 100644 index 0000000000..31149923e2 --- /dev/null +++ b/perception/sandbox/polygrasp/conf/run_grasp.yaml @@ -0,0 +1,8 @@ +robot: + _target_: polygrasp.robot_interface.GraspingRobotInterface + ip_address: "100.67.224.116" + enforce_version: false + gripper: + _target_: polymetis.GripperInterface + +camera_extrinsics_path: ../eyehandcal/calibration.json \ No newline at end of file diff --git a/perception/sandbox/polygrasp/scripts/run_grasp.py b/perception/sandbox/polygrasp/scripts/run_grasp.py index 03480d221f..e938182682 100644 --- a/perception/sandbox/polygrasp/scripts/run_grasp.py +++ b/perception/sandbox/polygrasp/scripts/run_grasp.py @@ -12,6 +12,9 @@ from realsense_wrapper import RealsenseAPI +from polygrasp.pointcloud_rpc import PointCloudClient +from polygrasp.grasp_rpc import GraspClient + @hydra.main(config_path="../conf", config_name="run_grasp") def main(cfg): @@ -21,12 +24,12 @@ def main(cfg): # Initialize cameras cameras = RealsenseAPI() camera_intrinsics = cameras.get_intrinsics() - import pdb; pdb.set_trace() camera_extrinsics = json.load(hydra.utils.to_absolute_path(cfg.camera_extrinsics_path)) # Connect to grasp candidate selection and pointcloud processor + import pdb; pdb.set_trace() pcd_client = PointCloudClient(camera_intrinsics, camera_extrinsics) - grasp_suggester = GraspInterface() + grasp_suggester = GraspClient() num_iters = 1 for i in range(num_iters): diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py new file mode 100644 index 0000000000..28c8b65851 --- /dev/null +++ b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py @@ -0,0 +1,39 @@ +from typing import Iterator +import logging +from concurrent import futures + +import numpy as np +import open3d + +import grpc +from polygrasp import polygrasp_pb2 +from polygrasp import polygrasp_pb2_grpc + + +log = logging.getLogger(__name__) + + +class GraspServer(polygrasp_pb2_grpc.GraspServer): + def _get_grasps(self, pcd: open3d.geometry.PointCloud) -> np.ndarray: + raise NotImplementedError + + def GetGrasps(self, request_iterator: Iterator[polygrasp_pb2.PointCloud], context) -> Iterator[polygrasp_pb2.GraspGroup]: + raise NotImplementedError + + +class GraspClient: + def get_grasps(pcd: open3d.geometry.PointCloud) -> np.ndarray: + raise NotImplementedError + +def serve(port=50053, max_workers=10, *args, **kwargs): + server = grpc.server(futures.ThreadPoolExecutor(max_workers=max_workers)) + polygrasp_pb2_grpc.add_GraspServerServicer_to_server(GraspServer(*args, **kwargs), server) + server.add_insecure_port(f"[::]:{port}") + log.info(f"=== Starting server... ===") + server.start() + log.info(f"=== Done. Server running at port {port}. ===") + server.wait_for_termination() + + +if __name__ == "__main__": + serve() diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2.py b/perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2.py deleted file mode 100644 index 64a9539f12..0000000000 --- a/perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2.py +++ /dev/null @@ -1,60 +0,0 @@ -# -*- coding: utf-8 -*- -# Generated by the protocol buffer compiler. DO NOT EDIT! -# source: src/polygrasp/grasp_server.proto -"""Generated protocol buffer code.""" -from google.protobuf import descriptor as _descriptor -from google.protobuf import descriptor_pool as _descriptor_pool -from google.protobuf import message as _message -from google.protobuf import reflection as _reflection -from google.protobuf import symbol_database as _symbol_database -# @@protoc_insertion_point(imports) - -_sym_db = _symbol_database.Default() - - - - -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n src/polygrasp/grasp_server.proto\x12\tpolygrasp\"\x15\n\x05Image\x12\x0c\n\x04rgbd\x18\x01 \x01(\x0c\"(\n\nPointCloud\x12\x0b\n\x03pcd\x18\x01 \x01(\x0c\x12\r\n\x05\x63olor\x18\x02 \x01(\x0c\"\'\n\nGraspGroup\x12\x19\n\x11grasp_group_array\x18\x01 \x01(\x0c\x32N\n\x0bGraspServer\x12?\n\tGetGrasps\x12\x15.polygrasp.PointCloud\x1a\x15.polygrasp.GraspGroup\"\x00(\x01\x30\x01\x32R\n\x10PointCloudServer\x12>\n\rGetPointcloud\x12\x10.polygrasp.Image\x1a\x15.polygrasp.PointCloud\"\x00(\x01\x30\x01\x62\x06proto3') - - - -_IMAGE = DESCRIPTOR.message_types_by_name['Image'] -_POINTCLOUD = DESCRIPTOR.message_types_by_name['PointCloud'] -_GRASPGROUP = DESCRIPTOR.message_types_by_name['GraspGroup'] -Image = _reflection.GeneratedProtocolMessageType('Image', (_message.Message,), { - 'DESCRIPTOR' : _IMAGE, - '__module__' : 'src.polygrasp.grasp_server_pb2' - # @@protoc_insertion_point(class_scope:polygrasp.Image) - }) -_sym_db.RegisterMessage(Image) - -PointCloud = _reflection.GeneratedProtocolMessageType('PointCloud', (_message.Message,), { - 'DESCRIPTOR' : _POINTCLOUD, - '__module__' : 'src.polygrasp.grasp_server_pb2' - # @@protoc_insertion_point(class_scope:polygrasp.PointCloud) - }) -_sym_db.RegisterMessage(PointCloud) - -GraspGroup = _reflection.GeneratedProtocolMessageType('GraspGroup', (_message.Message,), { - 'DESCRIPTOR' : _GRASPGROUP, - '__module__' : 'src.polygrasp.grasp_server_pb2' - # @@protoc_insertion_point(class_scope:polygrasp.GraspGroup) - }) -_sym_db.RegisterMessage(GraspGroup) - -_GRASPSERVER = DESCRIPTOR.services_by_name['GraspServer'] -_POINTCLOUDSERVER = DESCRIPTOR.services_by_name['PointCloudServer'] -if _descriptor._USE_C_DESCRIPTORS == False: - - DESCRIPTOR._options = None - _IMAGE._serialized_start=47 - _IMAGE._serialized_end=68 - _POINTCLOUD._serialized_start=70 - _POINTCLOUD._serialized_end=110 - _GRASPGROUP._serialized_start=112 - _GRASPGROUP._serialized_end=151 - _GRASPSERVER._serialized_start=153 - _GRASPSERVER._serialized_end=231 - _POINTCLOUDSERVER._serialized_start=233 - _POINTCLOUDSERVER._serialized_end=315 -# @@protoc_insertion_point(module_scope) diff --git a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py new file mode 100644 index 0000000000..7f027b7552 --- /dev/null +++ b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py @@ -0,0 +1,44 @@ +from typing import Iterator +import logging +from concurrent import futures + +import numpy as np +import open3d + +import grpc +from polygrasp import polygrasp_pb2 +from polygrasp import polygrasp_pb2_grpc + + +log = logging.getLogger(__name__) + + +class PointCloudServer(polygrasp_pb2_grpc.PointCloudServer): + def GetPointcloud(self, request_iterator: Iterator[polygrasp_pb2.Image], context) -> Iterator[polygrasp_pb2.PointCloud]: + raise NotImplementedError + + def SegmentPointcloud(self, request_iterator: Iterator[polygrasp_pb2.PointCloud], context) -> Iterator[polygrasp_pb2.ObjectMask]: + raise NotImplementedError + +class PointCloudClient: + def __init__(self, camera_intrinsics: np.ndarray, camera_extrinsics: np.ndarray): + pass + + def get_pcd(self) -> open3d.geometry.PointCloud: + raise NotImplementedError + + def segment_pcd(self): + raise NotImplementedError + +def serve(port=50054, max_workers=10, *args, **kwargs): + server = grpc.server(futures.ThreadPoolExecutor(max_workers=max_workers)) + polygrasp_pb2_grpc.add_PointCloudServerServicer_to_server(PointCloudServer(*args, **kwargs), server) + server.add_insecure_port(f"[::]:{port}") + log.info(f"=== Starting server... ===") + server.start() + log.info(f"=== Done. Server running at port {port}. ===") + server.wait_for_termination() + + +if __name__ == "__main__": + serve() diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_server.proto b/perception/sandbox/polygrasp/src/polygrasp/polygrasp.proto similarity index 74% rename from perception/sandbox/polygrasp/src/polygrasp/grasp_server.proto rename to perception/sandbox/polygrasp/src/polygrasp/polygrasp.proto index d61e760484..cf4e40f61e 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/grasp_server.proto +++ b/perception/sandbox/polygrasp/src/polygrasp/polygrasp.proto @@ -8,12 +8,18 @@ service GraspServer { service PointCloudServer { rpc GetPointcloud(stream Image) returns (stream PointCloud) {} + rpc SegmentPointcloud(stream PointCloud) returns (stream ObjectMask) {} } message Image { bytes rgbd = 1; } +message ObjectMask { + int64 id = 1; + bytes mask = 2; +} + message PointCloud { bytes pcd = 1; bytes color = 2; diff --git a/perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2.py b/perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2.py new file mode 100644 index 0000000000..9975579de3 --- /dev/null +++ b/perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2.py @@ -0,0 +1,70 @@ +# -*- coding: utf-8 -*- +# Generated by the protocol buffer compiler. DO NOT EDIT! +# source: polygrasp/polygrasp.proto +"""Generated protocol buffer code.""" +from google.protobuf import descriptor as _descriptor +from google.protobuf import descriptor_pool as _descriptor_pool +from google.protobuf import message as _message +from google.protobuf import reflection as _reflection +from google.protobuf import symbol_database as _symbol_database +# @@protoc_insertion_point(imports) + +_sym_db = _symbol_database.Default() + + + + +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x19polygrasp/polygrasp.proto\x12\tpolygrasp\"\x15\n\x05Image\x12\x0c\n\x04rgbd\x18\x01 \x01(\x0c\"&\n\nObjectMask\x12\n\n\x02id\x18\x01 \x01(\x03\x12\x0c\n\x04mask\x18\x02 \x01(\x0c\"(\n\nPointCloud\x12\x0b\n\x03pcd\x18\x01 \x01(\x0c\x12\r\n\x05\x63olor\x18\x02 \x01(\x0c\"\'\n\nGraspGroup\x12\x19\n\x11grasp_group_array\x18\x01 \x01(\x0c\x32N\n\x0bGraspServer\x12?\n\tGetGrasps\x12\x15.polygrasp.PointCloud\x1a\x15.polygrasp.GraspGroup\"\x00(\x01\x30\x01\x32\x9b\x01\n\x10PointCloudServer\x12>\n\rGetPointcloud\x12\x10.polygrasp.Image\x1a\x15.polygrasp.PointCloud\"\x00(\x01\x30\x01\x12G\n\x11SegmentPointcloud\x12\x15.polygrasp.PointCloud\x1a\x15.polygrasp.ObjectMask\"\x00(\x01\x30\x01\x62\x06proto3') + + + +_IMAGE = DESCRIPTOR.message_types_by_name['Image'] +_OBJECTMASK = DESCRIPTOR.message_types_by_name['ObjectMask'] +_POINTCLOUD = DESCRIPTOR.message_types_by_name['PointCloud'] +_GRASPGROUP = DESCRIPTOR.message_types_by_name['GraspGroup'] +Image = _reflection.GeneratedProtocolMessageType('Image', (_message.Message,), { + 'DESCRIPTOR' : _IMAGE, + '__module__' : 'polygrasp.polygrasp_pb2' + # @@protoc_insertion_point(class_scope:polygrasp.Image) + }) +_sym_db.RegisterMessage(Image) + +ObjectMask = _reflection.GeneratedProtocolMessageType('ObjectMask', (_message.Message,), { + 'DESCRIPTOR' : _OBJECTMASK, + '__module__' : 'polygrasp.polygrasp_pb2' + # @@protoc_insertion_point(class_scope:polygrasp.ObjectMask) + }) +_sym_db.RegisterMessage(ObjectMask) + +PointCloud = _reflection.GeneratedProtocolMessageType('PointCloud', (_message.Message,), { + 'DESCRIPTOR' : _POINTCLOUD, + '__module__' : 'polygrasp.polygrasp_pb2' + # @@protoc_insertion_point(class_scope:polygrasp.PointCloud) + }) +_sym_db.RegisterMessage(PointCloud) + +GraspGroup = _reflection.GeneratedProtocolMessageType('GraspGroup', (_message.Message,), { + 'DESCRIPTOR' : _GRASPGROUP, + '__module__' : 'polygrasp.polygrasp_pb2' + # @@protoc_insertion_point(class_scope:polygrasp.GraspGroup) + }) +_sym_db.RegisterMessage(GraspGroup) + +_GRASPSERVER = DESCRIPTOR.services_by_name['GraspServer'] +_POINTCLOUDSERVER = DESCRIPTOR.services_by_name['PointCloudServer'] +if _descriptor._USE_C_DESCRIPTORS == False: + + DESCRIPTOR._options = None + _IMAGE._serialized_start=40 + _IMAGE._serialized_end=61 + _OBJECTMASK._serialized_start=63 + _OBJECTMASK._serialized_end=101 + _POINTCLOUD._serialized_start=103 + _POINTCLOUD._serialized_end=143 + _GRASPGROUP._serialized_start=145 + _GRASPGROUP._serialized_end=184 + _GRASPSERVER._serialized_start=186 + _GRASPSERVER._serialized_end=264 + _POINTCLOUDSERVER._serialized_start=267 + _POINTCLOUDSERVER._serialized_end=422 +# @@protoc_insertion_point(module_scope) diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2_grpc.py b/perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2_grpc.py similarity index 58% rename from perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2_grpc.py rename to perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2_grpc.py index 4dcd6ca73b..a9f0d07c2d 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/grasp_server_pb2_grpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2_grpc.py @@ -2,7 +2,7 @@ """Client and server classes corresponding to protobuf-defined services.""" import grpc -from src.polygrasp import grasp_server_pb2 as src_dot_polygrasp_dot_grasp__server__pb2 +from polygrasp import polygrasp_pb2 as polygrasp_dot_polygrasp__pb2 class GraspServerStub(object): @@ -16,8 +16,8 @@ def __init__(self, channel): """ self.GetGrasps = channel.stream_stream( '/polygrasp.GraspServer/GetGrasps', - request_serializer=src_dot_polygrasp_dot_grasp__server__pb2.PointCloud.SerializeToString, - response_deserializer=src_dot_polygrasp_dot_grasp__server__pb2.GraspGroup.FromString, + request_serializer=polygrasp_dot_polygrasp__pb2.PointCloud.SerializeToString, + response_deserializer=polygrasp_dot_polygrasp__pb2.GraspGroup.FromString, ) @@ -35,8 +35,8 @@ def add_GraspServerServicer_to_server(servicer, server): rpc_method_handlers = { 'GetGrasps': grpc.stream_stream_rpc_method_handler( servicer.GetGrasps, - request_deserializer=src_dot_polygrasp_dot_grasp__server__pb2.PointCloud.FromString, - response_serializer=src_dot_polygrasp_dot_grasp__server__pb2.GraspGroup.SerializeToString, + request_deserializer=polygrasp_dot_polygrasp__pb2.PointCloud.FromString, + response_serializer=polygrasp_dot_polygrasp__pb2.GraspGroup.SerializeToString, ), } generic_handler = grpc.method_handlers_generic_handler( @@ -60,8 +60,8 @@ def GetGrasps(request_iterator, timeout=None, metadata=None): return grpc.experimental.stream_stream(request_iterator, target, '/polygrasp.GraspServer/GetGrasps', - src_dot_polygrasp_dot_grasp__server__pb2.PointCloud.SerializeToString, - src_dot_polygrasp_dot_grasp__server__pb2.GraspGroup.FromString, + polygrasp_dot_polygrasp__pb2.PointCloud.SerializeToString, + polygrasp_dot_polygrasp__pb2.GraspGroup.FromString, options, channel_credentials, insecure, call_credentials, compression, wait_for_ready, timeout, metadata) @@ -77,8 +77,13 @@ def __init__(self, channel): """ self.GetPointcloud = channel.stream_stream( '/polygrasp.PointCloudServer/GetPointcloud', - request_serializer=src_dot_polygrasp_dot_grasp__server__pb2.Image.SerializeToString, - response_deserializer=src_dot_polygrasp_dot_grasp__server__pb2.PointCloud.FromString, + request_serializer=polygrasp_dot_polygrasp__pb2.Image.SerializeToString, + response_deserializer=polygrasp_dot_polygrasp__pb2.PointCloud.FromString, + ) + self.SegmentPointcloud = channel.stream_stream( + '/polygrasp.PointCloudServer/SegmentPointcloud', + request_serializer=polygrasp_dot_polygrasp__pb2.PointCloud.SerializeToString, + response_deserializer=polygrasp_dot_polygrasp__pb2.ObjectMask.FromString, ) @@ -91,13 +96,24 @@ def GetPointcloud(self, request_iterator, context): context.set_details('Method not implemented!') raise NotImplementedError('Method not implemented!') + def SegmentPointcloud(self, request_iterator, context): + """Missing associated documentation comment in .proto file.""" + context.set_code(grpc.StatusCode.UNIMPLEMENTED) + context.set_details('Method not implemented!') + raise NotImplementedError('Method not implemented!') + def add_PointCloudServerServicer_to_server(servicer, server): rpc_method_handlers = { 'GetPointcloud': grpc.stream_stream_rpc_method_handler( servicer.GetPointcloud, - request_deserializer=src_dot_polygrasp_dot_grasp__server__pb2.Image.FromString, - response_serializer=src_dot_polygrasp_dot_grasp__server__pb2.PointCloud.SerializeToString, + request_deserializer=polygrasp_dot_polygrasp__pb2.Image.FromString, + response_serializer=polygrasp_dot_polygrasp__pb2.PointCloud.SerializeToString, + ), + 'SegmentPointcloud': grpc.stream_stream_rpc_method_handler( + servicer.SegmentPointcloud, + request_deserializer=polygrasp_dot_polygrasp__pb2.PointCloud.FromString, + response_serializer=polygrasp_dot_polygrasp__pb2.ObjectMask.SerializeToString, ), } generic_handler = grpc.method_handlers_generic_handler( @@ -121,7 +137,24 @@ def GetPointcloud(request_iterator, timeout=None, metadata=None): return grpc.experimental.stream_stream(request_iterator, target, '/polygrasp.PointCloudServer/GetPointcloud', - src_dot_polygrasp_dot_grasp__server__pb2.Image.SerializeToString, - src_dot_polygrasp_dot_grasp__server__pb2.PointCloud.FromString, + polygrasp_dot_polygrasp__pb2.Image.SerializeToString, + polygrasp_dot_polygrasp__pb2.PointCloud.FromString, + options, channel_credentials, + insecure, call_credentials, compression, wait_for_ready, timeout, metadata) + + @staticmethod + def SegmentPointcloud(request_iterator, + target, + options=(), + channel_credentials=None, + call_credentials=None, + insecure=False, + compression=None, + wait_for_ready=None, + timeout=None, + metadata=None): + return grpc.experimental.stream_stream(request_iterator, target, '/polygrasp.PointCloudServer/SegmentPointcloud', + polygrasp_dot_polygrasp__pb2.PointCloud.SerializeToString, + polygrasp_dot_polygrasp__pb2.ObjectMask.FromString, options, channel_credentials, insecure, call_credentials, compression, wait_for_ready, timeout, metadata) diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_server.py b/perception/sandbox/polygrasp/src/polygrasp/utils.py similarity index 100% rename from perception/sandbox/polygrasp/src/polygrasp/grasp_server.py rename to perception/sandbox/polygrasp/src/polygrasp/utils.py From 62782059254eb7ec6e5d25c5b28427d4ee6cfb91 Mon Sep 17 00:00:00 2001 From: 1heart Date: Wed, 13 Apr 2022 14:51:01 -0700 Subject: [PATCH 08/69] Add msgs --- .circleci/config.yml | 7 + msg/.gitignore | 160 + msg/MANIFEST.in | 2 + msg/README.md | 18 + msg/msetup.py | 22 + msg/scripts/gen.py | 146 + msg/setup.py | 23 + msg/src/fairomsg/__init__.py | 2 + msg/src/fairomsg/cpp/actionlib_msgs.capnp.c++ | 671 ++ msg/src/fairomsg/cpp/actionlib_msgs.capnp.h | 617 ++ .../fairomsg/cpp/diagnostic_msgs.capnp.c++ | 453 ++ msg/src/fairomsg/cpp/diagnostic_msgs.capnp.h | 681 ++ msg/src/fairomsg/cpp/geometry_msgs.capnp.c++ | 2290 ++++++ msg/src/fairomsg/cpp/geometry_msgs.capnp.h | 5324 +++++++++++++ msg/src/fairomsg/cpp/nav_msgs.capnp.c++ | 987 +++ msg/src/fairomsg/cpp/nav_msgs.capnp.h | 2452 ++++++ msg/src/fairomsg/cpp/sensor_msgs.capnp.c++ | 5417 +++++++++++++ msg/src/fairomsg/cpp/sensor_msgs.capnp.h | 7096 +++++++++++++++++ msg/src/fairomsg/cpp/shape_msgs.capnp.c++ | 788 ++ msg/src/fairomsg/cpp/shape_msgs.capnp.h | 661 ++ msg/src/fairomsg/cpp/std_msgs.capnp.c++ | 1494 ++++ msg/src/fairomsg/cpp/std_msgs.capnp.h | 3427 ++++++++ msg/src/fairomsg/cpp/stereo_msgs.capnp.c++ | 185 + msg/src/fairomsg/cpp/stereo_msgs.capnp.h | 368 + .../fairomsg/cpp/trajectory_msgs.capnp.c++ | 472 ++ msg/src/fairomsg/cpp/trajectory_msgs.capnp.h | 1098 +++ .../fairomsg/cpp/visualization_msgs.capnp.c++ | 3605 +++++++++ .../fairomsg/cpp/visualization_msgs.capnp.h | 3593 +++++++++ msg/src/fairomsg/def/actionlib_msgs.capnp | 28 + msg/src/fairomsg/def/diagnostic_msgs.capnp | 23 + msg/src/fairomsg/def/geometry_msgs.capnp | 132 + msg/src/fairomsg/def/nav_msgs.capnp | 67 + msg/src/fairomsg/def/sensor_msgs.capnp | 249 + msg/src/fairomsg/def/shape_msgs.capnp | 30 + msg/src/fairomsg/def/std_msgs.capnp | 86 + msg/src/fairomsg/def/stereo_msgs.capnp | 16 + msg/src/fairomsg/def/trajectory_msgs.capnp | 30 + msg/src/fairomsg/def/visualization_msgs.capnp | 147 + msg/src/fairomsg/serdes.py | 28 + msg/tests/test_fairomsg.py | 13 + 40 files changed, 42908 insertions(+) create mode 100644 msg/.gitignore create mode 100644 msg/MANIFEST.in create mode 100644 msg/README.md create mode 100644 msg/msetup.py create mode 100644 msg/scripts/gen.py create mode 100644 msg/setup.py create mode 100644 msg/src/fairomsg/__init__.py create mode 100644 msg/src/fairomsg/cpp/actionlib_msgs.capnp.c++ create mode 100644 msg/src/fairomsg/cpp/actionlib_msgs.capnp.h create mode 100644 msg/src/fairomsg/cpp/diagnostic_msgs.capnp.c++ create mode 100644 msg/src/fairomsg/cpp/diagnostic_msgs.capnp.h create mode 100644 msg/src/fairomsg/cpp/geometry_msgs.capnp.c++ create mode 100644 msg/src/fairomsg/cpp/geometry_msgs.capnp.h create mode 100644 msg/src/fairomsg/cpp/nav_msgs.capnp.c++ create mode 100644 msg/src/fairomsg/cpp/nav_msgs.capnp.h create mode 100644 msg/src/fairomsg/cpp/sensor_msgs.capnp.c++ create mode 100644 msg/src/fairomsg/cpp/sensor_msgs.capnp.h create mode 100644 msg/src/fairomsg/cpp/shape_msgs.capnp.c++ create mode 100644 msg/src/fairomsg/cpp/shape_msgs.capnp.h create mode 100644 msg/src/fairomsg/cpp/std_msgs.capnp.c++ create mode 100644 msg/src/fairomsg/cpp/std_msgs.capnp.h create mode 100644 msg/src/fairomsg/cpp/stereo_msgs.capnp.c++ create mode 100644 msg/src/fairomsg/cpp/stereo_msgs.capnp.h create mode 100644 msg/src/fairomsg/cpp/trajectory_msgs.capnp.c++ create mode 100644 msg/src/fairomsg/cpp/trajectory_msgs.capnp.h create mode 100644 msg/src/fairomsg/cpp/visualization_msgs.capnp.c++ create mode 100644 msg/src/fairomsg/cpp/visualization_msgs.capnp.h create mode 100644 msg/src/fairomsg/def/actionlib_msgs.capnp create mode 100644 msg/src/fairomsg/def/diagnostic_msgs.capnp create mode 100644 msg/src/fairomsg/def/geometry_msgs.capnp create mode 100644 msg/src/fairomsg/def/nav_msgs.capnp create mode 100644 msg/src/fairomsg/def/sensor_msgs.capnp create mode 100644 msg/src/fairomsg/def/shape_msgs.capnp create mode 100644 msg/src/fairomsg/def/std_msgs.capnp create mode 100644 msg/src/fairomsg/def/stereo_msgs.capnp create mode 100644 msg/src/fairomsg/def/trajectory_msgs.capnp create mode 100644 msg/src/fairomsg/def/visualization_msgs.capnp create mode 100644 msg/src/fairomsg/serdes.py create mode 100644 msg/tests/test_fairomsg.py diff --git a/.circleci/config.yml b/.circleci/config.yml index 411a2448b1..8e3cba83fe 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -359,6 +359,13 @@ jobs: - run: name: Run PyTest command: pytest -s -vvv ./mrp + fairomsg: + docker: + - image: cimg/python:3.8 + steps: + - checkout + - run: pip install ./fairomsg + - run: pip install pytest && pytest fairomsg/tests update-docs: docker: - image: cimg/node:current diff --git a/msg/.gitignore b/msg/.gitignore new file mode 100644 index 0000000000..68bc17f9ff --- /dev/null +++ b/msg/.gitignore @@ -0,0 +1,160 @@ +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +*$py.class + +# C extensions +*.so + +# Distribution / packaging +.Python +build/ +develop-eggs/ +dist/ +downloads/ +eggs/ +.eggs/ +lib/ +lib64/ +parts/ +sdist/ +var/ +wheels/ +share/python-wheels/ +*.egg-info/ +.installed.cfg +*.egg +MANIFEST + +# PyInstaller +# Usually these files are written by a python script from a template +# before PyInstaller builds the exe, so as to inject date/other infos into it. +*.manifest +*.spec + +# Installer logs +pip-log.txt +pip-delete-this-directory.txt + +# Unit test / coverage reports +htmlcov/ +.tox/ +.nox/ +.coverage +.coverage.* +.cache +nosetests.xml +coverage.xml +*.cover +*.py,cover +.hypothesis/ +.pytest_cache/ +cover/ + +# Translations +*.mo +*.pot + +# Django stuff: +*.log +local_settings.py +db.sqlite3 +db.sqlite3-journal + +# Flask stuff: +instance/ +.webassets-cache + +# Scrapy stuff: +.scrapy + +# Sphinx documentation +docs/_build/ + +# PyBuilder +.pybuilder/ +target/ + +# Jupyter Notebook +.ipynb_checkpoints + +# IPython +profile_default/ +ipython_config.py + +# pyenv +# For a library or package, you might want to ignore these files since the code is +# intended to run in multiple environments; otherwise, check them in: +# .python-version + +# pipenv +# According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control. +# However, in case of collaboration, if having platform-specific dependencies or dependencies +# having no cross-platform support, pipenv may install dependencies that don't work, or not +# install all needed dependencies. +#Pipfile.lock + +# poetry +# Similar to Pipfile.lock, it is generally recommended to include poetry.lock in version control. +# This is especially recommended for binary packages to ensure reproducibility, and is more +# commonly ignored for libraries. +# https://python-poetry.org/docs/basic-usage/#commit-your-poetrylock-file-to-version-control +#poetry.lock + +# pdm +# Similar to Pipfile.lock, it is generally recommended to include pdm.lock in version control. +#pdm.lock +# pdm stores project-wide configurations in .pdm.toml, but it is recommended to not include it +# in version control. +# https://pdm.fming.dev/#use-with-ide +.pdm.toml + +# PEP 582; used by e.g. github.com/David-OConnor/pyflow and github.com/pdm-project/pdm +__pypackages__/ + +# Celery stuff +celerybeat-schedule +celerybeat.pid + +# SageMath parsed files +*.sage.py + +# Environments +.env +.venv +env/ +venv/ +ENV/ +env.bak/ +venv.bak/ + +# Spyder project settings +.spyderproject +.spyproject + +# Rope project settings +.ropeproject + +# mkdocs documentation +/site + +# mypy +.mypy_cache/ +.dmypy.json +dmypy.json + +# Pyre type checker +.pyre/ + +# pytype static type analyzer +.pytype/ + +# Cython debug symbols +cython_debug/ + +# PyCharm +# JetBrains specific template is maintained in a separate JetBrains.gitignore that can +# be found at https://github.com/github/gitignore/blob/main/Global/JetBrains.gitignore +# and can be added to the global gitignore or merged into this file. For a more nuclear +# option (not recommended) you can uncomment the following to ignore the entire idea folder. +#.idea/ diff --git a/msg/MANIFEST.in b/msg/MANIFEST.in new file mode 100644 index 0000000000..2b652c73fb --- /dev/null +++ b/msg/MANIFEST.in @@ -0,0 +1,2 @@ +include src/fairomsg/cpp/* +include src/fairomsg/def/* \ No newline at end of file diff --git a/msg/README.md b/msg/README.md new file mode 100644 index 0000000000..5399ee1d5d --- /dev/null +++ b/msg/README.md @@ -0,0 +1,18 @@ +# fairomsg + +Cap'n Proto message definitions, auto-generated from rosmsg. + +## Install + +```bash +pip install git+https://github.com/facebookresearch/fairo.git@main#subdirectory=msg +``` + +## Build + +Add ROS msg packages to the Conda environment as necessary in [msetup.py](msetup.py) by appending to `ros_msg_packages`. Then, + +```bash +pip install mrp +mrp up +``` diff --git a/msg/msetup.py b/msg/msetup.py new file mode 100644 index 0000000000..fafbb1307e --- /dev/null +++ b/msg/msetup.py @@ -0,0 +1,22 @@ +import mrp + + +ros_msg_packages = [ + "ros-noetic-std-msgs", + "ros-noetic-common-msgs", +] + +mrp.process( + name="gen", + runtime=mrp.Conda( + channels=["conda-forge", "robostack"], + dependencies=[ + "python=3.8", + "capnproto", + ] + + ros_msg_packages, + run_command=["python", "scripts/gen.py"], + ), +) + +mrp.main() diff --git a/msg/scripts/gen.py b/msg/scripts/gen.py new file mode 100644 index 0000000000..2d811fda93 --- /dev/null +++ b/msg/scripts/gen.py @@ -0,0 +1,146 @@ +import dataclasses +import os +import glob +import re +import subprocess + + +@dataclasses.dataclass +class RosMsgFile: + path: str + namespace: str + name: str + + +def to_camel_case(token): + return token[0].lower() + token.replace("_", " ").title().replace(" ", "")[1:] + + +def rosmsg_files(): + paths = glob.glob(f"{os.environ['CONDA_PREFIX']}/share/*_msgs/msg/*.msg") + for path in paths: + match = re.match(".*/share/(.*)_msgs/msg/(.*).msg", path) + namespace, name = match.groups() + yield RosMsgFile(path, namespace, name) + + +def rosfile2capstruct(rosmsg_file): + special_case = { + ("std", "Time"): ( + set(), + [ + " sec @0 :UInt32;", + " nsec @1 :UInt32;", + ], + ), + ("std", "Duration"): ( + set(), + [ + " sec @0 :Int32;", + " nsec @1 :Int32;", + ], + ), + } + if (rosmsg_file.namespace, rosmsg_file.name) in special_case: + return special_case[(rosmsg_file.namespace, rosmsg_file.name)] + + primitive_type_map = { + "bool": "Bool", + "byte": "UInt8", + "char": "Int8", + "uint8": "UInt8", + "uint16": "UInt16", + "uint32": "UInt32", + "uint64": "UInt64", + "int8": "Int8", + "int16": "Int16", + "int32": "Int32", + "int64": "Int64", + "float32": "Float32", + "float64": "Float64", + "string": "Text", + "time": "std_msgs/Time", + "duration": "std_msgs/Duration", + } + + if rosmsg_file.namespace == "std" and rosmsg_file.name in primitive_type_map.values(): + return None + + import_set = set() + struct_fields = [] + + field_id = 0 + for line in open(rosmsg_file.path): + if "#" in line: + line = line.split("#")[0] + + line = line.strip() + if not line: + continue + + if match := re.fullmatch("([\w//]+)(\[\d*\])?\W+(\w+)", line): + field_type, is_arr, field_name = match.groups() + field_name = to_camel_case(field_name) + + field_type = primitive_type_map.get(field_type, field_type) + + if "/" in field_type: + namespace, field_type = field_type.split("/") + if namespace != f"{rosmsg_file.namespace}_msgs": + import_set.add( + f'using {field_type} = import "{namespace}.capnp".{field_type};' + ) + + if field_type == "Header" and rosmsg_file.namespace != "std": + import_set.add('using Header = import "std_msgs.capnp".Header;') + + if is_arr: + field_type = f"List({field_type})" + + if field_type in ["List(UInt8)", "List(Int8)"]: + field_type = "Data" + + struct_fields.append(f" {field_name} @{field_id} :{field_type};") + field_id += 1 + elif match := re.fullmatch("(\w+)\W+(\w+)\W*=\W*(\w+)", line): + const_type, const_name, const_value = match.groups() + + const_type = primitive_type_map.get(const_type, const_type) + const_name = to_camel_case("k_" + const_name) + + struct_fields.append(f" const {const_name} :{const_type} = {const_value};") + else: + assert False + + return import_set, struct_fields + + +new_files = {} +for i, rosmsg_file in enumerate(rosmsg_files()): + if rosmsg_file.namespace not in new_files: + new_files[rosmsg_file.namespace] = {"import_set": set(), "content": []} + capstruct = rosfile2capstruct(rosmsg_file) + if not capstruct: + continue + import_set, struct_fields = capstruct + file = new_files[rosmsg_file.namespace] + file["import_set"] |= import_set + file["content"].append(f"struct {rosmsg_file.name} {{") + file["content"].extend(struct_fields) + file["content"].append("}") + + +out_dir = "src/fairomsg/def" +os.makedirs(out_dir, exist_ok=True) +for filename, info in new_files.items(): + print(filename) + with open(os.path.join(out_dir, f"{filename}_msgs.capnp"), "w") as out: + print(subprocess.check_output(["capnp", "id"]).decode().strip() + ";", file=out) + print('using Cxx = import "/capnp/c++.capnp";', file=out) + print(f'$Cxx.namespace("mrp::{filename}");', file=out) + + for import_item in sorted(info["import_set"]): + print(import_item, file=out) + + for line in info["content"]: + print(line, file=out) diff --git a/msg/setup.py b/msg/setup.py new file mode 100644 index 0000000000..5f0b973ac6 --- /dev/null +++ b/msg/setup.py @@ -0,0 +1,23 @@ +from setuptools import setup, find_packages + + +__author__ = "Leonid Shamis" +__copyright__ = "2022, Meta" + + +install_requires = [ + "pycapnp", + "mrp", +] + + +setup( + name="fairomsg", + author="Leonid Shamis", + author_email="lshamis@fb.com", + version="0.1", + packages=find_packages(where="src"), + package_dir={"": "src"}, + install_requires=install_requires, + include_package_data=True, +) diff --git a/msg/src/fairomsg/__init__.py b/msg/src/fairomsg/__init__.py new file mode 100644 index 0000000000..bfdc196aa3 --- /dev/null +++ b/msg/src/fairomsg/__init__.py @@ -0,0 +1,2 @@ +from .serdes import get_msgs +from .serdes import get_pkgs \ No newline at end of file diff --git a/msg/src/fairomsg/cpp/actionlib_msgs.capnp.c++ b/msg/src/fairomsg/cpp/actionlib_msgs.capnp.c++ new file mode 100644 index 0000000000..321fc0e848 --- /dev/null +++ b/msg/src/fairomsg/cpp/actionlib_msgs.capnp.c++ @@ -0,0 +1,671 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: actionlib_msgs.capnp + +#include "actionlib_msgs.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<48> b_cf7675d72191adb9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 185, 173, 145, 33, 215, 117, 118, 207, + 25, 0, 0, 0, 1, 0, 0, 0, + 15, 95, 50, 123, 125, 197, 38, 137, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 97, 99, 116, 105, + 111, 110, 108, 105, 98, 95, 109, 115, + 103, 115, 46, 99, 97, 112, 110, 112, + 58, 71, 111, 97, 108, 73, 68, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 115, 116, 97, 109, 112, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 79, 12, 85, 207, 4, 92, 190, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 100, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cf7675d72191adb9 = b_cf7675d72191adb9.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_cf7675d72191adb9[] = { + &s_ebbe5c04cf550c4f, +}; +static const uint16_t m_cf7675d72191adb9[] = {1, 0}; +static const uint16_t i_cf7675d72191adb9[] = {0, 1}; +const ::capnp::_::RawSchema s_cf7675d72191adb9 = { + 0xcf7675d72191adb9, b_cf7675d72191adb9.words, 48, d_cf7675d72191adb9, m_cf7675d72191adb9, + 1, 2, i_cf7675d72191adb9, nullptr, nullptr, { &s_cf7675d72191adb9, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<102> b_bf587c1bf845ce13 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 25, 0, 0, 0, 1, 0, 1, 0, + 15, 95, 50, 123, 125, 197, 38, 137, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 167, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 97, 99, 116, 105, + 111, 110, 108, 105, 98, 95, 109, 115, + 103, 115, 46, 99, 97, 112, 110, 112, + 58, 71, 111, 97, 108, 83, 116, 97, + 116, 117, 115, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 1, 0, 1, 0, + 97, 133, 66, 28, 95, 227, 167, 168, + 73, 0, 0, 0, 74, 0, 0, 0, + 57, 166, 199, 91, 254, 77, 227, 232, + 73, 0, 0, 0, 66, 0, 0, 0, + 43, 233, 96, 141, 231, 166, 99, 230, + 69, 0, 0, 0, 90, 0, 0, 0, + 231, 160, 0, 111, 235, 127, 126, 148, + 69, 0, 0, 0, 90, 0, 0, 0, + 151, 115, 219, 93, 85, 182, 182, 174, + 69, 0, 0, 0, 74, 0, 0, 0, + 64, 205, 38, 196, 203, 89, 163, 191, + 69, 0, 0, 0, 82, 0, 0, 0, + 102, 56, 50, 97, 138, 16, 52, 182, + 69, 0, 0, 0, 98, 0, 0, 0, + 35, 115, 4, 94, 44, 93, 232, 155, + 69, 0, 0, 0, 90, 0, 0, 0, + 11, 140, 20, 80, 25, 227, 209, 255, + 69, 0, 0, 0, 82, 0, 0, 0, + 65, 21, 76, 64, 152, 144, 227, 239, + 69, 0, 0, 0, 50, 0, 0, 0, + 107, 80, 101, 110, 100, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 65, 99, 116, 105, 118, 101, 0, + 107, 80, 114, 101, 101, 109, 112, 116, + 101, 100, 0, 0, 0, 0, 0, 0, + 107, 83, 117, 99, 99, 101, 101, 100, + 101, 100, 0, 0, 0, 0, 0, 0, + 107, 65, 98, 111, 114, 116, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 82, 101, 106, 101, 99, 116, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 107, 80, 114, 101, 101, 109, 112, 116, + 105, 110, 103, 0, 0, 0, 0, 0, + 107, 82, 101, 99, 97, 108, 108, 105, + 110, 103, 0, 0, 0, 0, 0, 0, + 107, 82, 101, 99, 97, 108, 108, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 107, 76, 111, 115, 116, 0, 0, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 103, 111, 97, 108, 73, 100, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 185, 173, 145, 33, 215, 117, 118, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 120, 116, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bf587c1bf845ce13 = b_bf587c1bf845ce13.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_bf587c1bf845ce13[] = { + &s_cf7675d72191adb9, +}; +static const uint16_t m_bf587c1bf845ce13[] = {0, 1, 2}; +static const uint16_t i_bf587c1bf845ce13[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_bf587c1bf845ce13 = { + 0xbf587c1bf845ce13, b_bf587c1bf845ce13.words, 102, d_bf587c1bf845ce13, m_bf587c1bf845ce13, + 1, 3, i_bf587c1bf845ce13, nullptr, nullptr, { &s_bf587c1bf845ce13, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_a8a7e35f1c428561 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 97, 133, 66, 28, 95, 227, 167, 168, + 36, 0, 0, 0, 4, 0, 0, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 106, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 97, 99, 116, 105, + 111, 110, 108, 105, 98, 95, 109, 115, + 103, 115, 46, 99, 97, 112, 110, 112, + 58, 71, 111, 97, 108, 83, 116, 97, + 116, 117, 115, 46, 107, 80, 101, 110, + 100, 105, 110, 103, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a8a7e35f1c428561 = b_a8a7e35f1c428561.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_a8a7e35f1c428561 = { + 0xa8a7e35f1c428561, b_a8a7e35f1c428561.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_a8a7e35f1c428561, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_e8e34dfe5bc7a639 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 57, 166, 199, 91, 254, 77, 227, 232, + 36, 0, 0, 0, 4, 0, 0, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 98, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 97, 99, 116, 105, + 111, 110, 108, 105, 98, 95, 109, 115, + 103, 115, 46, 99, 97, 112, 110, 112, + 58, 71, 111, 97, 108, 83, 116, 97, + 116, 117, 115, 46, 107, 65, 99, 116, + 105, 118, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e8e34dfe5bc7a639 = b_e8e34dfe5bc7a639.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_e8e34dfe5bc7a639 = { + 0xe8e34dfe5bc7a639, b_e8e34dfe5bc7a639.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_e8e34dfe5bc7a639, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_e663a6e78d60e92b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 43, 233, 96, 141, 231, 166, 99, 230, + 36, 0, 0, 0, 4, 0, 0, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 122, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 97, 99, 116, 105, + 111, 110, 108, 105, 98, 95, 109, 115, + 103, 115, 46, 99, 97, 112, 110, 112, + 58, 71, 111, 97, 108, 83, 116, 97, + 116, 117, 115, 46, 107, 80, 114, 101, + 101, 109, 112, 116, 101, 100, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e663a6e78d60e92b = b_e663a6e78d60e92b.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_e663a6e78d60e92b = { + 0xe663a6e78d60e92b, b_e663a6e78d60e92b.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_e663a6e78d60e92b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_947e7feb6f00a0e7 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 231, 160, 0, 111, 235, 127, 126, 148, + 36, 0, 0, 0, 4, 0, 0, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 122, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 97, 99, 116, 105, + 111, 110, 108, 105, 98, 95, 109, 115, + 103, 115, 46, 99, 97, 112, 110, 112, + 58, 71, 111, 97, 108, 83, 116, 97, + 116, 117, 115, 46, 107, 83, 117, 99, + 99, 101, 101, 100, 101, 100, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_947e7feb6f00a0e7 = b_947e7feb6f00a0e7.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_947e7feb6f00a0e7 = { + 0x947e7feb6f00a0e7, b_947e7feb6f00a0e7.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_947e7feb6f00a0e7, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_aeb6b6555ddb7397 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 151, 115, 219, 93, 85, 182, 182, 174, + 36, 0, 0, 0, 4, 0, 0, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 106, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 97, 99, 116, 105, + 111, 110, 108, 105, 98, 95, 109, 115, + 103, 115, 46, 99, 97, 112, 110, 112, + 58, 71, 111, 97, 108, 83, 116, 97, + 116, 117, 115, 46, 107, 65, 98, 111, + 114, 116, 101, 100, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 4, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_aeb6b6555ddb7397 = b_aeb6b6555ddb7397.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_aeb6b6555ddb7397 = { + 0xaeb6b6555ddb7397, b_aeb6b6555ddb7397.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_aeb6b6555ddb7397, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_bfa359cbc426cd40 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 64, 205, 38, 196, 203, 89, 163, 191, + 36, 0, 0, 0, 4, 0, 0, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 114, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 97, 99, 116, 105, + 111, 110, 108, 105, 98, 95, 109, 115, + 103, 115, 46, 99, 97, 112, 110, 112, + 58, 71, 111, 97, 108, 83, 116, 97, + 116, 117, 115, 46, 107, 82, 101, 106, + 101, 99, 116, 101, 100, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 5, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bfa359cbc426cd40 = b_bfa359cbc426cd40.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_bfa359cbc426cd40 = { + 0xbfa359cbc426cd40, b_bfa359cbc426cd40.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_bfa359cbc426cd40, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_b634108a61323866 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 102, 56, 50, 97, 138, 16, 52, 182, + 36, 0, 0, 0, 4, 0, 0, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 130, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 97, 99, 116, 105, + 111, 110, 108, 105, 98, 95, 109, 115, + 103, 115, 46, 99, 97, 112, 110, 112, + 58, 71, 111, 97, 108, 83, 116, 97, + 116, 117, 115, 46, 107, 80, 114, 101, + 101, 109, 112, 116, 105, 110, 103, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 6, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b634108a61323866 = b_b634108a61323866.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_b634108a61323866 = { + 0xb634108a61323866, b_b634108a61323866.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_b634108a61323866, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_9be85d2c5e047323 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 35, 115, 4, 94, 44, 93, 232, 155, + 36, 0, 0, 0, 4, 0, 0, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 122, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 97, 99, 116, 105, + 111, 110, 108, 105, 98, 95, 109, 115, + 103, 115, 46, 99, 97, 112, 110, 112, + 58, 71, 111, 97, 108, 83, 116, 97, + 116, 117, 115, 46, 107, 82, 101, 99, + 97, 108, 108, 105, 110, 103, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9be85d2c5e047323 = b_9be85d2c5e047323.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_9be85d2c5e047323 = { + 0x9be85d2c5e047323, b_9be85d2c5e047323.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_9be85d2c5e047323, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_ffd1e31950148c0b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 11, 140, 20, 80, 25, 227, 209, 255, + 36, 0, 0, 0, 4, 0, 0, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 114, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 97, 99, 116, 105, + 111, 110, 108, 105, 98, 95, 109, 115, + 103, 115, 46, 99, 97, 112, 110, 112, + 58, 71, 111, 97, 108, 83, 116, 97, + 116, 117, 115, 46, 107, 82, 101, 99, + 97, 108, 108, 101, 100, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 8, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ffd1e31950148c0b = b_ffd1e31950148c0b.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_ffd1e31950148c0b = { + 0xffd1e31950148c0b, b_ffd1e31950148c0b.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_ffd1e31950148c0b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_efe39098404c1541 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 65, 21, 76, 64, 152, 144, 227, 239, + 36, 0, 0, 0, 4, 0, 0, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 97, 99, 116, 105, + 111, 110, 108, 105, 98, 95, 109, 115, + 103, 115, 46, 99, 97, 112, 110, 112, + 58, 71, 111, 97, 108, 83, 116, 97, + 116, 117, 115, 46, 107, 76, 111, 115, + 116, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 9, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_efe39098404c1541 = b_efe39098404c1541.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_efe39098404c1541 = { + 0xefe39098404c1541, b_efe39098404c1541.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_efe39098404c1541, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<55> b_b688d53fabdc6ee9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 233, 110, 220, 171, 63, 213, 136, 182, + 25, 0, 0, 0, 1, 0, 0, 0, + 15, 95, 50, 123, 125, 197, 38, 137, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 97, 99, 116, 105, + 111, 110, 108, 105, 98, 95, 109, 115, + 103, 115, 46, 99, 97, 112, 110, 112, + 58, 71, 111, 97, 108, 83, 116, 97, + 116, 117, 115, 65, 114, 114, 97, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 72, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 76, 105, + 115, 116, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b688d53fabdc6ee9 = b_b688d53fabdc6ee9.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_b688d53fabdc6ee9[] = { + &s_bf587c1bf845ce13, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_b688d53fabdc6ee9[] = {0, 1}; +static const uint16_t i_b688d53fabdc6ee9[] = {0, 1}; +const ::capnp::_::RawSchema s_b688d53fabdc6ee9 = { + 0xb688d53fabdc6ee9, b_b688d53fabdc6ee9.words, 55, d_b688d53fabdc6ee9, m_b688d53fabdc6ee9, + 2, 2, i_b688d53fabdc6ee9, nullptr, nullptr, { &s_b688d53fabdc6ee9, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace mrp { +namespace actionlib { + +// GoalID +constexpr uint16_t GoalID::_capnpPrivate::dataWordSize; +constexpr uint16_t GoalID::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind GoalID::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GoalID::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// GoalStatus +constexpr uint16_t GoalStatus::_capnpPrivate::dataWordSize; +constexpr uint16_t GoalStatus::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind GoalStatus::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GoalStatus::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t GoalStatus::K_PENDING; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t GoalStatus::K_ACTIVE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t GoalStatus::K_PREEMPTED; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t GoalStatus::K_SUCCEEDED; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t GoalStatus::K_ABORTED; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t GoalStatus::K_REJECTED; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t GoalStatus::K_PREEMPTING; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t GoalStatus::K_RECALLING; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t GoalStatus::K_RECALLED; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t GoalStatus::K_LOST; +#endif +// GoalStatusArray +constexpr uint16_t GoalStatusArray::_capnpPrivate::dataWordSize; +constexpr uint16_t GoalStatusArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind GoalStatusArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GoalStatusArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + + +} // namespace +} // namespace + diff --git a/msg/src/fairomsg/cpp/actionlib_msgs.capnp.h b/msg/src/fairomsg/cpp/actionlib_msgs.capnp.h new file mode 100644 index 0000000000..77286b7e3a --- /dev/null +++ b/msg/src/fairomsg/cpp/actionlib_msgs.capnp.h @@ -0,0 +1,617 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: actionlib_msgs.capnp + +#pragma once + +#include +#include + +#if CAPNP_VERSION != 9001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + +#include "std_msgs.capnp.h" + +CAPNP_BEGIN_HEADER + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(cf7675d72191adb9); +CAPNP_DECLARE_SCHEMA(bf587c1bf845ce13); +CAPNP_DECLARE_SCHEMA(a8a7e35f1c428561); +CAPNP_DECLARE_SCHEMA(e8e34dfe5bc7a639); +CAPNP_DECLARE_SCHEMA(e663a6e78d60e92b); +CAPNP_DECLARE_SCHEMA(947e7feb6f00a0e7); +CAPNP_DECLARE_SCHEMA(aeb6b6555ddb7397); +CAPNP_DECLARE_SCHEMA(bfa359cbc426cd40); +CAPNP_DECLARE_SCHEMA(b634108a61323866); +CAPNP_DECLARE_SCHEMA(9be85d2c5e047323); +CAPNP_DECLARE_SCHEMA(ffd1e31950148c0b); +CAPNP_DECLARE_SCHEMA(efe39098404c1541); +CAPNP_DECLARE_SCHEMA(b688d53fabdc6ee9); + +} // namespace schemas +} // namespace capnp + +namespace mrp { +namespace actionlib { + +struct GoalID { + GoalID() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(cf7675d72191adb9, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct GoalStatus { + GoalStatus() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_PENDING = 0u; + static constexpr ::uint8_t K_ACTIVE = 1u; + static constexpr ::uint8_t K_PREEMPTED = 2u; + static constexpr ::uint8_t K_SUCCEEDED = 3u; + static constexpr ::uint8_t K_ABORTED = 4u; + static constexpr ::uint8_t K_REJECTED = 5u; + static constexpr ::uint8_t K_PREEMPTING = 6u; + static constexpr ::uint8_t K_RECALLING = 7u; + static constexpr ::uint8_t K_RECALLED = 8u; + static constexpr ::uint8_t K_LOST = 9u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bf587c1bf845ce13, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct GoalStatusArray { + GoalStatusArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b688d53fabdc6ee9, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class GoalID::Reader { +public: + typedef GoalID Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasStamp() const; + inline ::mrp::std::Time::Reader getStamp() const; + + inline bool hasId() const; + inline ::capnp::Text::Reader getId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class GoalID::Builder { +public: + typedef GoalID Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasStamp(); + inline ::mrp::std::Time::Builder getStamp(); + inline void setStamp( ::mrp::std::Time::Reader value); + inline ::mrp::std::Time::Builder initStamp(); + inline void adoptStamp(::capnp::Orphan< ::mrp::std::Time>&& value); + inline ::capnp::Orphan< ::mrp::std::Time> disownStamp(); + + inline bool hasId(); + inline ::capnp::Text::Builder getId(); + inline void setId( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initId(unsigned int size); + inline void adoptId(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownId(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class GoalID::Pipeline { +public: + typedef GoalID Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Time::Pipeline getStamp(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class GoalStatus::Reader { +public: + typedef GoalStatus Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasGoalId() const; + inline ::mrp::actionlib::GoalID::Reader getGoalId() const; + + inline ::uint8_t getStatus() const; + + inline bool hasText() const; + inline ::capnp::Text::Reader getText() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class GoalStatus::Builder { +public: + typedef GoalStatus Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasGoalId(); + inline ::mrp::actionlib::GoalID::Builder getGoalId(); + inline void setGoalId( ::mrp::actionlib::GoalID::Reader value); + inline ::mrp::actionlib::GoalID::Builder initGoalId(); + inline void adoptGoalId(::capnp::Orphan< ::mrp::actionlib::GoalID>&& value); + inline ::capnp::Orphan< ::mrp::actionlib::GoalID> disownGoalId(); + + inline ::uint8_t getStatus(); + inline void setStatus( ::uint8_t value); + + inline bool hasText(); + inline ::capnp::Text::Builder getText(); + inline void setText( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initText(unsigned int size); + inline void adoptText(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownText(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class GoalStatus::Pipeline { +public: + typedef GoalStatus Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::actionlib::GoalID::Pipeline getGoalId(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class GoalStatusArray::Reader { +public: + typedef GoalStatusArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasStatusList() const; + inline ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>::Reader getStatusList() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class GoalStatusArray::Builder { +public: + typedef GoalStatusArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasStatusList(); + inline ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>::Builder getStatusList(); + inline void setStatusList( ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>::Builder initStatusList(unsigned int size); + inline void adoptStatusList(::capnp::Orphan< ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>> disownStatusList(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class GoalStatusArray::Pipeline { +public: + typedef GoalStatusArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline bool GoalID::Reader::hasStamp() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool GoalID::Builder::hasStamp() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Time::Reader GoalID::Reader::getStamp() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Time::Builder GoalID::Builder::getStamp() { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Time::Pipeline GoalID::Pipeline::getStamp() { + return ::mrp::std::Time::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void GoalID::Builder::setStamp( ::mrp::std::Time::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Time>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Time::Builder GoalID::Builder::initStamp() { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void GoalID::Builder::adoptStamp( + ::capnp::Orphan< ::mrp::std::Time>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Time>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Time> GoalID::Builder::disownStamp() { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool GoalID::Reader::hasId() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool GoalID::Builder::hasId() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader GoalID::Reader::getId() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder GoalID::Builder::getId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void GoalID::Builder::setId( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder GoalID::Builder::initId(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void GoalID::Builder::adoptId( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> GoalID::Builder::disownId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool GoalStatus::Reader::hasGoalId() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool GoalStatus::Builder::hasGoalId() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::actionlib::GoalID::Reader GoalStatus::Reader::getGoalId() const { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalID>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::actionlib::GoalID::Builder GoalStatus::Builder::getGoalId() { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalID>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::actionlib::GoalID::Pipeline GoalStatus::Pipeline::getGoalId() { + return ::mrp::actionlib::GoalID::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void GoalStatus::Builder::setGoalId( ::mrp::actionlib::GoalID::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalID>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::actionlib::GoalID::Builder GoalStatus::Builder::initGoalId() { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalID>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void GoalStatus::Builder::adoptGoalId( + ::capnp::Orphan< ::mrp::actionlib::GoalID>&& value) { + ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalID>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::actionlib::GoalID> GoalStatus::Builder::disownGoalId() { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalID>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint8_t GoalStatus::Reader::getStatus() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t GoalStatus::Builder::getStatus() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void GoalStatus::Builder::setStatus( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool GoalStatus::Reader::hasText() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool GoalStatus::Builder::hasText() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader GoalStatus::Reader::getText() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder GoalStatus::Builder::getText() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void GoalStatus::Builder::setText( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder GoalStatus::Builder::initText(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void GoalStatus::Builder::adoptText( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> GoalStatus::Builder::disownText() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool GoalStatusArray::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool GoalStatusArray::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader GoalStatusArray::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder GoalStatusArray::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline GoalStatusArray::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void GoalStatusArray::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder GoalStatusArray::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void GoalStatusArray::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> GoalStatusArray::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool GoalStatusArray::Reader::hasStatusList() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool GoalStatusArray::Builder::hasStatusList() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>::Reader GoalStatusArray::Reader::getStatusList() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>::Builder GoalStatusArray::Builder::getStatusList() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void GoalStatusArray::Builder::setStatusList( ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>::Builder GoalStatusArray::Builder::initStatusList(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void GoalStatusArray::Builder::adoptStatusList( + ::capnp::Orphan< ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>> GoalStatusArray::Builder::disownStatusList() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::actionlib::GoalStatus, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +} // namespace +} // namespace + +CAPNP_END_HEADER + diff --git a/msg/src/fairomsg/cpp/diagnostic_msgs.capnp.c++ b/msg/src/fairomsg/cpp/diagnostic_msgs.capnp.c++ new file mode 100644 index 0000000000..ae15a169ec --- /dev/null +++ b/msg/src/fairomsg/cpp/diagnostic_msgs.capnp.c++ @@ -0,0 +1,453 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: diagnostic_msgs.capnp + +#include "diagnostic_msgs.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<54> b_adaa5408704b2852 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 82, 40, 75, 112, 8, 84, 170, 173, + 26, 0, 0, 0, 1, 0, 0, 0, + 136, 226, 197, 141, 100, 237, 154, 195, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 100, 105, 97, 103, + 110, 111, 115, 116, 105, 99, 95, 109, + 115, 103, 115, 46, 99, 97, 112, 110, + 112, 58, 68, 105, 97, 103, 110, 111, + 115, 116, 105, 99, 65, 114, 114, 97, + 121, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 211, 86, 20, 239, 14, 189, 126, 148, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_adaa5408704b2852 = b_adaa5408704b2852.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_adaa5408704b2852[] = { + &s_947ebd0eef1456d3, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_adaa5408704b2852[] = {0, 1}; +static const uint16_t i_adaa5408704b2852[] = {0, 1}; +const ::capnp::_::RawSchema s_adaa5408704b2852 = { + 0xadaa5408704b2852, b_adaa5408704b2852.words, 54, d_adaa5408704b2852, m_adaa5408704b2852, + 2, 2, i_adaa5408704b2852, nullptr, nullptr, { &s_adaa5408704b2852, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<112> b_947ebd0eef1456d3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 211, 86, 20, 239, 14, 189, 126, 148, + 26, 0, 0, 0, 1, 0, 1, 0, + 136, 226, 197, 141, 100, 237, 154, 195, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 1, 0, 0, + 41, 0, 0, 0, 71, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 100, 105, 97, 103, + 110, 111, 115, 116, 105, 99, 95, 109, + 115, 103, 115, 46, 99, 97, 112, 110, + 112, 58, 68, 105, 97, 103, 110, 111, + 115, 116, 105, 99, 83, 116, 97, 116, + 117, 115, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 1, 0, 1, 0, + 86, 63, 125, 140, 234, 72, 150, 209, + 25, 0, 0, 0, 34, 0, 0, 0, + 226, 184, 28, 214, 193, 74, 177, 163, + 21, 0, 0, 0, 50, 0, 0, 0, + 87, 122, 242, 90, 103, 138, 88, 237, + 17, 0, 0, 0, 58, 0, 0, 0, + 134, 29, 77, 132, 21, 157, 28, 199, + 13, 0, 0, 0, 58, 0, 0, 0, + 107, 79, 107, 0, 0, 0, 0, 0, + 107, 87, 97, 114, 110, 0, 0, 0, + 107, 69, 114, 114, 111, 114, 0, 0, + 107, 83, 116, 97, 108, 101, 0, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 0, 0, 0, 3, 0, 1, 0, + 168, 0, 0, 0, 2, 0, 1, 0, + 108, 101, 118, 101, 108, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 115, 115, 97, 103, 101, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 114, 100, 119, 97, 114, 101, + 73, 100, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 108, 117, 101, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 160, 49, 33, 3, 43, 39, 39, 215, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_947ebd0eef1456d3 = b_947ebd0eef1456d3.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_947ebd0eef1456d3[] = { + &s_d727272b032131a0, +}; +static const uint16_t m_947ebd0eef1456d3[] = {3, 0, 2, 1, 4}; +static const uint16_t i_947ebd0eef1456d3[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_947ebd0eef1456d3 = { + 0x947ebd0eef1456d3, b_947ebd0eef1456d3.words, 112, d_947ebd0eef1456d3, m_947ebd0eef1456d3, + 1, 5, i_947ebd0eef1456d3, nullptr, nullptr, { &s_947ebd0eef1456d3, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_d19648ea8c7d3f56 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 86, 63, 125, 140, 234, 72, 150, 209, + 43, 0, 0, 0, 4, 0, 0, 0, + 211, 86, 20, 239, 14, 189, 126, 148, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 122, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 100, 105, 97, 103, + 110, 111, 115, 116, 105, 99, 95, 109, + 115, 103, 115, 46, 99, 97, 112, 110, + 112, 58, 68, 105, 97, 103, 110, 111, + 115, 116, 105, 99, 83, 116, 97, 116, + 117, 115, 46, 107, 79, 107, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d19648ea8c7d3f56 = b_d19648ea8c7d3f56.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_d19648ea8c7d3f56 = { + 0xd19648ea8c7d3f56, b_d19648ea8c7d3f56.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_d19648ea8c7d3f56, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_a3b14ac1d61cb8e2 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 226, 184, 28, 214, 193, 74, 177, 163, + 43, 0, 0, 0, 4, 0, 0, 0, + 211, 86, 20, 239, 14, 189, 126, 148, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 138, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 100, 105, 97, 103, + 110, 111, 115, 116, 105, 99, 95, 109, + 115, 103, 115, 46, 99, 97, 112, 110, + 112, 58, 68, 105, 97, 103, 110, 111, + 115, 116, 105, 99, 83, 116, 97, 116, + 117, 115, 46, 107, 87, 97, 114, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a3b14ac1d61cb8e2 = b_a3b14ac1d61cb8e2.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_a3b14ac1d61cb8e2 = { + 0xa3b14ac1d61cb8e2, b_a3b14ac1d61cb8e2.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_a3b14ac1d61cb8e2, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_ed588a675af27a57 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 87, 122, 242, 90, 103, 138, 88, 237, + 43, 0, 0, 0, 4, 0, 0, 0, + 211, 86, 20, 239, 14, 189, 126, 148, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 100, 105, 97, 103, + 110, 111, 115, 116, 105, 99, 95, 109, + 115, 103, 115, 46, 99, 97, 112, 110, + 112, 58, 68, 105, 97, 103, 110, 111, + 115, 116, 105, 99, 83, 116, 97, 116, + 117, 115, 46, 107, 69, 114, 114, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ed588a675af27a57 = b_ed588a675af27a57.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_ed588a675af27a57 = { + 0xed588a675af27a57, b_ed588a675af27a57.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_ed588a675af27a57, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_c71c9d15844d1d86 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 134, 29, 77, 132, 21, 157, 28, 199, + 43, 0, 0, 0, 4, 0, 0, 0, + 211, 86, 20, 239, 14, 189, 126, 148, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 100, 105, 97, 103, + 110, 111, 115, 116, 105, 99, 95, 109, + 115, 103, 115, 46, 99, 97, 112, 110, + 112, 58, 68, 105, 97, 103, 110, 111, + 115, 116, 105, 99, 83, 116, 97, 116, + 117, 115, 46, 107, 83, 116, 97, 108, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c71c9d15844d1d86 = b_c71c9d15844d1d86.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c71c9d15844d1d86 = { + 0xc71c9d15844d1d86, b_c71c9d15844d1d86.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c71c9d15844d1d86, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_d727272b032131a0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 160, 49, 33, 3, 43, 39, 39, 215, + 26, 0, 0, 0, 1, 0, 0, 0, + 136, 226, 197, 141, 100, 237, 154, 195, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 100, 105, 97, 103, + 110, 111, 115, 116, 105, 99, 95, 109, + 115, 103, 115, 46, 99, 97, 112, 110, + 112, 58, 75, 101, 121, 86, 97, 108, + 117, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 107, 101, 121, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 108, 117, 101, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d727272b032131a0 = b_d727272b032131a0.words; +#if !CAPNP_LITE +static const uint16_t m_d727272b032131a0[] = {0, 1}; +static const uint16_t i_d727272b032131a0[] = {0, 1}; +const ::capnp::_::RawSchema s_d727272b032131a0 = { + 0xd727272b032131a0, b_d727272b032131a0.words, 49, nullptr, m_d727272b032131a0, + 0, 2, i_d727272b032131a0, nullptr, nullptr, { &s_d727272b032131a0, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace mrp { +namespace diagnostic { + +// DiagnosticArray +constexpr uint16_t DiagnosticArray::_capnpPrivate::dataWordSize; +constexpr uint16_t DiagnosticArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind DiagnosticArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* DiagnosticArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// DiagnosticStatus +constexpr uint16_t DiagnosticStatus::_capnpPrivate::dataWordSize; +constexpr uint16_t DiagnosticStatus::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind DiagnosticStatus::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* DiagnosticStatus::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t DiagnosticStatus::K_OK; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t DiagnosticStatus::K_WARN; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t DiagnosticStatus::K_ERROR; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t DiagnosticStatus::K_STALE; +#endif +// KeyValue +constexpr uint16_t KeyValue::_capnpPrivate::dataWordSize; +constexpr uint16_t KeyValue::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind KeyValue::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* KeyValue::_capnpPrivate::schema; +#endif // !CAPNP_LITE + + +} // namespace +} // namespace + diff --git a/msg/src/fairomsg/cpp/diagnostic_msgs.capnp.h b/msg/src/fairomsg/cpp/diagnostic_msgs.capnp.h new file mode 100644 index 0000000000..0a6e52e37f --- /dev/null +++ b/msg/src/fairomsg/cpp/diagnostic_msgs.capnp.h @@ -0,0 +1,681 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: diagnostic_msgs.capnp + +#pragma once + +#include +#include + +#if CAPNP_VERSION != 9001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + +#include "std_msgs.capnp.h" + +CAPNP_BEGIN_HEADER + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(adaa5408704b2852); +CAPNP_DECLARE_SCHEMA(947ebd0eef1456d3); +CAPNP_DECLARE_SCHEMA(d19648ea8c7d3f56); +CAPNP_DECLARE_SCHEMA(a3b14ac1d61cb8e2); +CAPNP_DECLARE_SCHEMA(ed588a675af27a57); +CAPNP_DECLARE_SCHEMA(c71c9d15844d1d86); +CAPNP_DECLARE_SCHEMA(d727272b032131a0); + +} // namespace schemas +} // namespace capnp + +namespace mrp { +namespace diagnostic { + +struct DiagnosticArray { + DiagnosticArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(adaa5408704b2852, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct DiagnosticStatus { + DiagnosticStatus() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_OK = 0u; + static constexpr ::uint8_t K_WARN = 1u; + static constexpr ::uint8_t K_ERROR = 2u; + static constexpr ::uint8_t K_STALE = 3u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(947ebd0eef1456d3, 1, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct KeyValue { + KeyValue() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d727272b032131a0, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class DiagnosticArray::Reader { +public: + typedef DiagnosticArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasStatus() const; + inline ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>::Reader getStatus() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class DiagnosticArray::Builder { +public: + typedef DiagnosticArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasStatus(); + inline ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>::Builder getStatus(); + inline void setStatus( ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>::Builder initStatus(unsigned int size); + inline void adoptStatus(::capnp::Orphan< ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>> disownStatus(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class DiagnosticArray::Pipeline { +public: + typedef DiagnosticArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class DiagnosticStatus::Reader { +public: + typedef DiagnosticStatus Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint8_t getLevel() const; + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline bool hasMessage() const; + inline ::capnp::Text::Reader getMessage() const; + + inline bool hasHardwareId() const; + inline ::capnp::Text::Reader getHardwareId() const; + + inline bool hasValues() const; + inline ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>::Reader getValues() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class DiagnosticStatus::Builder { +public: + typedef DiagnosticStatus Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint8_t getLevel(); + inline void setLevel( ::uint8_t value); + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline bool hasMessage(); + inline ::capnp::Text::Builder getMessage(); + inline void setMessage( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initMessage(unsigned int size); + inline void adoptMessage(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownMessage(); + + inline bool hasHardwareId(); + inline ::capnp::Text::Builder getHardwareId(); + inline void setHardwareId( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initHardwareId(unsigned int size); + inline void adoptHardwareId(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownHardwareId(); + + inline bool hasValues(); + inline ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>::Builder getValues(); + inline void setValues( ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>::Builder initValues(unsigned int size); + inline void adoptValues(::capnp::Orphan< ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>> disownValues(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class DiagnosticStatus::Pipeline { +public: + typedef DiagnosticStatus Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class KeyValue::Reader { +public: + typedef KeyValue Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasKey() const; + inline ::capnp::Text::Reader getKey() const; + + inline bool hasValue() const; + inline ::capnp::Text::Reader getValue() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class KeyValue::Builder { +public: + typedef KeyValue Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasKey(); + inline ::capnp::Text::Builder getKey(); + inline void setKey( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initKey(unsigned int size); + inline void adoptKey(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownKey(); + + inline bool hasValue(); + inline ::capnp::Text::Builder getValue(); + inline void setValue( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initValue(unsigned int size); + inline void adoptValue(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownValue(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class KeyValue::Pipeline { +public: + typedef KeyValue Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline bool DiagnosticArray::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool DiagnosticArray::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader DiagnosticArray::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder DiagnosticArray::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline DiagnosticArray::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void DiagnosticArray::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder DiagnosticArray::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void DiagnosticArray::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> DiagnosticArray::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool DiagnosticArray::Reader::hasStatus() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool DiagnosticArray::Builder::hasStatus() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>::Reader DiagnosticArray::Reader::getStatus() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>::Builder DiagnosticArray::Builder::getStatus() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void DiagnosticArray::Builder::setStatus( ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>::Builder DiagnosticArray::Builder::initStatus(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void DiagnosticArray::Builder::adoptStatus( + ::capnp::Orphan< ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>> DiagnosticArray::Builder::disownStatus() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::diagnostic::DiagnosticStatus, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::uint8_t DiagnosticStatus::Reader::getLevel() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t DiagnosticStatus::Builder::getLevel() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void DiagnosticStatus::Builder::setLevel( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool DiagnosticStatus::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool DiagnosticStatus::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader DiagnosticStatus::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder DiagnosticStatus::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void DiagnosticStatus::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder DiagnosticStatus::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void DiagnosticStatus::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> DiagnosticStatus::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool DiagnosticStatus::Reader::hasMessage() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool DiagnosticStatus::Builder::hasMessage() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader DiagnosticStatus::Reader::getMessage() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder DiagnosticStatus::Builder::getMessage() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void DiagnosticStatus::Builder::setMessage( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder DiagnosticStatus::Builder::initMessage(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void DiagnosticStatus::Builder::adoptMessage( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> DiagnosticStatus::Builder::disownMessage() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool DiagnosticStatus::Reader::hasHardwareId() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool DiagnosticStatus::Builder::hasHardwareId() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader DiagnosticStatus::Reader::getHardwareId() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder DiagnosticStatus::Builder::getHardwareId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void DiagnosticStatus::Builder::setHardwareId( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder DiagnosticStatus::Builder::initHardwareId(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void DiagnosticStatus::Builder::adoptHardwareId( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> DiagnosticStatus::Builder::disownHardwareId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool DiagnosticStatus::Reader::hasValues() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool DiagnosticStatus::Builder::hasValues() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>::Reader DiagnosticStatus::Reader::getValues() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>::Builder DiagnosticStatus::Builder::getValues() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void DiagnosticStatus::Builder::setValues( ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>::Builder DiagnosticStatus::Builder::initValues(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void DiagnosticStatus::Builder::adoptValues( + ::capnp::Orphan< ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>> DiagnosticStatus::Builder::disownValues() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::diagnostic::KeyValue, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool KeyValue::Reader::hasKey() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool KeyValue::Builder::hasKey() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader KeyValue::Reader::getKey() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder KeyValue::Builder::getKey() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void KeyValue::Builder::setKey( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder KeyValue::Builder::initKey(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void KeyValue::Builder::adoptKey( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> KeyValue::Builder::disownKey() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool KeyValue::Reader::hasValue() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool KeyValue::Builder::hasValue() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader KeyValue::Reader::getValue() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder KeyValue::Builder::getValue() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void KeyValue::Builder::setValue( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder KeyValue::Builder::initValue(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void KeyValue::Builder::adoptValue( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> KeyValue::Builder::disownValue() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +} // namespace +} // namespace + +CAPNP_END_HEADER + diff --git a/msg/src/fairomsg/cpp/geometry_msgs.capnp.c++ b/msg/src/fairomsg/cpp/geometry_msgs.capnp.c++ new file mode 100644 index 0000000000..5927ba0f31 --- /dev/null +++ b/msg/src/fairomsg/cpp/geometry_msgs.capnp.c++ @@ -0,0 +1,2290 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: geometry_msgs.capnp + +#include "geometry_msgs.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<48> b_c85214e2b79237b1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 177, 55, 146, 183, 226, 20, 82, 200, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 65, 99, 99, 101, 108, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 108, 105, 110, 101, 97, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 117, 108, 97, 114, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c85214e2b79237b1 = b_c85214e2b79237b1.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c85214e2b79237b1[] = { + &s_89d716bb34f0209a, +}; +static const uint16_t m_c85214e2b79237b1[] = {1, 0}; +static const uint16_t i_c85214e2b79237b1[] = {0, 1}; +const ::capnp::_::RawSchema s_c85214e2b79237b1 = { + 0xc85214e2b79237b1, b_c85214e2b79237b1.words, 48, d_c85214e2b79237b1, m_c85214e2b79237b1, + 1, 2, i_c85214e2b79237b1, nullptr, nullptr, { &s_c85214e2b79237b1, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_8806d80e8e8c4d40 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 64, 77, 140, 142, 14, 216, 6, 136, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 65, 99, 99, 101, 108, 83, 116, 97, + 109, 112, 101, 100, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 177, 55, 146, 183, 226, 20, 82, 200, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8806d80e8e8c4d40 = b_8806d80e8e8c4d40.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_8806d80e8e8c4d40[] = { + &s_c85214e2b79237b1, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_8806d80e8e8c4d40[] = {1, 0}; +static const uint16_t i_8806d80e8e8c4d40[] = {0, 1}; +const ::capnp::_::RawSchema s_8806d80e8e8c4d40 = { + 0x8806d80e8e8c4d40, b_8806d80e8e8c4d40.words, 49, d_8806d80e8e8c4d40, m_8806d80e8e8c4d40, + 2, 2, i_8806d80e8e8c4d40, nullptr, nullptr, { &s_8806d80e8e8c4d40, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<55> b_a51c6b3c512f5eee = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 238, 94, 47, 81, 60, 107, 28, 165, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 98, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 65, 99, 99, 101, 108, 87, 105, 116, + 104, 67, 111, 118, 97, 114, 105, 97, + 110, 99, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 72, 0, 0, 0, 2, 0, 1, 0, + 97, 99, 99, 101, 108, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 177, 55, 146, 183, 226, 20, 82, 200, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 118, 97, 114, 105, 97, 110, + 99, 101, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a51c6b3c512f5eee = b_a51c6b3c512f5eee.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a51c6b3c512f5eee[] = { + &s_c85214e2b79237b1, +}; +static const uint16_t m_a51c6b3c512f5eee[] = {0, 1}; +static const uint16_t i_a51c6b3c512f5eee[] = {0, 1}; +const ::capnp::_::RawSchema s_a51c6b3c512f5eee = { + 0xa51c6b3c512f5eee, b_a51c6b3c512f5eee.words, 55, d_a51c6b3c512f5eee, m_a51c6b3c512f5eee, + 1, 2, i_a51c6b3c512f5eee, nullptr, nullptr, { &s_a51c6b3c512f5eee, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<51> b_fd8fa84434c29dd4 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 212, 157, 194, 52, 68, 168, 143, 253, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 65, 99, 99, 101, 108, 87, 105, 116, + 104, 67, 111, 118, 97, 114, 105, 97, + 110, 99, 101, 83, 116, 97, 109, 112, + 101, 100, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 238, 94, 47, 81, 60, 107, 28, 165, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fd8fa84434c29dd4 = b_fd8fa84434c29dd4.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_fd8fa84434c29dd4[] = { + &s_a51c6b3c512f5eee, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_fd8fa84434c29dd4[] = {1, 0}; +static const uint16_t i_fd8fa84434c29dd4[] = {0, 1}; +const ::capnp::_::RawSchema s_fd8fa84434c29dd4 = { + 0xfd8fa84434c29dd4, b_fd8fa84434c29dd4.words, 51, d_fd8fa84434c29dd4, m_fd8fa84434c29dd4, + 2, 2, i_fd8fa84434c29dd4, nullptr, nullptr, { &s_fd8fa84434c29dd4, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<138> b_85066bc334c104d8 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 216, 4, 193, 52, 195, 107, 6, 133, + 24, 0, 0, 0, 1, 0, 7, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 73, 110, 101, 114, 116, 105, 97, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 0, 0, 0, 3, 0, 1, 0, + 236, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 0, 0, 0, 3, 0, 1, 0, + 240, 0, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 109, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 109, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 120, 120, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 120, 121, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 120, 122, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 121, 121, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 121, 122, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 122, 122, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_85066bc334c104d8 = b_85066bc334c104d8.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_85066bc334c104d8[] = { + &s_89d716bb34f0209a, +}; +static const uint16_t m_85066bc334c104d8[] = {1, 2, 3, 4, 5, 6, 7, 0}; +static const uint16_t i_85066bc334c104d8[] = {0, 1, 2, 3, 4, 5, 6, 7}; +const ::capnp::_::RawSchema s_85066bc334c104d8 = { + 0x85066bc334c104d8, b_85066bc334c104d8.words, 138, d_85066bc334c104d8, m_85066bc334c104d8, + 1, 8, i_85066bc334c104d8, nullptr, nullptr, { &s_85066bc334c104d8, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_c0a33a5089a90236 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 54, 2, 169, 137, 80, 58, 163, 192, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 73, 110, 101, 114, 116, 105, 97, 83, + 116, 97, 109, 112, 101, 100, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 101, 114, 116, 105, 97, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 216, 4, 193, 52, 195, 107, 6, 133, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c0a33a5089a90236 = b_c0a33a5089a90236.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c0a33a5089a90236[] = { + &s_85066bc334c104d8, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_c0a33a5089a90236[] = {0, 1}; +static const uint16_t i_c0a33a5089a90236[] = {0, 1}; +const ::capnp::_::RawSchema s_c0a33a5089a90236 = { + 0xc0a33a5089a90236, b_c0a33a5089a90236.words, 49, d_c0a33a5089a90236, m_c0a33a5089a90236, + 2, 2, i_c0a33a5089a90236, nullptr, nullptr, { &s_c0a33a5089a90236, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<63> b_ebab599af84d3b44 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 68, 59, 77, 248, 154, 89, 171, 235, + 24, 0, 0, 0, 1, 0, 3, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 80, 111, 105, 110, 116, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 122, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ebab599af84d3b44 = b_ebab599af84d3b44.words; +#if !CAPNP_LITE +static const uint16_t m_ebab599af84d3b44[] = {0, 1, 2}; +static const uint16_t i_ebab599af84d3b44[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_ebab599af84d3b44 = { + 0xebab599af84d3b44, b_ebab599af84d3b44.words, 63, nullptr, m_ebab599af84d3b44, + 0, 3, i_ebab599af84d3b44, nullptr, nullptr, { &s_ebab599af84d3b44, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<63> b_bd17305162f7a3dd = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 221, 163, 247, 98, 81, 48, 23, 189, + 24, 0, 0, 0, 1, 0, 2, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 80, 111, 105, 110, 116, 51, 50, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 122, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bd17305162f7a3dd = b_bd17305162f7a3dd.words; +#if !CAPNP_LITE +static const uint16_t m_bd17305162f7a3dd[] = {0, 1, 2}; +static const uint16_t i_bd17305162f7a3dd[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_bd17305162f7a3dd = { + 0xbd17305162f7a3dd, b_bd17305162f7a3dd.words, 63, nullptr, m_bd17305162f7a3dd, + 0, 3, i_bd17305162f7a3dd, nullptr, nullptr, { &s_bd17305162f7a3dd, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_bb3a4e3eb6109801 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 1, 152, 16, 182, 62, 78, 58, 187, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 80, 111, 105, 110, 116, 83, 116, 97, + 109, 112, 101, 100, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 105, 110, 116, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 68, 59, 77, 248, 154, 89, 171, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bb3a4e3eb6109801 = b_bb3a4e3eb6109801.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_bb3a4e3eb6109801[] = { + &s_cf9a8bcf03922937, + &s_ebab599af84d3b44, +}; +static const uint16_t m_bb3a4e3eb6109801[] = {0, 1}; +static const uint16_t i_bb3a4e3eb6109801[] = {0, 1}; +const ::capnp::_::RawSchema s_bb3a4e3eb6109801 = { + 0xbb3a4e3eb6109801, b_bb3a4e3eb6109801.words, 49, d_bb3a4e3eb6109801, m_bb3a4e3eb6109801, + 2, 2, i_bb3a4e3eb6109801, nullptr, nullptr, { &s_bb3a4e3eb6109801, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<37> b_ac7d25eb0068cd89 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 137, 205, 104, 0, 235, 37, 125, 172, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 80, 111, 108, 121, 103, 111, 110, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 36, 0, 0, 0, 2, 0, 1, 0, + 112, 111, 105, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 221, 163, 247, 98, 81, 48, 23, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ac7d25eb0068cd89 = b_ac7d25eb0068cd89.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_ac7d25eb0068cd89[] = { + &s_bd17305162f7a3dd, +}; +static const uint16_t m_ac7d25eb0068cd89[] = {0}; +static const uint16_t i_ac7d25eb0068cd89[] = {0}; +const ::capnp::_::RawSchema s_ac7d25eb0068cd89 = { + 0xac7d25eb0068cd89, b_ac7d25eb0068cd89.words, 37, d_ac7d25eb0068cd89, m_ac7d25eb0068cd89, + 1, 1, i_ac7d25eb0068cd89, nullptr, nullptr, { &s_ac7d25eb0068cd89, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_90ebe6e3a8d4af38 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 56, 175, 212, 168, 227, 230, 235, 144, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 80, 111, 108, 121, 103, 111, 110, 83, + 116, 97, 109, 112, 101, 100, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 108, 121, 103, 111, 110, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 137, 205, 104, 0, 235, 37, 125, 172, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_90ebe6e3a8d4af38 = b_90ebe6e3a8d4af38.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_90ebe6e3a8d4af38[] = { + &s_ac7d25eb0068cd89, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_90ebe6e3a8d4af38[] = {0, 1}; +static const uint16_t i_90ebe6e3a8d4af38[] = {0, 1}; +const ::capnp::_::RawSchema s_90ebe6e3a8d4af38 = { + 0x90ebe6e3a8d4af38, b_90ebe6e3a8d4af38.words, 49, d_90ebe6e3a8d4af38, m_90ebe6e3a8d4af38, + 2, 2, i_90ebe6e3a8d4af38, nullptr, nullptr, { &s_90ebe6e3a8d4af38, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<50> b_aaf6c5a3bec98ba8 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 168, 139, 201, 190, 163, 197, 246, 170, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 80, 111, 115, 101, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 68, 59, 77, 248, 154, 89, 171, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 101, 110, 116, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 100, 4, 183, 255, 76, 138, 17, 175, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_aaf6c5a3bec98ba8 = b_aaf6c5a3bec98ba8.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_aaf6c5a3bec98ba8[] = { + &s_af118a4cffb70464, + &s_ebab599af84d3b44, +}; +static const uint16_t m_aaf6c5a3bec98ba8[] = {1, 0}; +static const uint16_t i_aaf6c5a3bec98ba8[] = {0, 1}; +const ::capnp::_::RawSchema s_aaf6c5a3bec98ba8 = { + 0xaaf6c5a3bec98ba8, b_aaf6c5a3bec98ba8.words, 50, d_aaf6c5a3bec98ba8, m_aaf6c5a3bec98ba8, + 2, 2, i_aaf6c5a3bec98ba8, nullptr, nullptr, { &s_aaf6c5a3bec98ba8, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<63> b_e5f936f25dcdb4a0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 160, 180, 205, 93, 242, 54, 249, 229, + 24, 0, 0, 0, 1, 0, 3, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 80, 111, 115, 101, 50, 68, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 104, 101, 116, 97, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e5f936f25dcdb4a0 = b_e5f936f25dcdb4a0.words; +#if !CAPNP_LITE +static const uint16_t m_e5f936f25dcdb4a0[] = {2, 0, 1}; +static const uint16_t i_e5f936f25dcdb4a0[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_e5f936f25dcdb4a0 = { + 0xe5f936f25dcdb4a0, b_e5f936f25dcdb4a0.words, 63, nullptr, m_e5f936f25dcdb4a0, + 0, 3, i_e5f936f25dcdb4a0, nullptr, nullptr, { &s_e5f936f25dcdb4a0, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_a7f72661fcb193b7 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 183, 147, 177, 252, 97, 38, 247, 167, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 80, 111, 115, 101, 65, 114, 114, 97, + 121, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 168, 139, 201, 190, 163, 197, 246, 170, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a7f72661fcb193b7 = b_a7f72661fcb193b7.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a7f72661fcb193b7[] = { + &s_aaf6c5a3bec98ba8, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_a7f72661fcb193b7[] = {0, 1}; +static const uint16_t i_a7f72661fcb193b7[] = {0, 1}; +const ::capnp::_::RawSchema s_a7f72661fcb193b7 = { + 0xa7f72661fcb193b7, b_a7f72661fcb193b7.words, 53, d_a7f72661fcb193b7, m_a7f72661fcb193b7, + 2, 2, i_a7f72661fcb193b7, nullptr, nullptr, { &s_a7f72661fcb193b7, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_9e7f144eb85fe85e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 94, 232, 95, 184, 78, 20, 127, 158, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 80, 111, 115, 101, 83, 116, 97, 109, + 112, 101, 100, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 168, 139, 201, 190, 163, 197, 246, 170, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9e7f144eb85fe85e = b_9e7f144eb85fe85e.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_9e7f144eb85fe85e[] = { + &s_aaf6c5a3bec98ba8, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_9e7f144eb85fe85e[] = {0, 1}; +static const uint16_t i_9e7f144eb85fe85e[] = {0, 1}; +const ::capnp::_::RawSchema s_9e7f144eb85fe85e = { + 0x9e7f144eb85fe85e, b_9e7f144eb85fe85e.words, 49, d_9e7f144eb85fe85e, m_9e7f144eb85fe85e, + 2, 2, i_9e7f144eb85fe85e, nullptr, nullptr, { &s_9e7f144eb85fe85e, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<55> b_fa182984d85f3156 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 86, 49, 95, 216, 132, 41, 24, 250, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 80, 111, 115, 101, 87, 105, 116, 104, + 67, 111, 118, 97, 114, 105, 97, 110, + 99, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 72, 0, 0, 0, 2, 0, 1, 0, + 112, 111, 115, 101, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 168, 139, 201, 190, 163, 197, 246, 170, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 118, 97, 114, 105, 97, 110, + 99, 101, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fa182984d85f3156 = b_fa182984d85f3156.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_fa182984d85f3156[] = { + &s_aaf6c5a3bec98ba8, +}; +static const uint16_t m_fa182984d85f3156[] = {1, 0}; +static const uint16_t i_fa182984d85f3156[] = {0, 1}; +const ::capnp::_::RawSchema s_fa182984d85f3156 = { + 0xfa182984d85f3156, b_fa182984d85f3156.words, 55, d_fa182984d85f3156, m_fa182984d85f3156, + 1, 2, i_fa182984d85f3156, nullptr, nullptr, { &s_fa182984d85f3156, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<51> b_90e5c0f787726f80 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 128, 111, 114, 135, 247, 192, 229, 144, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 80, 111, 115, 101, 87, 105, 116, 104, + 67, 111, 118, 97, 114, 105, 97, 110, + 99, 101, 83, 116, 97, 109, 112, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 86, 49, 95, 216, 132, 41, 24, 250, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_90e5c0f787726f80 = b_90e5c0f787726f80.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_90e5c0f787726f80[] = { + &s_cf9a8bcf03922937, + &s_fa182984d85f3156, +}; +static const uint16_t m_90e5c0f787726f80[] = {0, 1}; +static const uint16_t i_90e5c0f787726f80[] = {0, 1}; +const ::capnp::_::RawSchema s_90e5c0f787726f80 = { + 0x90e5c0f787726f80, b_90e5c0f787726f80.words, 51, d_90e5c0f787726f80, m_90e5c0f787726f80, + 2, 2, i_90e5c0f787726f80, nullptr, nullptr, { &s_90e5c0f787726f80, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<79> b_af118a4cffb70464 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 100, 4, 183, 255, 76, 138, 17, 175, + 24, 0, 0, 0, 1, 0, 4, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 81, 117, 97, 116, 101, 114, 110, 105, + 111, 110, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 122, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_af118a4cffb70464 = b_af118a4cffb70464.words; +#if !CAPNP_LITE +static const uint16_t m_af118a4cffb70464[] = {3, 0, 1, 2}; +static const uint16_t i_af118a4cffb70464[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_af118a4cffb70464 = { + 0xaf118a4cffb70464, b_af118a4cffb70464.words, 79, nullptr, m_af118a4cffb70464, + 0, 4, i_af118a4cffb70464, nullptr, nullptr, { &s_af118a4cffb70464, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<51> b_e714439bda2b8906 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 6, 137, 43, 218, 155, 67, 20, 231, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 81, 117, 97, 116, 101, 114, 110, 105, + 111, 110, 83, 116, 97, 109, 112, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 117, 97, 116, 101, 114, 110, 105, + 111, 110, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 100, 4, 183, 255, 76, 138, 17, 175, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e714439bda2b8906 = b_e714439bda2b8906.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_e714439bda2b8906[] = { + &s_af118a4cffb70464, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_e714439bda2b8906[] = {0, 1}; +static const uint16_t i_e714439bda2b8906[] = {0, 1}; +const ::capnp::_::RawSchema s_e714439bda2b8906 = { + 0xe714439bda2b8906, b_e714439bda2b8906.words, 51, d_e714439bda2b8906, m_e714439bda2b8906, + 2, 2, i_e714439bda2b8906, nullptr, nullptr, { &s_e714439bda2b8906, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<51> b_cf223f32b610adbc = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 188, 173, 16, 182, 50, 63, 34, 207, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 84, 114, 97, 110, 115, 102, 111, 114, + 109, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 116, 114, 97, 110, 115, 108, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 116, 97, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 100, 4, 183, 255, 76, 138, 17, 175, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cf223f32b610adbc = b_cf223f32b610adbc.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_cf223f32b610adbc[] = { + &s_89d716bb34f0209a, + &s_af118a4cffb70464, +}; +static const uint16_t m_cf223f32b610adbc[] = {1, 0}; +static const uint16_t i_cf223f32b610adbc[] = {0, 1}; +const ::capnp::_::RawSchema s_cf223f32b610adbc = { + 0xcf223f32b610adbc, b_cf223f32b610adbc.words, 51, d_cf223f32b610adbc, m_cf223f32b610adbc, + 2, 2, i_cf223f32b610adbc, nullptr, nullptr, { &s_cf223f32b610adbc, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<67> b_dfcb9692fa102dfa = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 250, 45, 16, 250, 146, 150, 203, 223, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 84, 114, 97, 110, 115, 102, 111, 114, + 109, 83, 116, 97, 109, 112, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 104, 105, 108, 100, 70, 114, 97, + 109, 101, 73, 100, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 110, 115, 102, 111, 114, + 109, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 188, 173, 16, 182, 50, 63, 34, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_dfcb9692fa102dfa = b_dfcb9692fa102dfa.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_dfcb9692fa102dfa[] = { + &s_cf223f32b610adbc, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_dfcb9692fa102dfa[] = {1, 0, 2}; +static const uint16_t i_dfcb9692fa102dfa[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_dfcb9692fa102dfa = { + 0xdfcb9692fa102dfa, b_dfcb9692fa102dfa.words, 67, d_dfcb9692fa102dfa, m_dfcb9692fa102dfa, + 2, 3, i_dfcb9692fa102dfa, nullptr, nullptr, { &s_dfcb9692fa102dfa, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<48> b_e3eff53945d605c5 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 197, 5, 214, 69, 57, 245, 239, 227, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 84, 119, 105, 115, 116, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 108, 105, 110, 101, 97, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 117, 108, 97, 114, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e3eff53945d605c5 = b_e3eff53945d605c5.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_e3eff53945d605c5[] = { + &s_89d716bb34f0209a, +}; +static const uint16_t m_e3eff53945d605c5[] = {1, 0}; +static const uint16_t i_e3eff53945d605c5[] = {0, 1}; +const ::capnp::_::RawSchema s_e3eff53945d605c5 = { + 0xe3eff53945d605c5, b_e3eff53945d605c5.words, 48, d_e3eff53945d605c5, m_e3eff53945d605c5, + 1, 2, i_e3eff53945d605c5, nullptr, nullptr, { &s_e3eff53945d605c5, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_ec932d063971839b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 155, 131, 113, 57, 6, 45, 147, 236, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 84, 119, 105, 115, 116, 83, 116, 97, + 109, 112, 101, 100, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 119, 105, 115, 116, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 197, 5, 214, 69, 57, 245, 239, 227, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ec932d063971839b = b_ec932d063971839b.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_ec932d063971839b[] = { + &s_cf9a8bcf03922937, + &s_e3eff53945d605c5, +}; +static const uint16_t m_ec932d063971839b[] = {0, 1}; +static const uint16_t i_ec932d063971839b[] = {0, 1}; +const ::capnp::_::RawSchema s_ec932d063971839b = { + 0xec932d063971839b, b_ec932d063971839b.words, 49, d_ec932d063971839b, m_ec932d063971839b, + 2, 2, i_ec932d063971839b, nullptr, nullptr, { &s_ec932d063971839b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<55> b_f3d733cd6fbc271d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 29, 39, 188, 111, 205, 51, 215, 243, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 98, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 84, 119, 105, 115, 116, 87, 105, 116, + 104, 67, 111, 118, 97, 114, 105, 97, + 110, 99, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 72, 0, 0, 0, 2, 0, 1, 0, + 116, 119, 105, 115, 116, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 197, 5, 214, 69, 57, 245, 239, 227, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 118, 97, 114, 105, 97, 110, + 99, 101, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f3d733cd6fbc271d = b_f3d733cd6fbc271d.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f3d733cd6fbc271d[] = { + &s_e3eff53945d605c5, +}; +static const uint16_t m_f3d733cd6fbc271d[] = {1, 0}; +static const uint16_t i_f3d733cd6fbc271d[] = {0, 1}; +const ::capnp::_::RawSchema s_f3d733cd6fbc271d = { + 0xf3d733cd6fbc271d, b_f3d733cd6fbc271d.words, 55, d_f3d733cd6fbc271d, m_f3d733cd6fbc271d, + 1, 2, i_f3d733cd6fbc271d, nullptr, nullptr, { &s_f3d733cd6fbc271d, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<51> b_a7564fb9bc29b220 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 32, 178, 41, 188, 185, 79, 86, 167, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 84, 119, 105, 115, 116, 87, 105, 116, + 104, 67, 111, 118, 97, 114, 105, 97, + 110, 99, 101, 83, 116, 97, 109, 112, + 101, 100, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 119, 105, 115, 116, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 29, 39, 188, 111, 205, 51, 215, 243, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a7564fb9bc29b220 = b_a7564fb9bc29b220.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a7564fb9bc29b220[] = { + &s_cf9a8bcf03922937, + &s_f3d733cd6fbc271d, +}; +static const uint16_t m_a7564fb9bc29b220[] = {0, 1}; +static const uint16_t i_a7564fb9bc29b220[] = {0, 1}; +const ::capnp::_::RawSchema s_a7564fb9bc29b220 = { + 0xa7564fb9bc29b220, b_a7564fb9bc29b220.words, 51, d_a7564fb9bc29b220, m_a7564fb9bc29b220, + 2, 2, i_a7564fb9bc29b220, nullptr, nullptr, { &s_a7564fb9bc29b220, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<63> b_89d716bb34f0209a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 24, 0, 0, 0, 1, 0, 3, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 86, 101, 99, 116, 111, 114, 51, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 122, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_89d716bb34f0209a = b_89d716bb34f0209a.words; +#if !CAPNP_LITE +static const uint16_t m_89d716bb34f0209a[] = {0, 1, 2}; +static const uint16_t i_89d716bb34f0209a[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_89d716bb34f0209a = { + 0x89d716bb34f0209a, b_89d716bb34f0209a.words, 63, nullptr, m_89d716bb34f0209a, + 0, 3, i_89d716bb34f0209a, nullptr, nullptr, { &s_89d716bb34f0209a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_f1b4c19528330dc3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 195, 13, 51, 40, 149, 193, 180, 241, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 86, 101, 99, 116, 111, 114, 51, 83, + 116, 97, 109, 112, 101, 100, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 99, 116, 111, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f1b4c19528330dc3 = b_f1b4c19528330dc3.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f1b4c19528330dc3[] = { + &s_89d716bb34f0209a, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_f1b4c19528330dc3[] = {0, 1}; +static const uint16_t i_f1b4c19528330dc3[] = {0, 1}; +const ::capnp::_::RawSchema s_f1b4c19528330dc3 = { + 0xf1b4c19528330dc3, b_f1b4c19528330dc3.words, 49, d_f1b4c19528330dc3, m_f1b4c19528330dc3, + 2, 2, i_f1b4c19528330dc3, nullptr, nullptr, { &s_f1b4c19528330dc3, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<48> b_81c2ac67ce6ef5ac = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 172, 245, 110, 206, 103, 172, 194, 129, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 87, 114, 101, 110, 99, 104, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 102, 111, 114, 99, 101, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 114, 113, 117, 101, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_81c2ac67ce6ef5ac = b_81c2ac67ce6ef5ac.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_81c2ac67ce6ef5ac[] = { + &s_89d716bb34f0209a, +}; +static const uint16_t m_81c2ac67ce6ef5ac[] = {0, 1}; +static const uint16_t i_81c2ac67ce6ef5ac[] = {0, 1}; +const ::capnp::_::RawSchema s_81c2ac67ce6ef5ac = { + 0x81c2ac67ce6ef5ac, b_81c2ac67ce6ef5ac.words, 48, d_81c2ac67ce6ef5ac, m_81c2ac67ce6ef5ac, + 1, 2, i_81c2ac67ce6ef5ac, nullptr, nullptr, { &s_81c2ac67ce6ef5ac, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_92557f02c3e04d9a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 154, 77, 224, 195, 2, 127, 85, 146, + 24, 0, 0, 0, 1, 0, 0, 0, + 196, 87, 211, 6, 199, 0, 66, 146, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 103, 101, 111, 109, + 101, 116, 114, 121, 95, 109, 115, 103, + 115, 46, 99, 97, 112, 110, 112, 58, + 87, 114, 101, 110, 99, 104, 83, 116, + 97, 109, 112, 101, 100, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 114, 101, 110, 99, 104, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 172, 245, 110, 206, 103, 172, 194, 129, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_92557f02c3e04d9a = b_92557f02c3e04d9a.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_92557f02c3e04d9a[] = { + &s_81c2ac67ce6ef5ac, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_92557f02c3e04d9a[] = {0, 1}; +static const uint16_t i_92557f02c3e04d9a[] = {0, 1}; +const ::capnp::_::RawSchema s_92557f02c3e04d9a = { + 0x92557f02c3e04d9a, b_92557f02c3e04d9a.words, 49, d_92557f02c3e04d9a, m_92557f02c3e04d9a, + 2, 2, i_92557f02c3e04d9a, nullptr, nullptr, { &s_92557f02c3e04d9a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace mrp { +namespace geometry { + +// Accel +constexpr uint16_t Accel::_capnpPrivate::dataWordSize; +constexpr uint16_t Accel::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Accel::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Accel::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// AccelStamped +constexpr uint16_t AccelStamped::_capnpPrivate::dataWordSize; +constexpr uint16_t AccelStamped::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind AccelStamped::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* AccelStamped::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// AccelWithCovariance +constexpr uint16_t AccelWithCovariance::_capnpPrivate::dataWordSize; +constexpr uint16_t AccelWithCovariance::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind AccelWithCovariance::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* AccelWithCovariance::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// AccelWithCovarianceStamped +constexpr uint16_t AccelWithCovarianceStamped::_capnpPrivate::dataWordSize; +constexpr uint16_t AccelWithCovarianceStamped::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind AccelWithCovarianceStamped::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* AccelWithCovarianceStamped::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Inertia +constexpr uint16_t Inertia::_capnpPrivate::dataWordSize; +constexpr uint16_t Inertia::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Inertia::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Inertia::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// InertiaStamped +constexpr uint16_t InertiaStamped::_capnpPrivate::dataWordSize; +constexpr uint16_t InertiaStamped::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind InertiaStamped::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InertiaStamped::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Point +constexpr uint16_t Point::_capnpPrivate::dataWordSize; +constexpr uint16_t Point::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Point::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Point::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Point32 +constexpr uint16_t Point32::_capnpPrivate::dataWordSize; +constexpr uint16_t Point32::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Point32::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Point32::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// PointStamped +constexpr uint16_t PointStamped::_capnpPrivate::dataWordSize; +constexpr uint16_t PointStamped::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind PointStamped::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* PointStamped::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Polygon +constexpr uint16_t Polygon::_capnpPrivate::dataWordSize; +constexpr uint16_t Polygon::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Polygon::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Polygon::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// PolygonStamped +constexpr uint16_t PolygonStamped::_capnpPrivate::dataWordSize; +constexpr uint16_t PolygonStamped::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind PolygonStamped::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* PolygonStamped::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Pose +constexpr uint16_t Pose::_capnpPrivate::dataWordSize; +constexpr uint16_t Pose::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Pose::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Pose::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Pose2D +constexpr uint16_t Pose2D::_capnpPrivate::dataWordSize; +constexpr uint16_t Pose2D::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Pose2D::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Pose2D::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// PoseArray +constexpr uint16_t PoseArray::_capnpPrivate::dataWordSize; +constexpr uint16_t PoseArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind PoseArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* PoseArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// PoseStamped +constexpr uint16_t PoseStamped::_capnpPrivate::dataWordSize; +constexpr uint16_t PoseStamped::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind PoseStamped::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* PoseStamped::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// PoseWithCovariance +constexpr uint16_t PoseWithCovariance::_capnpPrivate::dataWordSize; +constexpr uint16_t PoseWithCovariance::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind PoseWithCovariance::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* PoseWithCovariance::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// PoseWithCovarianceStamped +constexpr uint16_t PoseWithCovarianceStamped::_capnpPrivate::dataWordSize; +constexpr uint16_t PoseWithCovarianceStamped::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind PoseWithCovarianceStamped::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* PoseWithCovarianceStamped::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Quaternion +constexpr uint16_t Quaternion::_capnpPrivate::dataWordSize; +constexpr uint16_t Quaternion::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Quaternion::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Quaternion::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// QuaternionStamped +constexpr uint16_t QuaternionStamped::_capnpPrivate::dataWordSize; +constexpr uint16_t QuaternionStamped::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind QuaternionStamped::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* QuaternionStamped::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Transform +constexpr uint16_t Transform::_capnpPrivate::dataWordSize; +constexpr uint16_t Transform::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Transform::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Transform::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// TransformStamped +constexpr uint16_t TransformStamped::_capnpPrivate::dataWordSize; +constexpr uint16_t TransformStamped::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind TransformStamped::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* TransformStamped::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Twist +constexpr uint16_t Twist::_capnpPrivate::dataWordSize; +constexpr uint16_t Twist::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Twist::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Twist::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// TwistStamped +constexpr uint16_t TwistStamped::_capnpPrivate::dataWordSize; +constexpr uint16_t TwistStamped::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind TwistStamped::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* TwistStamped::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// TwistWithCovariance +constexpr uint16_t TwistWithCovariance::_capnpPrivate::dataWordSize; +constexpr uint16_t TwistWithCovariance::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind TwistWithCovariance::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* TwistWithCovariance::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// TwistWithCovarianceStamped +constexpr uint16_t TwistWithCovarianceStamped::_capnpPrivate::dataWordSize; +constexpr uint16_t TwistWithCovarianceStamped::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind TwistWithCovarianceStamped::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* TwistWithCovarianceStamped::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Vector3 +constexpr uint16_t Vector3::_capnpPrivate::dataWordSize; +constexpr uint16_t Vector3::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Vector3::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Vector3::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Vector3Stamped +constexpr uint16_t Vector3Stamped::_capnpPrivate::dataWordSize; +constexpr uint16_t Vector3Stamped::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Vector3Stamped::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Vector3Stamped::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Wrench +constexpr uint16_t Wrench::_capnpPrivate::dataWordSize; +constexpr uint16_t Wrench::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Wrench::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Wrench::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// WrenchStamped +constexpr uint16_t WrenchStamped::_capnpPrivate::dataWordSize; +constexpr uint16_t WrenchStamped::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind WrenchStamped::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* WrenchStamped::_capnpPrivate::schema; +#endif // !CAPNP_LITE + + +} // namespace +} // namespace + diff --git a/msg/src/fairomsg/cpp/geometry_msgs.capnp.h b/msg/src/fairomsg/cpp/geometry_msgs.capnp.h new file mode 100644 index 0000000000..d4e87b8f28 --- /dev/null +++ b/msg/src/fairomsg/cpp/geometry_msgs.capnp.h @@ -0,0 +1,5324 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: geometry_msgs.capnp + +#pragma once + +#include +#include + +#if CAPNP_VERSION != 9001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + +#include "std_msgs.capnp.h" + +CAPNP_BEGIN_HEADER + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(c85214e2b79237b1); +CAPNP_DECLARE_SCHEMA(8806d80e8e8c4d40); +CAPNP_DECLARE_SCHEMA(a51c6b3c512f5eee); +CAPNP_DECLARE_SCHEMA(fd8fa84434c29dd4); +CAPNP_DECLARE_SCHEMA(85066bc334c104d8); +CAPNP_DECLARE_SCHEMA(c0a33a5089a90236); +CAPNP_DECLARE_SCHEMA(ebab599af84d3b44); +CAPNP_DECLARE_SCHEMA(bd17305162f7a3dd); +CAPNP_DECLARE_SCHEMA(bb3a4e3eb6109801); +CAPNP_DECLARE_SCHEMA(ac7d25eb0068cd89); +CAPNP_DECLARE_SCHEMA(90ebe6e3a8d4af38); +CAPNP_DECLARE_SCHEMA(aaf6c5a3bec98ba8); +CAPNP_DECLARE_SCHEMA(e5f936f25dcdb4a0); +CAPNP_DECLARE_SCHEMA(a7f72661fcb193b7); +CAPNP_DECLARE_SCHEMA(9e7f144eb85fe85e); +CAPNP_DECLARE_SCHEMA(fa182984d85f3156); +CAPNP_DECLARE_SCHEMA(90e5c0f787726f80); +CAPNP_DECLARE_SCHEMA(af118a4cffb70464); +CAPNP_DECLARE_SCHEMA(e714439bda2b8906); +CAPNP_DECLARE_SCHEMA(cf223f32b610adbc); +CAPNP_DECLARE_SCHEMA(dfcb9692fa102dfa); +CAPNP_DECLARE_SCHEMA(e3eff53945d605c5); +CAPNP_DECLARE_SCHEMA(ec932d063971839b); +CAPNP_DECLARE_SCHEMA(f3d733cd6fbc271d); +CAPNP_DECLARE_SCHEMA(a7564fb9bc29b220); +CAPNP_DECLARE_SCHEMA(89d716bb34f0209a); +CAPNP_DECLARE_SCHEMA(f1b4c19528330dc3); +CAPNP_DECLARE_SCHEMA(81c2ac67ce6ef5ac); +CAPNP_DECLARE_SCHEMA(92557f02c3e04d9a); + +} // namespace schemas +} // namespace capnp + +namespace mrp { +namespace geometry { + +struct Accel { + Accel() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c85214e2b79237b1, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct AccelStamped { + AccelStamped() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8806d80e8e8c4d40, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct AccelWithCovariance { + AccelWithCovariance() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a51c6b3c512f5eee, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct AccelWithCovarianceStamped { + AccelWithCovarianceStamped() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(fd8fa84434c29dd4, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Inertia { + Inertia() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(85066bc334c104d8, 7, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct InertiaStamped { + InertiaStamped() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c0a33a5089a90236, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Point { + Point() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ebab599af84d3b44, 3, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Point32 { + Point32() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bd17305162f7a3dd, 2, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct PointStamped { + PointStamped() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bb3a4e3eb6109801, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Polygon { + Polygon() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ac7d25eb0068cd89, 0, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct PolygonStamped { + PolygonStamped() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(90ebe6e3a8d4af38, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Pose { + Pose() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(aaf6c5a3bec98ba8, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Pose2D { + Pose2D() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e5f936f25dcdb4a0, 3, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct PoseArray { + PoseArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a7f72661fcb193b7, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct PoseStamped { + PoseStamped() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9e7f144eb85fe85e, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct PoseWithCovariance { + PoseWithCovariance() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(fa182984d85f3156, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct PoseWithCovarianceStamped { + PoseWithCovarianceStamped() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(90e5c0f787726f80, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Quaternion { + Quaternion() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(af118a4cffb70464, 4, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct QuaternionStamped { + QuaternionStamped() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e714439bda2b8906, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Transform { + Transform() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(cf223f32b610adbc, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct TransformStamped { + TransformStamped() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(dfcb9692fa102dfa, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Twist { + Twist() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e3eff53945d605c5, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct TwistStamped { + TwistStamped() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ec932d063971839b, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct TwistWithCovariance { + TwistWithCovariance() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f3d733cd6fbc271d, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct TwistWithCovarianceStamped { + TwistWithCovarianceStamped() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a7564fb9bc29b220, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Vector3 { + Vector3() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(89d716bb34f0209a, 3, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Vector3Stamped { + Vector3Stamped() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f1b4c19528330dc3, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Wrench { + Wrench() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(81c2ac67ce6ef5ac, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct WrenchStamped { + WrenchStamped() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(92557f02c3e04d9a, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class Accel::Reader { +public: + typedef Accel Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLinear() const; + inline ::mrp::geometry::Vector3::Reader getLinear() const; + + inline bool hasAngular() const; + inline ::mrp::geometry::Vector3::Reader getAngular() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Accel::Builder { +public: + typedef Accel Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLinear(); + inline ::mrp::geometry::Vector3::Builder getLinear(); + inline void setLinear( ::mrp::geometry::Vector3::Reader value); + inline ::mrp::geometry::Vector3::Builder initLinear(); + inline void adoptLinear(::capnp::Orphan< ::mrp::geometry::Vector3>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Vector3> disownLinear(); + + inline bool hasAngular(); + inline ::mrp::geometry::Vector3::Builder getAngular(); + inline void setAngular( ::mrp::geometry::Vector3::Reader value); + inline ::mrp::geometry::Vector3::Builder initAngular(); + inline void adoptAngular(::capnp::Orphan< ::mrp::geometry::Vector3>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Vector3> disownAngular(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Accel::Pipeline { +public: + typedef Accel Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::geometry::Vector3::Pipeline getLinear(); + inline ::mrp::geometry::Vector3::Pipeline getAngular(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class AccelStamped::Reader { +public: + typedef AccelStamped Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasAccel() const; + inline ::mrp::geometry::Accel::Reader getAccel() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class AccelStamped::Builder { +public: + typedef AccelStamped Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasAccel(); + inline ::mrp::geometry::Accel::Builder getAccel(); + inline void setAccel( ::mrp::geometry::Accel::Reader value); + inline ::mrp::geometry::Accel::Builder initAccel(); + inline void adoptAccel(::capnp::Orphan< ::mrp::geometry::Accel>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Accel> disownAccel(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class AccelStamped::Pipeline { +public: + typedef AccelStamped Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Accel::Pipeline getAccel(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class AccelWithCovariance::Reader { +public: + typedef AccelWithCovariance Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasAccel() const; + inline ::mrp::geometry::Accel::Reader getAccel() const; + + inline bool hasCovariance() const; + inline ::capnp::List::Reader getCovariance() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class AccelWithCovariance::Builder { +public: + typedef AccelWithCovariance Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasAccel(); + inline ::mrp::geometry::Accel::Builder getAccel(); + inline void setAccel( ::mrp::geometry::Accel::Reader value); + inline ::mrp::geometry::Accel::Builder initAccel(); + inline void adoptAccel(::capnp::Orphan< ::mrp::geometry::Accel>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Accel> disownAccel(); + + inline bool hasCovariance(); + inline ::capnp::List::Builder getCovariance(); + inline void setCovariance( ::capnp::List::Reader value); + inline void setCovariance(::kj::ArrayPtr value); + inline ::capnp::List::Builder initCovariance(unsigned int size); + inline void adoptCovariance(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownCovariance(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class AccelWithCovariance::Pipeline { +public: + typedef AccelWithCovariance Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::geometry::Accel::Pipeline getAccel(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class AccelWithCovarianceStamped::Reader { +public: + typedef AccelWithCovarianceStamped Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasAccel() const; + inline ::mrp::geometry::AccelWithCovariance::Reader getAccel() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class AccelWithCovarianceStamped::Builder { +public: + typedef AccelWithCovarianceStamped Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasAccel(); + inline ::mrp::geometry::AccelWithCovariance::Builder getAccel(); + inline void setAccel( ::mrp::geometry::AccelWithCovariance::Reader value); + inline ::mrp::geometry::AccelWithCovariance::Builder initAccel(); + inline void adoptAccel(::capnp::Orphan< ::mrp::geometry::AccelWithCovariance>&& value); + inline ::capnp::Orphan< ::mrp::geometry::AccelWithCovariance> disownAccel(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class AccelWithCovarianceStamped::Pipeline { +public: + typedef AccelWithCovarianceStamped Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::AccelWithCovariance::Pipeline getAccel(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Inertia::Reader { +public: + typedef Inertia Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline double getM() const; + + inline bool hasCom() const; + inline ::mrp::geometry::Vector3::Reader getCom() const; + + inline double getIxx() const; + + inline double getIxy() const; + + inline double getIxz() const; + + inline double getIyy() const; + + inline double getIyz() const; + + inline double getIzz() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Inertia::Builder { +public: + typedef Inertia Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline double getM(); + inline void setM(double value); + + inline bool hasCom(); + inline ::mrp::geometry::Vector3::Builder getCom(); + inline void setCom( ::mrp::geometry::Vector3::Reader value); + inline ::mrp::geometry::Vector3::Builder initCom(); + inline void adoptCom(::capnp::Orphan< ::mrp::geometry::Vector3>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Vector3> disownCom(); + + inline double getIxx(); + inline void setIxx(double value); + + inline double getIxy(); + inline void setIxy(double value); + + inline double getIxz(); + inline void setIxz(double value); + + inline double getIyy(); + inline void setIyy(double value); + + inline double getIyz(); + inline void setIyz(double value); + + inline double getIzz(); + inline void setIzz(double value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Inertia::Pipeline { +public: + typedef Inertia Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::geometry::Vector3::Pipeline getCom(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class InertiaStamped::Reader { +public: + typedef InertiaStamped Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasInertia() const; + inline ::mrp::geometry::Inertia::Reader getInertia() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class InertiaStamped::Builder { +public: + typedef InertiaStamped Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasInertia(); + inline ::mrp::geometry::Inertia::Builder getInertia(); + inline void setInertia( ::mrp::geometry::Inertia::Reader value); + inline ::mrp::geometry::Inertia::Builder initInertia(); + inline void adoptInertia(::capnp::Orphan< ::mrp::geometry::Inertia>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Inertia> disownInertia(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class InertiaStamped::Pipeline { +public: + typedef InertiaStamped Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Inertia::Pipeline getInertia(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Point::Reader { +public: + typedef Point Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline double getX() const; + + inline double getY() const; + + inline double getZ() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Point::Builder { +public: + typedef Point Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline double getX(); + inline void setX(double value); + + inline double getY(); + inline void setY(double value); + + inline double getZ(); + inline void setZ(double value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Point::Pipeline { +public: + typedef Point Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Point32::Reader { +public: + typedef Point32 Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline float getX() const; + + inline float getY() const; + + inline float getZ() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Point32::Builder { +public: + typedef Point32 Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline float getX(); + inline void setX(float value); + + inline float getY(); + inline void setY(float value); + + inline float getZ(); + inline void setZ(float value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Point32::Pipeline { +public: + typedef Point32 Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class PointStamped::Reader { +public: + typedef PointStamped Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasPoint() const; + inline ::mrp::geometry::Point::Reader getPoint() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class PointStamped::Builder { +public: + typedef PointStamped Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasPoint(); + inline ::mrp::geometry::Point::Builder getPoint(); + inline void setPoint( ::mrp::geometry::Point::Reader value); + inline ::mrp::geometry::Point::Builder initPoint(); + inline void adoptPoint(::capnp::Orphan< ::mrp::geometry::Point>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Point> disownPoint(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class PointStamped::Pipeline { +public: + typedef PointStamped Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Point::Pipeline getPoint(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Polygon::Reader { +public: + typedef Polygon Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasPoints() const; + inline ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Reader getPoints() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Polygon::Builder { +public: + typedef Polygon Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasPoints(); + inline ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Builder getPoints(); + inline void setPoints( ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Builder initPoints(unsigned int size); + inline void adoptPoints(::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>> disownPoints(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Polygon::Pipeline { +public: + typedef Polygon Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class PolygonStamped::Reader { +public: + typedef PolygonStamped Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasPolygon() const; + inline ::mrp::geometry::Polygon::Reader getPolygon() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class PolygonStamped::Builder { +public: + typedef PolygonStamped Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasPolygon(); + inline ::mrp::geometry::Polygon::Builder getPolygon(); + inline void setPolygon( ::mrp::geometry::Polygon::Reader value); + inline ::mrp::geometry::Polygon::Builder initPolygon(); + inline void adoptPolygon(::capnp::Orphan< ::mrp::geometry::Polygon>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Polygon> disownPolygon(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class PolygonStamped::Pipeline { +public: + typedef PolygonStamped Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Polygon::Pipeline getPolygon(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Pose::Reader { +public: + typedef Pose Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasPosition() const; + inline ::mrp::geometry::Point::Reader getPosition() const; + + inline bool hasOrientation() const; + inline ::mrp::geometry::Quaternion::Reader getOrientation() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Pose::Builder { +public: + typedef Pose Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasPosition(); + inline ::mrp::geometry::Point::Builder getPosition(); + inline void setPosition( ::mrp::geometry::Point::Reader value); + inline ::mrp::geometry::Point::Builder initPosition(); + inline void adoptPosition(::capnp::Orphan< ::mrp::geometry::Point>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Point> disownPosition(); + + inline bool hasOrientation(); + inline ::mrp::geometry::Quaternion::Builder getOrientation(); + inline void setOrientation( ::mrp::geometry::Quaternion::Reader value); + inline ::mrp::geometry::Quaternion::Builder initOrientation(); + inline void adoptOrientation(::capnp::Orphan< ::mrp::geometry::Quaternion>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Quaternion> disownOrientation(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Pose::Pipeline { +public: + typedef Pose Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::geometry::Point::Pipeline getPosition(); + inline ::mrp::geometry::Quaternion::Pipeline getOrientation(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Pose2D::Reader { +public: + typedef Pose2D Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline double getX() const; + + inline double getY() const; + + inline double getTheta() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Pose2D::Builder { +public: + typedef Pose2D Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline double getX(); + inline void setX(double value); + + inline double getY(); + inline void setY(double value); + + inline double getTheta(); + inline void setTheta(double value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Pose2D::Pipeline { +public: + typedef Pose2D Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class PoseArray::Reader { +public: + typedef PoseArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasPoses() const; + inline ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>::Reader getPoses() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class PoseArray::Builder { +public: + typedef PoseArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasPoses(); + inline ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>::Builder getPoses(); + inline void setPoses( ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>::Builder initPoses(unsigned int size); + inline void adoptPoses(::capnp::Orphan< ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>> disownPoses(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class PoseArray::Pipeline { +public: + typedef PoseArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class PoseStamped::Reader { +public: + typedef PoseStamped Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasPose() const; + inline ::mrp::geometry::Pose::Reader getPose() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class PoseStamped::Builder { +public: + typedef PoseStamped Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasPose(); + inline ::mrp::geometry::Pose::Builder getPose(); + inline void setPose( ::mrp::geometry::Pose::Reader value); + inline ::mrp::geometry::Pose::Builder initPose(); + inline void adoptPose(::capnp::Orphan< ::mrp::geometry::Pose>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Pose> disownPose(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class PoseStamped::Pipeline { +public: + typedef PoseStamped Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Pose::Pipeline getPose(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class PoseWithCovariance::Reader { +public: + typedef PoseWithCovariance Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasPose() const; + inline ::mrp::geometry::Pose::Reader getPose() const; + + inline bool hasCovariance() const; + inline ::capnp::List::Reader getCovariance() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class PoseWithCovariance::Builder { +public: + typedef PoseWithCovariance Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasPose(); + inline ::mrp::geometry::Pose::Builder getPose(); + inline void setPose( ::mrp::geometry::Pose::Reader value); + inline ::mrp::geometry::Pose::Builder initPose(); + inline void adoptPose(::capnp::Orphan< ::mrp::geometry::Pose>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Pose> disownPose(); + + inline bool hasCovariance(); + inline ::capnp::List::Builder getCovariance(); + inline void setCovariance( ::capnp::List::Reader value); + inline void setCovariance(::kj::ArrayPtr value); + inline ::capnp::List::Builder initCovariance(unsigned int size); + inline void adoptCovariance(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownCovariance(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class PoseWithCovariance::Pipeline { +public: + typedef PoseWithCovariance Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::geometry::Pose::Pipeline getPose(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class PoseWithCovarianceStamped::Reader { +public: + typedef PoseWithCovarianceStamped Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasPose() const; + inline ::mrp::geometry::PoseWithCovariance::Reader getPose() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class PoseWithCovarianceStamped::Builder { +public: + typedef PoseWithCovarianceStamped Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasPose(); + inline ::mrp::geometry::PoseWithCovariance::Builder getPose(); + inline void setPose( ::mrp::geometry::PoseWithCovariance::Reader value); + inline ::mrp::geometry::PoseWithCovariance::Builder initPose(); + inline void adoptPose(::capnp::Orphan< ::mrp::geometry::PoseWithCovariance>&& value); + inline ::capnp::Orphan< ::mrp::geometry::PoseWithCovariance> disownPose(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class PoseWithCovarianceStamped::Pipeline { +public: + typedef PoseWithCovarianceStamped Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::PoseWithCovariance::Pipeline getPose(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Quaternion::Reader { +public: + typedef Quaternion Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline double getX() const; + + inline double getY() const; + + inline double getZ() const; + + inline double getW() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Quaternion::Builder { +public: + typedef Quaternion Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline double getX(); + inline void setX(double value); + + inline double getY(); + inline void setY(double value); + + inline double getZ(); + inline void setZ(double value); + + inline double getW(); + inline void setW(double value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Quaternion::Pipeline { +public: + typedef Quaternion Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class QuaternionStamped::Reader { +public: + typedef QuaternionStamped Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasQuaternion() const; + inline ::mrp::geometry::Quaternion::Reader getQuaternion() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class QuaternionStamped::Builder { +public: + typedef QuaternionStamped Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasQuaternion(); + inline ::mrp::geometry::Quaternion::Builder getQuaternion(); + inline void setQuaternion( ::mrp::geometry::Quaternion::Reader value); + inline ::mrp::geometry::Quaternion::Builder initQuaternion(); + inline void adoptQuaternion(::capnp::Orphan< ::mrp::geometry::Quaternion>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Quaternion> disownQuaternion(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class QuaternionStamped::Pipeline { +public: + typedef QuaternionStamped Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Quaternion::Pipeline getQuaternion(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Transform::Reader { +public: + typedef Transform Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasTranslation() const; + inline ::mrp::geometry::Vector3::Reader getTranslation() const; + + inline bool hasRotation() const; + inline ::mrp::geometry::Quaternion::Reader getRotation() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Transform::Builder { +public: + typedef Transform Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasTranslation(); + inline ::mrp::geometry::Vector3::Builder getTranslation(); + inline void setTranslation( ::mrp::geometry::Vector3::Reader value); + inline ::mrp::geometry::Vector3::Builder initTranslation(); + inline void adoptTranslation(::capnp::Orphan< ::mrp::geometry::Vector3>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Vector3> disownTranslation(); + + inline bool hasRotation(); + inline ::mrp::geometry::Quaternion::Builder getRotation(); + inline void setRotation( ::mrp::geometry::Quaternion::Reader value); + inline ::mrp::geometry::Quaternion::Builder initRotation(); + inline void adoptRotation(::capnp::Orphan< ::mrp::geometry::Quaternion>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Quaternion> disownRotation(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Transform::Pipeline { +public: + typedef Transform Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::geometry::Vector3::Pipeline getTranslation(); + inline ::mrp::geometry::Quaternion::Pipeline getRotation(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class TransformStamped::Reader { +public: + typedef TransformStamped Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasChildFrameId() const; + inline ::capnp::Text::Reader getChildFrameId() const; + + inline bool hasTransform() const; + inline ::mrp::geometry::Transform::Reader getTransform() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class TransformStamped::Builder { +public: + typedef TransformStamped Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasChildFrameId(); + inline ::capnp::Text::Builder getChildFrameId(); + inline void setChildFrameId( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initChildFrameId(unsigned int size); + inline void adoptChildFrameId(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownChildFrameId(); + + inline bool hasTransform(); + inline ::mrp::geometry::Transform::Builder getTransform(); + inline void setTransform( ::mrp::geometry::Transform::Reader value); + inline ::mrp::geometry::Transform::Builder initTransform(); + inline void adoptTransform(::capnp::Orphan< ::mrp::geometry::Transform>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Transform> disownTransform(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class TransformStamped::Pipeline { +public: + typedef TransformStamped Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Transform::Pipeline getTransform(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Twist::Reader { +public: + typedef Twist Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLinear() const; + inline ::mrp::geometry::Vector3::Reader getLinear() const; + + inline bool hasAngular() const; + inline ::mrp::geometry::Vector3::Reader getAngular() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Twist::Builder { +public: + typedef Twist Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLinear(); + inline ::mrp::geometry::Vector3::Builder getLinear(); + inline void setLinear( ::mrp::geometry::Vector3::Reader value); + inline ::mrp::geometry::Vector3::Builder initLinear(); + inline void adoptLinear(::capnp::Orphan< ::mrp::geometry::Vector3>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Vector3> disownLinear(); + + inline bool hasAngular(); + inline ::mrp::geometry::Vector3::Builder getAngular(); + inline void setAngular( ::mrp::geometry::Vector3::Reader value); + inline ::mrp::geometry::Vector3::Builder initAngular(); + inline void adoptAngular(::capnp::Orphan< ::mrp::geometry::Vector3>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Vector3> disownAngular(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Twist::Pipeline { +public: + typedef Twist Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::geometry::Vector3::Pipeline getLinear(); + inline ::mrp::geometry::Vector3::Pipeline getAngular(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class TwistStamped::Reader { +public: + typedef TwistStamped Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasTwist() const; + inline ::mrp::geometry::Twist::Reader getTwist() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class TwistStamped::Builder { +public: + typedef TwistStamped Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasTwist(); + inline ::mrp::geometry::Twist::Builder getTwist(); + inline void setTwist( ::mrp::geometry::Twist::Reader value); + inline ::mrp::geometry::Twist::Builder initTwist(); + inline void adoptTwist(::capnp::Orphan< ::mrp::geometry::Twist>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Twist> disownTwist(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class TwistStamped::Pipeline { +public: + typedef TwistStamped Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Twist::Pipeline getTwist(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class TwistWithCovariance::Reader { +public: + typedef TwistWithCovariance Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasTwist() const; + inline ::mrp::geometry::Twist::Reader getTwist() const; + + inline bool hasCovariance() const; + inline ::capnp::List::Reader getCovariance() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class TwistWithCovariance::Builder { +public: + typedef TwistWithCovariance Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasTwist(); + inline ::mrp::geometry::Twist::Builder getTwist(); + inline void setTwist( ::mrp::geometry::Twist::Reader value); + inline ::mrp::geometry::Twist::Builder initTwist(); + inline void adoptTwist(::capnp::Orphan< ::mrp::geometry::Twist>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Twist> disownTwist(); + + inline bool hasCovariance(); + inline ::capnp::List::Builder getCovariance(); + inline void setCovariance( ::capnp::List::Reader value); + inline void setCovariance(::kj::ArrayPtr value); + inline ::capnp::List::Builder initCovariance(unsigned int size); + inline void adoptCovariance(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownCovariance(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class TwistWithCovariance::Pipeline { +public: + typedef TwistWithCovariance Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::geometry::Twist::Pipeline getTwist(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class TwistWithCovarianceStamped::Reader { +public: + typedef TwistWithCovarianceStamped Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasTwist() const; + inline ::mrp::geometry::TwistWithCovariance::Reader getTwist() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class TwistWithCovarianceStamped::Builder { +public: + typedef TwistWithCovarianceStamped Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasTwist(); + inline ::mrp::geometry::TwistWithCovariance::Builder getTwist(); + inline void setTwist( ::mrp::geometry::TwistWithCovariance::Reader value); + inline ::mrp::geometry::TwistWithCovariance::Builder initTwist(); + inline void adoptTwist(::capnp::Orphan< ::mrp::geometry::TwistWithCovariance>&& value); + inline ::capnp::Orphan< ::mrp::geometry::TwistWithCovariance> disownTwist(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class TwistWithCovarianceStamped::Pipeline { +public: + typedef TwistWithCovarianceStamped Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::TwistWithCovariance::Pipeline getTwist(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Vector3::Reader { +public: + typedef Vector3 Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline double getX() const; + + inline double getY() const; + + inline double getZ() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Vector3::Builder { +public: + typedef Vector3 Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline double getX(); + inline void setX(double value); + + inline double getY(); + inline void setY(double value); + + inline double getZ(); + inline void setZ(double value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Vector3::Pipeline { +public: + typedef Vector3 Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Vector3Stamped::Reader { +public: + typedef Vector3Stamped Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasVector() const; + inline ::mrp::geometry::Vector3::Reader getVector() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Vector3Stamped::Builder { +public: + typedef Vector3Stamped Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasVector(); + inline ::mrp::geometry::Vector3::Builder getVector(); + inline void setVector( ::mrp::geometry::Vector3::Reader value); + inline ::mrp::geometry::Vector3::Builder initVector(); + inline void adoptVector(::capnp::Orphan< ::mrp::geometry::Vector3>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Vector3> disownVector(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Vector3Stamped::Pipeline { +public: + typedef Vector3Stamped Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Vector3::Pipeline getVector(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Wrench::Reader { +public: + typedef Wrench Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasForce() const; + inline ::mrp::geometry::Vector3::Reader getForce() const; + + inline bool hasTorque() const; + inline ::mrp::geometry::Vector3::Reader getTorque() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Wrench::Builder { +public: + typedef Wrench Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasForce(); + inline ::mrp::geometry::Vector3::Builder getForce(); + inline void setForce( ::mrp::geometry::Vector3::Reader value); + inline ::mrp::geometry::Vector3::Builder initForce(); + inline void adoptForce(::capnp::Orphan< ::mrp::geometry::Vector3>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Vector3> disownForce(); + + inline bool hasTorque(); + inline ::mrp::geometry::Vector3::Builder getTorque(); + inline void setTorque( ::mrp::geometry::Vector3::Reader value); + inline ::mrp::geometry::Vector3::Builder initTorque(); + inline void adoptTorque(::capnp::Orphan< ::mrp::geometry::Vector3>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Vector3> disownTorque(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Wrench::Pipeline { +public: + typedef Wrench Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::geometry::Vector3::Pipeline getForce(); + inline ::mrp::geometry::Vector3::Pipeline getTorque(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class WrenchStamped::Reader { +public: + typedef WrenchStamped Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasWrench() const; + inline ::mrp::geometry::Wrench::Reader getWrench() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class WrenchStamped::Builder { +public: + typedef WrenchStamped Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasWrench(); + inline ::mrp::geometry::Wrench::Builder getWrench(); + inline void setWrench( ::mrp::geometry::Wrench::Reader value); + inline ::mrp::geometry::Wrench::Builder initWrench(); + inline void adoptWrench(::capnp::Orphan< ::mrp::geometry::Wrench>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Wrench> disownWrench(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class WrenchStamped::Pipeline { +public: + typedef WrenchStamped Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Wrench::Pipeline getWrench(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline bool Accel::Reader::hasLinear() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Accel::Builder::hasLinear() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Vector3::Reader Accel::Reader::getLinear() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Vector3::Builder Accel::Builder::getLinear() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Vector3::Pipeline Accel::Pipeline::getLinear() { + return ::mrp::geometry::Vector3::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Accel::Builder::setLinear( ::mrp::geometry::Vector3::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Vector3::Builder Accel::Builder::initLinear() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Accel::Builder::adoptLinear( + ::capnp::Orphan< ::mrp::geometry::Vector3>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Vector3> Accel::Builder::disownLinear() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Accel::Reader::hasAngular() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Accel::Builder::hasAngular() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Vector3::Reader Accel::Reader::getAngular() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Vector3::Builder Accel::Builder::getAngular() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Vector3::Pipeline Accel::Pipeline::getAngular() { + return ::mrp::geometry::Vector3::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void Accel::Builder::setAngular( ::mrp::geometry::Vector3::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Vector3::Builder Accel::Builder::initAngular() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Accel::Builder::adoptAngular( + ::capnp::Orphan< ::mrp::geometry::Vector3>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Vector3> Accel::Builder::disownAngular() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool AccelStamped::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool AccelStamped::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader AccelStamped::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder AccelStamped::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline AccelStamped::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void AccelStamped::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder AccelStamped::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void AccelStamped::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> AccelStamped::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool AccelStamped::Reader::hasAccel() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool AccelStamped::Builder::hasAccel() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Accel::Reader AccelStamped::Reader::getAccel() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Accel>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Accel::Builder AccelStamped::Builder::getAccel() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Accel>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Accel::Pipeline AccelStamped::Pipeline::getAccel() { + return ::mrp::geometry::Accel::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void AccelStamped::Builder::setAccel( ::mrp::geometry::Accel::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Accel>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Accel::Builder AccelStamped::Builder::initAccel() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Accel>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void AccelStamped::Builder::adoptAccel( + ::capnp::Orphan< ::mrp::geometry::Accel>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Accel>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Accel> AccelStamped::Builder::disownAccel() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Accel>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool AccelWithCovariance::Reader::hasAccel() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool AccelWithCovariance::Builder::hasAccel() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Accel::Reader AccelWithCovariance::Reader::getAccel() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Accel>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Accel::Builder AccelWithCovariance::Builder::getAccel() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Accel>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Accel::Pipeline AccelWithCovariance::Pipeline::getAccel() { + return ::mrp::geometry::Accel::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void AccelWithCovariance::Builder::setAccel( ::mrp::geometry::Accel::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Accel>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Accel::Builder AccelWithCovariance::Builder::initAccel() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Accel>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void AccelWithCovariance::Builder::adoptAccel( + ::capnp::Orphan< ::mrp::geometry::Accel>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Accel>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Accel> AccelWithCovariance::Builder::disownAccel() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Accel>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool AccelWithCovariance::Reader::hasCovariance() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool AccelWithCovariance::Builder::hasCovariance() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader AccelWithCovariance::Reader::getCovariance() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder AccelWithCovariance::Builder::getCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void AccelWithCovariance::Builder::setCovariance( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void AccelWithCovariance::Builder::setCovariance(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder AccelWithCovariance::Builder::initCovariance(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void AccelWithCovariance::Builder::adoptCovariance( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> AccelWithCovariance::Builder::disownCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool AccelWithCovarianceStamped::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool AccelWithCovarianceStamped::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader AccelWithCovarianceStamped::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder AccelWithCovarianceStamped::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline AccelWithCovarianceStamped::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void AccelWithCovarianceStamped::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder AccelWithCovarianceStamped::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void AccelWithCovarianceStamped::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> AccelWithCovarianceStamped::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool AccelWithCovarianceStamped::Reader::hasAccel() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool AccelWithCovarianceStamped::Builder::hasAccel() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::AccelWithCovariance::Reader AccelWithCovarianceStamped::Reader::getAccel() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::AccelWithCovariance>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::AccelWithCovariance::Builder AccelWithCovarianceStamped::Builder::getAccel() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::AccelWithCovariance>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::AccelWithCovariance::Pipeline AccelWithCovarianceStamped::Pipeline::getAccel() { + return ::mrp::geometry::AccelWithCovariance::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void AccelWithCovarianceStamped::Builder::setAccel( ::mrp::geometry::AccelWithCovariance::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::AccelWithCovariance>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::AccelWithCovariance::Builder AccelWithCovarianceStamped::Builder::initAccel() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::AccelWithCovariance>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void AccelWithCovarianceStamped::Builder::adoptAccel( + ::capnp::Orphan< ::mrp::geometry::AccelWithCovariance>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::AccelWithCovariance>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::AccelWithCovariance> AccelWithCovarianceStamped::Builder::disownAccel() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::AccelWithCovariance>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline double Inertia::Reader::getM() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline double Inertia::Builder::getM() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Inertia::Builder::setM(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Inertia::Reader::hasCom() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Inertia::Builder::hasCom() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Vector3::Reader Inertia::Reader::getCom() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Vector3::Builder Inertia::Builder::getCom() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Vector3::Pipeline Inertia::Pipeline::getCom() { + return ::mrp::geometry::Vector3::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Inertia::Builder::setCom( ::mrp::geometry::Vector3::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Vector3::Builder Inertia::Builder::initCom() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Inertia::Builder::adoptCom( + ::capnp::Orphan< ::mrp::geometry::Vector3>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Vector3> Inertia::Builder::disownCom() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline double Inertia::Reader::getIxx() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double Inertia::Builder::getIxx() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Inertia::Builder::setIxx(double value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline double Inertia::Reader::getIxy() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline double Inertia::Builder::getIxy() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Inertia::Builder::setIxy(double value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline double Inertia::Reader::getIxz() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline double Inertia::Builder::getIxz() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void Inertia::Builder::setIxz(double value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline double Inertia::Reader::getIyy() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline double Inertia::Builder::getIyy() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline void Inertia::Builder::setIyy(double value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); +} + +inline double Inertia::Reader::getIyz() const { + return _reader.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline double Inertia::Builder::getIyz() { + return _builder.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline void Inertia::Builder::setIyz(double value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); +} + +inline double Inertia::Reader::getIzz() const { + return _reader.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} + +inline double Inertia::Builder::getIzz() { + return _builder.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} +inline void Inertia::Builder::setIzz(double value) { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, value); +} + +inline bool InertiaStamped::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool InertiaStamped::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader InertiaStamped::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder InertiaStamped::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline InertiaStamped::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void InertiaStamped::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder InertiaStamped::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void InertiaStamped::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> InertiaStamped::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool InertiaStamped::Reader::hasInertia() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool InertiaStamped::Builder::hasInertia() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Inertia::Reader InertiaStamped::Reader::getInertia() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Inertia>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Inertia::Builder InertiaStamped::Builder::getInertia() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Inertia>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Inertia::Pipeline InertiaStamped::Pipeline::getInertia() { + return ::mrp::geometry::Inertia::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void InertiaStamped::Builder::setInertia( ::mrp::geometry::Inertia::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Inertia>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Inertia::Builder InertiaStamped::Builder::initInertia() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Inertia>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void InertiaStamped::Builder::adoptInertia( + ::capnp::Orphan< ::mrp::geometry::Inertia>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Inertia>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Inertia> InertiaStamped::Builder::disownInertia() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Inertia>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline double Point::Reader::getX() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline double Point::Builder::getX() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Point::Builder::setX(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline double Point::Reader::getY() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double Point::Builder::getY() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Point::Builder::setY(double value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline double Point::Reader::getZ() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline double Point::Builder::getZ() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Point::Builder::setZ(double value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline float Point32::Reader::getX() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline float Point32::Builder::getX() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Point32::Builder::setX(float value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline float Point32::Reader::getY() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline float Point32::Builder::getY() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Point32::Builder::setY(float value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline float Point32::Reader::getZ() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline float Point32::Builder::getZ() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Point32::Builder::setZ(float value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool PointStamped::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool PointStamped::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader PointStamped::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder PointStamped::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline PointStamped::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void PointStamped::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder PointStamped::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void PointStamped::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> PointStamped::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool PointStamped::Reader::hasPoint() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool PointStamped::Builder::hasPoint() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Point::Reader PointStamped::Reader::getPoint() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Point::Builder PointStamped::Builder::getPoint() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Point::Pipeline PointStamped::Pipeline::getPoint() { + return ::mrp::geometry::Point::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void PointStamped::Builder::setPoint( ::mrp::geometry::Point::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Point::Builder PointStamped::Builder::initPoint() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void PointStamped::Builder::adoptPoint( + ::capnp::Orphan< ::mrp::geometry::Point>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Point> PointStamped::Builder::disownPoint() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Polygon::Reader::hasPoints() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Polygon::Builder::hasPoints() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Reader Polygon::Reader::getPoints() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Builder Polygon::Builder::getPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Polygon::Builder::setPoints( ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Builder Polygon::Builder::initPoints(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Polygon::Builder::adoptPoints( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>> Polygon::Builder::disownPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool PolygonStamped::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool PolygonStamped::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader PolygonStamped::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder PolygonStamped::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline PolygonStamped::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void PolygonStamped::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder PolygonStamped::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void PolygonStamped::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> PolygonStamped::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool PolygonStamped::Reader::hasPolygon() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool PolygonStamped::Builder::hasPolygon() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Polygon::Reader PolygonStamped::Reader::getPolygon() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Polygon>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Polygon::Builder PolygonStamped::Builder::getPolygon() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Polygon>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Polygon::Pipeline PolygonStamped::Pipeline::getPolygon() { + return ::mrp::geometry::Polygon::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void PolygonStamped::Builder::setPolygon( ::mrp::geometry::Polygon::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Polygon>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Polygon::Builder PolygonStamped::Builder::initPolygon() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Polygon>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void PolygonStamped::Builder::adoptPolygon( + ::capnp::Orphan< ::mrp::geometry::Polygon>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Polygon>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Polygon> PolygonStamped::Builder::disownPolygon() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Polygon>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Pose::Reader::hasPosition() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Pose::Builder::hasPosition() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Point::Reader Pose::Reader::getPosition() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Point::Builder Pose::Builder::getPosition() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Point::Pipeline Pose::Pipeline::getPosition() { + return ::mrp::geometry::Point::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Pose::Builder::setPosition( ::mrp::geometry::Point::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Point::Builder Pose::Builder::initPosition() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Pose::Builder::adoptPosition( + ::capnp::Orphan< ::mrp::geometry::Point>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Point> Pose::Builder::disownPosition() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Pose::Reader::hasOrientation() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Pose::Builder::hasOrientation() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Quaternion::Reader Pose::Reader::getOrientation() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Quaternion::Builder Pose::Builder::getOrientation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Quaternion::Pipeline Pose::Pipeline::getOrientation() { + return ::mrp::geometry::Quaternion::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void Pose::Builder::setOrientation( ::mrp::geometry::Quaternion::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Quaternion::Builder Pose::Builder::initOrientation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Pose::Builder::adoptOrientation( + ::capnp::Orphan< ::mrp::geometry::Quaternion>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Quaternion> Pose::Builder::disownOrientation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline double Pose2D::Reader::getX() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline double Pose2D::Builder::getX() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Pose2D::Builder::setX(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline double Pose2D::Reader::getY() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double Pose2D::Builder::getY() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Pose2D::Builder::setY(double value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline double Pose2D::Reader::getTheta() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline double Pose2D::Builder::getTheta() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Pose2D::Builder::setTheta(double value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool PoseArray::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool PoseArray::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader PoseArray::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder PoseArray::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline PoseArray::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void PoseArray::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder PoseArray::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void PoseArray::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> PoseArray::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool PoseArray::Reader::hasPoses() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool PoseArray::Builder::hasPoses() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>::Reader PoseArray::Reader::getPoses() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>::Builder PoseArray::Builder::getPoses() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void PoseArray::Builder::setPoses( ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>::Builder PoseArray::Builder::initPoses(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void PoseArray::Builder::adoptPoses( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>> PoseArray::Builder::disownPoses() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Pose, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool PoseStamped::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool PoseStamped::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader PoseStamped::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder PoseStamped::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline PoseStamped::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void PoseStamped::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder PoseStamped::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void PoseStamped::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> PoseStamped::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool PoseStamped::Reader::hasPose() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool PoseStamped::Builder::hasPose() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Pose::Reader PoseStamped::Reader::getPose() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Pose::Builder PoseStamped::Builder::getPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Pose::Pipeline PoseStamped::Pipeline::getPose() { + return ::mrp::geometry::Pose::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void PoseStamped::Builder::setPose( ::mrp::geometry::Pose::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Pose::Builder PoseStamped::Builder::initPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void PoseStamped::Builder::adoptPose( + ::capnp::Orphan< ::mrp::geometry::Pose>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Pose> PoseStamped::Builder::disownPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool PoseWithCovariance::Reader::hasPose() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool PoseWithCovariance::Builder::hasPose() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Pose::Reader PoseWithCovariance::Reader::getPose() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Pose::Builder PoseWithCovariance::Builder::getPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Pose::Pipeline PoseWithCovariance::Pipeline::getPose() { + return ::mrp::geometry::Pose::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void PoseWithCovariance::Builder::setPose( ::mrp::geometry::Pose::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Pose::Builder PoseWithCovariance::Builder::initPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void PoseWithCovariance::Builder::adoptPose( + ::capnp::Orphan< ::mrp::geometry::Pose>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Pose> PoseWithCovariance::Builder::disownPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool PoseWithCovariance::Reader::hasCovariance() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool PoseWithCovariance::Builder::hasCovariance() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader PoseWithCovariance::Reader::getCovariance() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder PoseWithCovariance::Builder::getCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void PoseWithCovariance::Builder::setCovariance( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void PoseWithCovariance::Builder::setCovariance(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder PoseWithCovariance::Builder::initCovariance(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void PoseWithCovariance::Builder::adoptCovariance( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> PoseWithCovariance::Builder::disownCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool PoseWithCovarianceStamped::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool PoseWithCovarianceStamped::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader PoseWithCovarianceStamped::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder PoseWithCovarianceStamped::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline PoseWithCovarianceStamped::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void PoseWithCovarianceStamped::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder PoseWithCovarianceStamped::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void PoseWithCovarianceStamped::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> PoseWithCovarianceStamped::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool PoseWithCovarianceStamped::Reader::hasPose() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool PoseWithCovarianceStamped::Builder::hasPose() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::PoseWithCovariance::Reader PoseWithCovarianceStamped::Reader::getPose() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::PoseWithCovariance>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::PoseWithCovariance::Builder PoseWithCovarianceStamped::Builder::getPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::PoseWithCovariance>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::PoseWithCovariance::Pipeline PoseWithCovarianceStamped::Pipeline::getPose() { + return ::mrp::geometry::PoseWithCovariance::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void PoseWithCovarianceStamped::Builder::setPose( ::mrp::geometry::PoseWithCovariance::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::PoseWithCovariance>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::PoseWithCovariance::Builder PoseWithCovarianceStamped::Builder::initPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::PoseWithCovariance>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void PoseWithCovarianceStamped::Builder::adoptPose( + ::capnp::Orphan< ::mrp::geometry::PoseWithCovariance>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::PoseWithCovariance>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::PoseWithCovariance> PoseWithCovarianceStamped::Builder::disownPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::PoseWithCovariance>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline double Quaternion::Reader::getX() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline double Quaternion::Builder::getX() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Quaternion::Builder::setX(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline double Quaternion::Reader::getY() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double Quaternion::Builder::getY() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Quaternion::Builder::setY(double value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline double Quaternion::Reader::getZ() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline double Quaternion::Builder::getZ() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Quaternion::Builder::setZ(double value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline double Quaternion::Reader::getW() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline double Quaternion::Builder::getW() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void Quaternion::Builder::setW(double value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline bool QuaternionStamped::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool QuaternionStamped::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader QuaternionStamped::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder QuaternionStamped::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline QuaternionStamped::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void QuaternionStamped::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder QuaternionStamped::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void QuaternionStamped::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> QuaternionStamped::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool QuaternionStamped::Reader::hasQuaternion() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool QuaternionStamped::Builder::hasQuaternion() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Quaternion::Reader QuaternionStamped::Reader::getQuaternion() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Quaternion::Builder QuaternionStamped::Builder::getQuaternion() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Quaternion::Pipeline QuaternionStamped::Pipeline::getQuaternion() { + return ::mrp::geometry::Quaternion::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void QuaternionStamped::Builder::setQuaternion( ::mrp::geometry::Quaternion::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Quaternion::Builder QuaternionStamped::Builder::initQuaternion() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void QuaternionStamped::Builder::adoptQuaternion( + ::capnp::Orphan< ::mrp::geometry::Quaternion>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Quaternion> QuaternionStamped::Builder::disownQuaternion() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Transform::Reader::hasTranslation() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Transform::Builder::hasTranslation() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Vector3::Reader Transform::Reader::getTranslation() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Vector3::Builder Transform::Builder::getTranslation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Vector3::Pipeline Transform::Pipeline::getTranslation() { + return ::mrp::geometry::Vector3::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Transform::Builder::setTranslation( ::mrp::geometry::Vector3::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Vector3::Builder Transform::Builder::initTranslation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Transform::Builder::adoptTranslation( + ::capnp::Orphan< ::mrp::geometry::Vector3>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Vector3> Transform::Builder::disownTranslation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Transform::Reader::hasRotation() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Transform::Builder::hasRotation() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Quaternion::Reader Transform::Reader::getRotation() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Quaternion::Builder Transform::Builder::getRotation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Quaternion::Pipeline Transform::Pipeline::getRotation() { + return ::mrp::geometry::Quaternion::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void Transform::Builder::setRotation( ::mrp::geometry::Quaternion::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Quaternion::Builder Transform::Builder::initRotation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Transform::Builder::adoptRotation( + ::capnp::Orphan< ::mrp::geometry::Quaternion>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Quaternion> Transform::Builder::disownRotation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool TransformStamped::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool TransformStamped::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader TransformStamped::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder TransformStamped::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline TransformStamped::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void TransformStamped::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder TransformStamped::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void TransformStamped::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> TransformStamped::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool TransformStamped::Reader::hasChildFrameId() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool TransformStamped::Builder::hasChildFrameId() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader TransformStamped::Reader::getChildFrameId() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder TransformStamped::Builder::getChildFrameId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void TransformStamped::Builder::setChildFrameId( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder TransformStamped::Builder::initChildFrameId(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void TransformStamped::Builder::adoptChildFrameId( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> TransformStamped::Builder::disownChildFrameId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool TransformStamped::Reader::hasTransform() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool TransformStamped::Builder::hasTransform() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Transform::Reader TransformStamped::Reader::getTransform() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Transform>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Transform::Builder TransformStamped::Builder::getTransform() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Transform>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Transform::Pipeline TransformStamped::Pipeline::getTransform() { + return ::mrp::geometry::Transform::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void TransformStamped::Builder::setTransform( ::mrp::geometry::Transform::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Transform>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Transform::Builder TransformStamped::Builder::initTransform() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Transform>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void TransformStamped::Builder::adoptTransform( + ::capnp::Orphan< ::mrp::geometry::Transform>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Transform>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Transform> TransformStamped::Builder::disownTransform() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Transform>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool Twist::Reader::hasLinear() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Twist::Builder::hasLinear() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Vector3::Reader Twist::Reader::getLinear() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Vector3::Builder Twist::Builder::getLinear() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Vector3::Pipeline Twist::Pipeline::getLinear() { + return ::mrp::geometry::Vector3::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Twist::Builder::setLinear( ::mrp::geometry::Vector3::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Vector3::Builder Twist::Builder::initLinear() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Twist::Builder::adoptLinear( + ::capnp::Orphan< ::mrp::geometry::Vector3>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Vector3> Twist::Builder::disownLinear() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Twist::Reader::hasAngular() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Twist::Builder::hasAngular() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Vector3::Reader Twist::Reader::getAngular() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Vector3::Builder Twist::Builder::getAngular() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Vector3::Pipeline Twist::Pipeline::getAngular() { + return ::mrp::geometry::Vector3::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void Twist::Builder::setAngular( ::mrp::geometry::Vector3::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Vector3::Builder Twist::Builder::initAngular() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Twist::Builder::adoptAngular( + ::capnp::Orphan< ::mrp::geometry::Vector3>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Vector3> Twist::Builder::disownAngular() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool TwistStamped::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool TwistStamped::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader TwistStamped::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder TwistStamped::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline TwistStamped::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void TwistStamped::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder TwistStamped::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void TwistStamped::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> TwistStamped::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool TwistStamped::Reader::hasTwist() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool TwistStamped::Builder::hasTwist() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Twist::Reader TwistStamped::Reader::getTwist() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Twist>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Twist::Builder TwistStamped::Builder::getTwist() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Twist>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Twist::Pipeline TwistStamped::Pipeline::getTwist() { + return ::mrp::geometry::Twist::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void TwistStamped::Builder::setTwist( ::mrp::geometry::Twist::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Twist>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Twist::Builder TwistStamped::Builder::initTwist() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Twist>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void TwistStamped::Builder::adoptTwist( + ::capnp::Orphan< ::mrp::geometry::Twist>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Twist>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Twist> TwistStamped::Builder::disownTwist() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Twist>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool TwistWithCovariance::Reader::hasTwist() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool TwistWithCovariance::Builder::hasTwist() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Twist::Reader TwistWithCovariance::Reader::getTwist() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Twist>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Twist::Builder TwistWithCovariance::Builder::getTwist() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Twist>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Twist::Pipeline TwistWithCovariance::Pipeline::getTwist() { + return ::mrp::geometry::Twist::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void TwistWithCovariance::Builder::setTwist( ::mrp::geometry::Twist::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Twist>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Twist::Builder TwistWithCovariance::Builder::initTwist() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Twist>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void TwistWithCovariance::Builder::adoptTwist( + ::capnp::Orphan< ::mrp::geometry::Twist>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Twist>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Twist> TwistWithCovariance::Builder::disownTwist() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Twist>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool TwistWithCovariance::Reader::hasCovariance() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool TwistWithCovariance::Builder::hasCovariance() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader TwistWithCovariance::Reader::getCovariance() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder TwistWithCovariance::Builder::getCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void TwistWithCovariance::Builder::setCovariance( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void TwistWithCovariance::Builder::setCovariance(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder TwistWithCovariance::Builder::initCovariance(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void TwistWithCovariance::Builder::adoptCovariance( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> TwistWithCovariance::Builder::disownCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool TwistWithCovarianceStamped::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool TwistWithCovarianceStamped::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader TwistWithCovarianceStamped::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder TwistWithCovarianceStamped::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline TwistWithCovarianceStamped::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void TwistWithCovarianceStamped::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder TwistWithCovarianceStamped::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void TwistWithCovarianceStamped::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> TwistWithCovarianceStamped::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool TwistWithCovarianceStamped::Reader::hasTwist() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool TwistWithCovarianceStamped::Builder::hasTwist() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::TwistWithCovariance::Reader TwistWithCovarianceStamped::Reader::getTwist() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::TwistWithCovariance>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::TwistWithCovariance::Builder TwistWithCovarianceStamped::Builder::getTwist() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::TwistWithCovariance>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::TwistWithCovariance::Pipeline TwistWithCovarianceStamped::Pipeline::getTwist() { + return ::mrp::geometry::TwistWithCovariance::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void TwistWithCovarianceStamped::Builder::setTwist( ::mrp::geometry::TwistWithCovariance::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::TwistWithCovariance>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::TwistWithCovariance::Builder TwistWithCovarianceStamped::Builder::initTwist() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::TwistWithCovariance>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void TwistWithCovarianceStamped::Builder::adoptTwist( + ::capnp::Orphan< ::mrp::geometry::TwistWithCovariance>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::TwistWithCovariance>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::TwistWithCovariance> TwistWithCovarianceStamped::Builder::disownTwist() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::TwistWithCovariance>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline double Vector3::Reader::getX() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline double Vector3::Builder::getX() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Vector3::Builder::setX(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline double Vector3::Reader::getY() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double Vector3::Builder::getY() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Vector3::Builder::setY(double value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline double Vector3::Reader::getZ() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline double Vector3::Builder::getZ() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Vector3::Builder::setZ(double value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Vector3Stamped::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Vector3Stamped::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader Vector3Stamped::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder Vector3Stamped::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline Vector3Stamped::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Vector3Stamped::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder Vector3Stamped::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Vector3Stamped::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> Vector3Stamped::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Vector3Stamped::Reader::hasVector() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Vector3Stamped::Builder::hasVector() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Vector3::Reader Vector3Stamped::Reader::getVector() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Vector3::Builder Vector3Stamped::Builder::getVector() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Vector3::Pipeline Vector3Stamped::Pipeline::getVector() { + return ::mrp::geometry::Vector3::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void Vector3Stamped::Builder::setVector( ::mrp::geometry::Vector3::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Vector3::Builder Vector3Stamped::Builder::initVector() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Vector3Stamped::Builder::adoptVector( + ::capnp::Orphan< ::mrp::geometry::Vector3>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Vector3> Vector3Stamped::Builder::disownVector() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Wrench::Reader::hasForce() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Wrench::Builder::hasForce() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Vector3::Reader Wrench::Reader::getForce() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Vector3::Builder Wrench::Builder::getForce() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Vector3::Pipeline Wrench::Pipeline::getForce() { + return ::mrp::geometry::Vector3::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Wrench::Builder::setForce( ::mrp::geometry::Vector3::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Vector3::Builder Wrench::Builder::initForce() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Wrench::Builder::adoptForce( + ::capnp::Orphan< ::mrp::geometry::Vector3>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Vector3> Wrench::Builder::disownForce() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Wrench::Reader::hasTorque() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Wrench::Builder::hasTorque() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Vector3::Reader Wrench::Reader::getTorque() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Vector3::Builder Wrench::Builder::getTorque() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Vector3::Pipeline Wrench::Pipeline::getTorque() { + return ::mrp::geometry::Vector3::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void Wrench::Builder::setTorque( ::mrp::geometry::Vector3::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Vector3::Builder Wrench::Builder::initTorque() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Wrench::Builder::adoptTorque( + ::capnp::Orphan< ::mrp::geometry::Vector3>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Vector3> Wrench::Builder::disownTorque() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool WrenchStamped::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool WrenchStamped::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader WrenchStamped::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder WrenchStamped::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline WrenchStamped::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void WrenchStamped::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder WrenchStamped::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void WrenchStamped::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> WrenchStamped::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool WrenchStamped::Reader::hasWrench() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool WrenchStamped::Builder::hasWrench() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Wrench::Reader WrenchStamped::Reader::getWrench() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Wrench>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Wrench::Builder WrenchStamped::Builder::getWrench() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Wrench>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Wrench::Pipeline WrenchStamped::Pipeline::getWrench() { + return ::mrp::geometry::Wrench::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void WrenchStamped::Builder::setWrench( ::mrp::geometry::Wrench::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Wrench>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Wrench::Builder WrenchStamped::Builder::initWrench() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Wrench>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void WrenchStamped::Builder::adoptWrench( + ::capnp::Orphan< ::mrp::geometry::Wrench>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Wrench>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Wrench> WrenchStamped::Builder::disownWrench() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Wrench>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +} // namespace +} // namespace + +CAPNP_END_HEADER + diff --git a/msg/src/fairomsg/cpp/nav_msgs.capnp.c++ b/msg/src/fairomsg/cpp/nav_msgs.capnp.c++ new file mode 100644 index 0000000000..5fdf4ff456 --- /dev/null +++ b/msg/src/fairomsg/cpp/nav_msgs.capnp.c++ @@ -0,0 +1,987 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: nav_msgs.capnp + +#include "nav_msgs.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<66> b_a2ac7ce134b92ab5 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 181, 42, 185, 52, 225, 124, 172, 162, + 19, 0, 0, 0, 1, 0, 0, 0, + 240, 97, 33, 100, 214, 141, 162, 197, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 110, 97, 118, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 71, 101, 116, 77, 97, + 112, 65, 99, 116, 105, 111, 110, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 0, 0, 0, 3, 0, 1, 0, + 88, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 0, 0, 0, 3, 0, 1, 0, + 96, 0, 0, 0, 2, 0, 1, 0, + 97, 99, 116, 105, 111, 110, 71, 111, + 97, 108, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 248, 92, 3, 168, 2, 17, 93, 144, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 105, 111, 110, 82, 101, + 115, 117, 108, 116, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 201, 97, 66, 111, 181, 215, 117, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 105, 111, 110, 70, 101, + 101, 100, 98, 97, 99, 107, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 229, 219, 152, 181, 162, 106, 252, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a2ac7ce134b92ab5 = b_a2ac7ce134b92ab5.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a2ac7ce134b92ab5[] = { + &s_905d1102a8035cf8, + &s_bf75d7b56f4261c9, + &s_bffc6aa2b598dbe5, +}; +static const uint16_t m_a2ac7ce134b92ab5[] = {2, 0, 1}; +static const uint16_t i_a2ac7ce134b92ab5[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_a2ac7ce134b92ab5 = { + 0xa2ac7ce134b92ab5, b_a2ac7ce134b92ab5.words, 66, d_a2ac7ce134b92ab5, m_a2ac7ce134b92ab5, + 3, 3, i_a2ac7ce134b92ab5, nullptr, nullptr, { &s_a2ac7ce134b92ab5, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<65> b_bffc6aa2b598dbe5 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 229, 219, 152, 181, 162, 106, 252, 191, + 19, 0, 0, 0, 1, 0, 0, 0, + 240, 97, 33, 100, 214, 141, 162, 197, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 66, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 110, 97, 118, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 71, 101, 116, 77, 97, + 112, 65, 99, 116, 105, 111, 110, 70, + 101, 101, 100, 98, 97, 99, 107, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 0, 0, 0, 3, 0, 1, 0, + 88, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 101, 101, 100, 98, 97, 99, 107, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 178, 47, 213, 154, 130, 85, 204, 196, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bffc6aa2b598dbe5 = b_bffc6aa2b598dbe5.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_bffc6aa2b598dbe5[] = { + &s_bf587c1bf845ce13, + &s_c4cc55829ad52fb2, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_bffc6aa2b598dbe5[] = {2, 0, 1}; +static const uint16_t i_bffc6aa2b598dbe5[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_bffc6aa2b598dbe5 = { + 0xbffc6aa2b598dbe5, b_bffc6aa2b598dbe5.words, 65, d_bffc6aa2b598dbe5, m_bffc6aa2b598dbe5, + 3, 3, i_bffc6aa2b598dbe5, nullptr, nullptr, { &s_bffc6aa2b598dbe5, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<64> b_905d1102a8035cf8 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 248, 92, 3, 168, 2, 17, 93, 144, + 19, 0, 0, 0, 1, 0, 0, 0, + 240, 97, 33, 100, 214, 141, 162, 197, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 110, 97, 118, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 71, 101, 116, 77, 97, + 112, 65, 99, 116, 105, 111, 110, 71, + 111, 97, 108, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 111, 97, 108, 73, 100, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 185, 173, 145, 33, 215, 117, 118, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 111, 97, 108, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 217, 190, 74, 152, 228, 31, 122, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_905d1102a8035cf8 = b_905d1102a8035cf8.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_905d1102a8035cf8[] = { + &s_cf7675d72191adb9, + &s_cf9a8bcf03922937, + &s_f57a1fe4984abed9, +}; +static const uint16_t m_905d1102a8035cf8[] = {2, 1, 0}; +static const uint16_t i_905d1102a8035cf8[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_905d1102a8035cf8 = { + 0x905d1102a8035cf8, b_905d1102a8035cf8.words, 64, d_905d1102a8035cf8, m_905d1102a8035cf8, + 3, 3, i_905d1102a8035cf8, nullptr, nullptr, { &s_905d1102a8035cf8, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<64> b_bf75d7b56f4261c9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 201, 97, 66, 111, 181, 215, 117, 191, + 19, 0, 0, 0, 1, 0, 0, 0, + 240, 97, 33, 100, 214, 141, 162, 197, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 110, 97, 118, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 71, 101, 116, 77, 97, + 112, 65, 99, 116, 105, 111, 110, 82, + 101, 115, 117, 108, 116, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 19, 206, 69, 248, 27, 124, 88, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 115, 117, 108, 116, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 187, 131, 23, 148, 57, 153, 186, 192, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bf75d7b56f4261c9 = b_bf75d7b56f4261c9.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_bf75d7b56f4261c9[] = { + &s_bf587c1bf845ce13, + &s_c0ba9939941783bb, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_bf75d7b56f4261c9[] = {0, 2, 1}; +static const uint16_t i_bf75d7b56f4261c9[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_bf75d7b56f4261c9 = { + 0xbf75d7b56f4261c9, b_bf75d7b56f4261c9.words, 64, d_bf75d7b56f4261c9, m_bf75d7b56f4261c9, + 3, 3, i_bf75d7b56f4261c9, nullptr, nullptr, { &s_bf75d7b56f4261c9, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<18> b_c4cc55829ad52fb2 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 178, 47, 213, 154, 130, 85, 204, 196, + 19, 0, 0, 0, 1, 0, 0, 0, + 240, 97, 33, 100, 214, 141, 162, 197, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 110, 97, 118, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 71, 101, 116, 77, 97, + 112, 70, 101, 101, 100, 98, 97, 99, + 107, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, } +}; +::capnp::word const* const bp_c4cc55829ad52fb2 = b_c4cc55829ad52fb2.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c4cc55829ad52fb2 = { + 0xc4cc55829ad52fb2, b_c4cc55829ad52fb2.words, 18, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c4cc55829ad52fb2, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<17> b_f57a1fe4984abed9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 217, 190, 74, 152, 228, 31, 122, 245, + 19, 0, 0, 0, 1, 0, 0, 0, + 240, 97, 33, 100, 214, 141, 162, 197, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 110, 97, 118, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 71, 101, 116, 77, 97, + 112, 71, 111, 97, 108, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, } +}; +::capnp::word const* const bp_f57a1fe4984abed9 = b_f57a1fe4984abed9.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_f57a1fe4984abed9 = { + 0xf57a1fe4984abed9, b_f57a1fe4984abed9.words, 17, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_f57a1fe4984abed9, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<33> b_c0ba9939941783bb = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 187, 131, 23, 148, 57, 153, 186, 192, + 19, 0, 0, 0, 1, 0, 0, 0, + 240, 97, 33, 100, 214, 141, 162, 197, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 110, 97, 118, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 71, 101, 116, 77, 97, + 112, 82, 101, 115, 117, 108, 116, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 20, 0, 0, 0, 2, 0, 1, 0, + 109, 97, 112, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 189, 227, 167, 114, 65, 61, 182, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c0ba9939941783bb = b_c0ba9939941783bb.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c0ba9939941783bb[] = { + &s_bdb63d4172a7e3bd, +}; +static const uint16_t m_c0ba9939941783bb[] = {0}; +static const uint16_t i_c0ba9939941783bb[] = {0}; +const ::capnp::_::RawSchema s_c0ba9939941783bb = { + 0xc0ba9939941783bb, b_c0ba9939941783bb.words, 33, d_c0ba9939941783bb, m_c0ba9939941783bb, + 1, 1, i_c0ba9939941783bb, nullptr, nullptr, { &s_c0ba9939941783bb, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<84> b_c8b077ab0ba7f1ab = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 171, 241, 167, 11, 171, 119, 176, 200, + 19, 0, 0, 0, 1, 0, 1, 0, + 240, 97, 33, 100, 214, 141, 162, 197, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 110, 97, 118, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 71, 114, 105, 100, 67, + 101, 108, 108, 115, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 101, 108, 108, 87, 105, 100, 116, + 104, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 101, 108, 108, 72, 101, 105, 103, + 104, 116, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 101, 108, 108, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 68, 59, 77, 248, 154, 89, 171, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c8b077ab0ba7f1ab = b_c8b077ab0ba7f1ab.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c8b077ab0ba7f1ab[] = { + &s_cf9a8bcf03922937, + &s_ebab599af84d3b44, +}; +static const uint16_t m_c8b077ab0ba7f1ab[] = {2, 1, 3, 0}; +static const uint16_t i_c8b077ab0ba7f1ab[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_c8b077ab0ba7f1ab = { + 0xc8b077ab0ba7f1ab, b_c8b077ab0ba7f1ab.words, 84, d_c8b077ab0ba7f1ab, m_c8b077ab0ba7f1ab, + 2, 4, i_c8b077ab0ba7f1ab, nullptr, nullptr, { &s_c8b077ab0ba7f1ab, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<95> b_e83746019d1a2700 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 0, 39, 26, 157, 1, 70, 55, 232, + 19, 0, 0, 0, 1, 0, 2, 0, + 240, 97, 33, 100, 214, 141, 162, 197, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 110, 97, 118, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 77, 97, 112, 77, 101, + 116, 97, 68, 97, 116, 97, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 0, 0, 0, 3, 0, 1, 0, + 152, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 0, 0, 0, 3, 0, 1, 0, + 156, 0, 0, 0, 2, 0, 1, 0, + 109, 97, 112, 76, 111, 97, 100, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 79, 12, 85, 207, 4, 92, 190, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 115, 111, 108, 117, 116, 105, + 111, 110, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 100, 116, 104, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 105, 103, 104, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 103, 105, 110, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 168, 139, 201, 190, 163, 197, 246, 170, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e83746019d1a2700 = b_e83746019d1a2700.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_e83746019d1a2700[] = { + &s_aaf6c5a3bec98ba8, + &s_ebbe5c04cf550c4f, +}; +static const uint16_t m_e83746019d1a2700[] = {3, 0, 4, 1, 2}; +static const uint16_t i_e83746019d1a2700[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_e83746019d1a2700 = { + 0xe83746019d1a2700, b_e83746019d1a2700.words, 95, d_e83746019d1a2700, m_e83746019d1a2700, + 2, 5, i_e83746019d1a2700, nullptr, nullptr, { &s_e83746019d1a2700, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<64> b_bdb63d4172a7e3bd = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 189, 227, 167, 114, 65, 61, 182, 189, + 19, 0, 0, 0, 1, 0, 0, 0, + 240, 97, 33, 100, 214, 141, 162, 197, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 110, 97, 118, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 79, 99, 99, 117, 112, + 97, 110, 99, 121, 71, 114, 105, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 102, 111, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 39, 26, 157, 1, 70, 55, 232, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bdb63d4172a7e3bd = b_bdb63d4172a7e3bd.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_bdb63d4172a7e3bd[] = { + &s_cf9a8bcf03922937, + &s_e83746019d1a2700, +}; +static const uint16_t m_bdb63d4172a7e3bd[] = {2, 0, 1}; +static const uint16_t i_bdb63d4172a7e3bd[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_bdb63d4172a7e3bd = { + 0xbdb63d4172a7e3bd, b_bdb63d4172a7e3bd.words, 64, d_bdb63d4172a7e3bd, m_bdb63d4172a7e3bd, + 2, 3, i_bdb63d4172a7e3bd, nullptr, nullptr, { &s_bdb63d4172a7e3bd, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<79> b_c3c4315f099df0c3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 195, 240, 157, 9, 95, 49, 196, 195, + 19, 0, 0, 0, 1, 0, 0, 0, + 240, 97, 33, 100, 214, 141, 162, 197, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 226, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 110, 97, 118, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 79, 100, 111, 109, 101, + 116, 114, 121, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 104, 105, 108, 100, 70, 114, 97, + 109, 101, 73, 100, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 86, 49, 95, 216, 132, 41, 24, 250, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 119, 105, 115, 116, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 29, 39, 188, 111, 205, 51, 215, 243, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c3c4315f099df0c3 = b_c3c4315f099df0c3.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c3c4315f099df0c3[] = { + &s_cf9a8bcf03922937, + &s_f3d733cd6fbc271d, + &s_fa182984d85f3156, +}; +static const uint16_t m_c3c4315f099df0c3[] = {1, 0, 2, 3}; +static const uint16_t i_c3c4315f099df0c3[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_c3c4315f099df0c3 = { + 0xc3c4315f099df0c3, b_c3c4315f099df0c3.words, 79, d_c3c4315f099df0c3, m_c3c4315f099df0c3, + 3, 4, i_c3c4315f099df0c3, nullptr, nullptr, { &s_c3c4315f099df0c3, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<51> b_f17f4bc183b07e30 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 48, 126, 176, 131, 193, 75, 127, 241, + 19, 0, 0, 0, 1, 0, 0, 0, + 240, 97, 33, 100, 214, 141, 162, 197, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 194, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 110, 97, 118, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 80, 97, 116, 104, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 94, 232, 95, 184, 78, 20, 127, 158, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f17f4bc183b07e30 = b_f17f4bc183b07e30.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f17f4bc183b07e30[] = { + &s_9e7f144eb85fe85e, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_f17f4bc183b07e30[] = {0, 1}; +static const uint16_t i_f17f4bc183b07e30[] = {0, 1}; +const ::capnp::_::RawSchema s_f17f4bc183b07e30 = { + 0xf17f4bc183b07e30, b_f17f4bc183b07e30.words, 51, d_f17f4bc183b07e30, m_f17f4bc183b07e30, + 2, 2, i_f17f4bc183b07e30, nullptr, nullptr, { &s_f17f4bc183b07e30, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace mrp { +namespace nav { + +// GetMapAction +constexpr uint16_t GetMapAction::_capnpPrivate::dataWordSize; +constexpr uint16_t GetMapAction::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind GetMapAction::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GetMapAction::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// GetMapActionFeedback +constexpr uint16_t GetMapActionFeedback::_capnpPrivate::dataWordSize; +constexpr uint16_t GetMapActionFeedback::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind GetMapActionFeedback::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GetMapActionFeedback::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// GetMapActionGoal +constexpr uint16_t GetMapActionGoal::_capnpPrivate::dataWordSize; +constexpr uint16_t GetMapActionGoal::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind GetMapActionGoal::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GetMapActionGoal::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// GetMapActionResult +constexpr uint16_t GetMapActionResult::_capnpPrivate::dataWordSize; +constexpr uint16_t GetMapActionResult::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind GetMapActionResult::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GetMapActionResult::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// GetMapFeedback +constexpr uint16_t GetMapFeedback::_capnpPrivate::dataWordSize; +constexpr uint16_t GetMapFeedback::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind GetMapFeedback::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GetMapFeedback::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// GetMapGoal +constexpr uint16_t GetMapGoal::_capnpPrivate::dataWordSize; +constexpr uint16_t GetMapGoal::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind GetMapGoal::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GetMapGoal::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// GetMapResult +constexpr uint16_t GetMapResult::_capnpPrivate::dataWordSize; +constexpr uint16_t GetMapResult::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind GetMapResult::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GetMapResult::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// GridCells +constexpr uint16_t GridCells::_capnpPrivate::dataWordSize; +constexpr uint16_t GridCells::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind GridCells::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GridCells::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// MapMetaData +constexpr uint16_t MapMetaData::_capnpPrivate::dataWordSize; +constexpr uint16_t MapMetaData::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind MapMetaData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* MapMetaData::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// OccupancyGrid +constexpr uint16_t OccupancyGrid::_capnpPrivate::dataWordSize; +constexpr uint16_t OccupancyGrid::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind OccupancyGrid::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* OccupancyGrid::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Odometry +constexpr uint16_t Odometry::_capnpPrivate::dataWordSize; +constexpr uint16_t Odometry::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Odometry::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Odometry::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Path +constexpr uint16_t Path::_capnpPrivate::dataWordSize; +constexpr uint16_t Path::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Path::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Path::_capnpPrivate::schema; +#endif // !CAPNP_LITE + + +} // namespace +} // namespace + diff --git a/msg/src/fairomsg/cpp/nav_msgs.capnp.h b/msg/src/fairomsg/cpp/nav_msgs.capnp.h new file mode 100644 index 0000000000..b9363c987a --- /dev/null +++ b/msg/src/fairomsg/cpp/nav_msgs.capnp.h @@ -0,0 +1,2452 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: nav_msgs.capnp + +#pragma once + +#include +#include + +#if CAPNP_VERSION != 9001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + +#include "actionlib_msgs.capnp.h" +#include "geometry_msgs.capnp.h" +#include "std_msgs.capnp.h" + +CAPNP_BEGIN_HEADER + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(a2ac7ce134b92ab5); +CAPNP_DECLARE_SCHEMA(bffc6aa2b598dbe5); +CAPNP_DECLARE_SCHEMA(905d1102a8035cf8); +CAPNP_DECLARE_SCHEMA(bf75d7b56f4261c9); +CAPNP_DECLARE_SCHEMA(c4cc55829ad52fb2); +CAPNP_DECLARE_SCHEMA(f57a1fe4984abed9); +CAPNP_DECLARE_SCHEMA(c0ba9939941783bb); +CAPNP_DECLARE_SCHEMA(c8b077ab0ba7f1ab); +CAPNP_DECLARE_SCHEMA(e83746019d1a2700); +CAPNP_DECLARE_SCHEMA(bdb63d4172a7e3bd); +CAPNP_DECLARE_SCHEMA(c3c4315f099df0c3); +CAPNP_DECLARE_SCHEMA(f17f4bc183b07e30); + +} // namespace schemas +} // namespace capnp + +namespace mrp { +namespace nav { + +struct GetMapAction { + GetMapAction() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a2ac7ce134b92ab5, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct GetMapActionFeedback { + GetMapActionFeedback() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bffc6aa2b598dbe5, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct GetMapActionGoal { + GetMapActionGoal() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(905d1102a8035cf8, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct GetMapActionResult { + GetMapActionResult() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bf75d7b56f4261c9, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct GetMapFeedback { + GetMapFeedback() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c4cc55829ad52fb2, 0, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct GetMapGoal { + GetMapGoal() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f57a1fe4984abed9, 0, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct GetMapResult { + GetMapResult() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c0ba9939941783bb, 0, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct GridCells { + GridCells() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c8b077ab0ba7f1ab, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct MapMetaData { + MapMetaData() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e83746019d1a2700, 2, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct OccupancyGrid { + OccupancyGrid() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bdb63d4172a7e3bd, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Odometry { + Odometry() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c3c4315f099df0c3, 0, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Path { + Path() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f17f4bc183b07e30, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class GetMapAction::Reader { +public: + typedef GetMapAction Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasActionGoal() const; + inline ::mrp::nav::GetMapActionGoal::Reader getActionGoal() const; + + inline bool hasActionResult() const; + inline ::mrp::nav::GetMapActionResult::Reader getActionResult() const; + + inline bool hasActionFeedback() const; + inline ::mrp::nav::GetMapActionFeedback::Reader getActionFeedback() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class GetMapAction::Builder { +public: + typedef GetMapAction Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasActionGoal(); + inline ::mrp::nav::GetMapActionGoal::Builder getActionGoal(); + inline void setActionGoal( ::mrp::nav::GetMapActionGoal::Reader value); + inline ::mrp::nav::GetMapActionGoal::Builder initActionGoal(); + inline void adoptActionGoal(::capnp::Orphan< ::mrp::nav::GetMapActionGoal>&& value); + inline ::capnp::Orphan< ::mrp::nav::GetMapActionGoal> disownActionGoal(); + + inline bool hasActionResult(); + inline ::mrp::nav::GetMapActionResult::Builder getActionResult(); + inline void setActionResult( ::mrp::nav::GetMapActionResult::Reader value); + inline ::mrp::nav::GetMapActionResult::Builder initActionResult(); + inline void adoptActionResult(::capnp::Orphan< ::mrp::nav::GetMapActionResult>&& value); + inline ::capnp::Orphan< ::mrp::nav::GetMapActionResult> disownActionResult(); + + inline bool hasActionFeedback(); + inline ::mrp::nav::GetMapActionFeedback::Builder getActionFeedback(); + inline void setActionFeedback( ::mrp::nav::GetMapActionFeedback::Reader value); + inline ::mrp::nav::GetMapActionFeedback::Builder initActionFeedback(); + inline void adoptActionFeedback(::capnp::Orphan< ::mrp::nav::GetMapActionFeedback>&& value); + inline ::capnp::Orphan< ::mrp::nav::GetMapActionFeedback> disownActionFeedback(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class GetMapAction::Pipeline { +public: + typedef GetMapAction Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::nav::GetMapActionGoal::Pipeline getActionGoal(); + inline ::mrp::nav::GetMapActionResult::Pipeline getActionResult(); + inline ::mrp::nav::GetMapActionFeedback::Pipeline getActionFeedback(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class GetMapActionFeedback::Reader { +public: + typedef GetMapActionFeedback Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasStatus() const; + inline ::mrp::actionlib::GoalStatus::Reader getStatus() const; + + inline bool hasFeedback() const; + inline ::mrp::nav::GetMapFeedback::Reader getFeedback() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class GetMapActionFeedback::Builder { +public: + typedef GetMapActionFeedback Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasStatus(); + inline ::mrp::actionlib::GoalStatus::Builder getStatus(); + inline void setStatus( ::mrp::actionlib::GoalStatus::Reader value); + inline ::mrp::actionlib::GoalStatus::Builder initStatus(); + inline void adoptStatus(::capnp::Orphan< ::mrp::actionlib::GoalStatus>&& value); + inline ::capnp::Orphan< ::mrp::actionlib::GoalStatus> disownStatus(); + + inline bool hasFeedback(); + inline ::mrp::nav::GetMapFeedback::Builder getFeedback(); + inline void setFeedback( ::mrp::nav::GetMapFeedback::Reader value); + inline ::mrp::nav::GetMapFeedback::Builder initFeedback(); + inline void adoptFeedback(::capnp::Orphan< ::mrp::nav::GetMapFeedback>&& value); + inline ::capnp::Orphan< ::mrp::nav::GetMapFeedback> disownFeedback(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class GetMapActionFeedback::Pipeline { +public: + typedef GetMapActionFeedback Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::actionlib::GoalStatus::Pipeline getStatus(); + inline ::mrp::nav::GetMapFeedback::Pipeline getFeedback(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class GetMapActionGoal::Reader { +public: + typedef GetMapActionGoal Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasGoalId() const; + inline ::mrp::actionlib::GoalID::Reader getGoalId() const; + + inline bool hasGoal() const; + inline ::mrp::nav::GetMapGoal::Reader getGoal() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class GetMapActionGoal::Builder { +public: + typedef GetMapActionGoal Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasGoalId(); + inline ::mrp::actionlib::GoalID::Builder getGoalId(); + inline void setGoalId( ::mrp::actionlib::GoalID::Reader value); + inline ::mrp::actionlib::GoalID::Builder initGoalId(); + inline void adoptGoalId(::capnp::Orphan< ::mrp::actionlib::GoalID>&& value); + inline ::capnp::Orphan< ::mrp::actionlib::GoalID> disownGoalId(); + + inline bool hasGoal(); + inline ::mrp::nav::GetMapGoal::Builder getGoal(); + inline void setGoal( ::mrp::nav::GetMapGoal::Reader value); + inline ::mrp::nav::GetMapGoal::Builder initGoal(); + inline void adoptGoal(::capnp::Orphan< ::mrp::nav::GetMapGoal>&& value); + inline ::capnp::Orphan< ::mrp::nav::GetMapGoal> disownGoal(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class GetMapActionGoal::Pipeline { +public: + typedef GetMapActionGoal Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::actionlib::GoalID::Pipeline getGoalId(); + inline ::mrp::nav::GetMapGoal::Pipeline getGoal(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class GetMapActionResult::Reader { +public: + typedef GetMapActionResult Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasStatus() const; + inline ::mrp::actionlib::GoalStatus::Reader getStatus() const; + + inline bool hasResult() const; + inline ::mrp::nav::GetMapResult::Reader getResult() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class GetMapActionResult::Builder { +public: + typedef GetMapActionResult Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasStatus(); + inline ::mrp::actionlib::GoalStatus::Builder getStatus(); + inline void setStatus( ::mrp::actionlib::GoalStatus::Reader value); + inline ::mrp::actionlib::GoalStatus::Builder initStatus(); + inline void adoptStatus(::capnp::Orphan< ::mrp::actionlib::GoalStatus>&& value); + inline ::capnp::Orphan< ::mrp::actionlib::GoalStatus> disownStatus(); + + inline bool hasResult(); + inline ::mrp::nav::GetMapResult::Builder getResult(); + inline void setResult( ::mrp::nav::GetMapResult::Reader value); + inline ::mrp::nav::GetMapResult::Builder initResult(); + inline void adoptResult(::capnp::Orphan< ::mrp::nav::GetMapResult>&& value); + inline ::capnp::Orphan< ::mrp::nav::GetMapResult> disownResult(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class GetMapActionResult::Pipeline { +public: + typedef GetMapActionResult Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::actionlib::GoalStatus::Pipeline getStatus(); + inline ::mrp::nav::GetMapResult::Pipeline getResult(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class GetMapFeedback::Reader { +public: + typedef GetMapFeedback Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class GetMapFeedback::Builder { +public: + typedef GetMapFeedback Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class GetMapFeedback::Pipeline { +public: + typedef GetMapFeedback Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class GetMapGoal::Reader { +public: + typedef GetMapGoal Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class GetMapGoal::Builder { +public: + typedef GetMapGoal Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class GetMapGoal::Pipeline { +public: + typedef GetMapGoal Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class GetMapResult::Reader { +public: + typedef GetMapResult Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasMap() const; + inline ::mrp::nav::OccupancyGrid::Reader getMap() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class GetMapResult::Builder { +public: + typedef GetMapResult Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasMap(); + inline ::mrp::nav::OccupancyGrid::Builder getMap(); + inline void setMap( ::mrp::nav::OccupancyGrid::Reader value); + inline ::mrp::nav::OccupancyGrid::Builder initMap(); + inline void adoptMap(::capnp::Orphan< ::mrp::nav::OccupancyGrid>&& value); + inline ::capnp::Orphan< ::mrp::nav::OccupancyGrid> disownMap(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class GetMapResult::Pipeline { +public: + typedef GetMapResult Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::nav::OccupancyGrid::Pipeline getMap(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class GridCells::Reader { +public: + typedef GridCells Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline float getCellWidth() const; + + inline float getCellHeight() const; + + inline bool hasCells() const; + inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader getCells() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class GridCells::Builder { +public: + typedef GridCells Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline float getCellWidth(); + inline void setCellWidth(float value); + + inline float getCellHeight(); + inline void setCellHeight(float value); + + inline bool hasCells(); + inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder getCells(); + inline void setCells( ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder initCells(unsigned int size); + inline void adoptCells(::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>> disownCells(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class GridCells::Pipeline { +public: + typedef GridCells Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class MapMetaData::Reader { +public: + typedef MapMetaData Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasMapLoadTime() const; + inline ::mrp::std::Time::Reader getMapLoadTime() const; + + inline float getResolution() const; + + inline ::uint32_t getWidth() const; + + inline ::uint32_t getHeight() const; + + inline bool hasOrigin() const; + inline ::mrp::geometry::Pose::Reader getOrigin() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class MapMetaData::Builder { +public: + typedef MapMetaData Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasMapLoadTime(); + inline ::mrp::std::Time::Builder getMapLoadTime(); + inline void setMapLoadTime( ::mrp::std::Time::Reader value); + inline ::mrp::std::Time::Builder initMapLoadTime(); + inline void adoptMapLoadTime(::capnp::Orphan< ::mrp::std::Time>&& value); + inline ::capnp::Orphan< ::mrp::std::Time> disownMapLoadTime(); + + inline float getResolution(); + inline void setResolution(float value); + + inline ::uint32_t getWidth(); + inline void setWidth( ::uint32_t value); + + inline ::uint32_t getHeight(); + inline void setHeight( ::uint32_t value); + + inline bool hasOrigin(); + inline ::mrp::geometry::Pose::Builder getOrigin(); + inline void setOrigin( ::mrp::geometry::Pose::Reader value); + inline ::mrp::geometry::Pose::Builder initOrigin(); + inline void adoptOrigin(::capnp::Orphan< ::mrp::geometry::Pose>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Pose> disownOrigin(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class MapMetaData::Pipeline { +public: + typedef MapMetaData Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Time::Pipeline getMapLoadTime(); + inline ::mrp::geometry::Pose::Pipeline getOrigin(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class OccupancyGrid::Reader { +public: + typedef OccupancyGrid Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasInfo() const; + inline ::mrp::nav::MapMetaData::Reader getInfo() const; + + inline bool hasData() const; + inline ::capnp::Data::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class OccupancyGrid::Builder { +public: + typedef OccupancyGrid Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasInfo(); + inline ::mrp::nav::MapMetaData::Builder getInfo(); + inline void setInfo( ::mrp::nav::MapMetaData::Reader value); + inline ::mrp::nav::MapMetaData::Builder initInfo(); + inline void adoptInfo(::capnp::Orphan< ::mrp::nav::MapMetaData>&& value); + inline ::capnp::Orphan< ::mrp::nav::MapMetaData> disownInfo(); + + inline bool hasData(); + inline ::capnp::Data::Builder getData(); + inline void setData( ::capnp::Data::Reader value); + inline ::capnp::Data::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::Data>&& value); + inline ::capnp::Orphan< ::capnp::Data> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class OccupancyGrid::Pipeline { +public: + typedef OccupancyGrid Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::nav::MapMetaData::Pipeline getInfo(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Odometry::Reader { +public: + typedef Odometry Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasChildFrameId() const; + inline ::capnp::Text::Reader getChildFrameId() const; + + inline bool hasPose() const; + inline ::mrp::geometry::PoseWithCovariance::Reader getPose() const; + + inline bool hasTwist() const; + inline ::mrp::geometry::TwistWithCovariance::Reader getTwist() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Odometry::Builder { +public: + typedef Odometry Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasChildFrameId(); + inline ::capnp::Text::Builder getChildFrameId(); + inline void setChildFrameId( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initChildFrameId(unsigned int size); + inline void adoptChildFrameId(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownChildFrameId(); + + inline bool hasPose(); + inline ::mrp::geometry::PoseWithCovariance::Builder getPose(); + inline void setPose( ::mrp::geometry::PoseWithCovariance::Reader value); + inline ::mrp::geometry::PoseWithCovariance::Builder initPose(); + inline void adoptPose(::capnp::Orphan< ::mrp::geometry::PoseWithCovariance>&& value); + inline ::capnp::Orphan< ::mrp::geometry::PoseWithCovariance> disownPose(); + + inline bool hasTwist(); + inline ::mrp::geometry::TwistWithCovariance::Builder getTwist(); + inline void setTwist( ::mrp::geometry::TwistWithCovariance::Reader value); + inline ::mrp::geometry::TwistWithCovariance::Builder initTwist(); + inline void adoptTwist(::capnp::Orphan< ::mrp::geometry::TwistWithCovariance>&& value); + inline ::capnp::Orphan< ::mrp::geometry::TwistWithCovariance> disownTwist(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Odometry::Pipeline { +public: + typedef Odometry Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::PoseWithCovariance::Pipeline getPose(); + inline ::mrp::geometry::TwistWithCovariance::Pipeline getTwist(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Path::Reader { +public: + typedef Path Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasPoses() const; + inline ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>::Reader getPoses() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Path::Builder { +public: + typedef Path Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasPoses(); + inline ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>::Builder getPoses(); + inline void setPoses( ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>::Builder initPoses(unsigned int size); + inline void adoptPoses(::capnp::Orphan< ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>> disownPoses(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Path::Pipeline { +public: + typedef Path Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline bool GetMapAction::Reader::hasActionGoal() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool GetMapAction::Builder::hasActionGoal() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::nav::GetMapActionGoal::Reader GetMapAction::Reader::getActionGoal() const { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionGoal>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::nav::GetMapActionGoal::Builder GetMapAction::Builder::getActionGoal() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionGoal>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::nav::GetMapActionGoal::Pipeline GetMapAction::Pipeline::getActionGoal() { + return ::mrp::nav::GetMapActionGoal::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void GetMapAction::Builder::setActionGoal( ::mrp::nav::GetMapActionGoal::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionGoal>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::nav::GetMapActionGoal::Builder GetMapAction::Builder::initActionGoal() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionGoal>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void GetMapAction::Builder::adoptActionGoal( + ::capnp::Orphan< ::mrp::nav::GetMapActionGoal>&& value) { + ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionGoal>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::nav::GetMapActionGoal> GetMapAction::Builder::disownActionGoal() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionGoal>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool GetMapAction::Reader::hasActionResult() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool GetMapAction::Builder::hasActionResult() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::nav::GetMapActionResult::Reader GetMapAction::Reader::getActionResult() const { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionResult>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::nav::GetMapActionResult::Builder GetMapAction::Builder::getActionResult() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionResult>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::nav::GetMapActionResult::Pipeline GetMapAction::Pipeline::getActionResult() { + return ::mrp::nav::GetMapActionResult::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void GetMapAction::Builder::setActionResult( ::mrp::nav::GetMapActionResult::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionResult>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::nav::GetMapActionResult::Builder GetMapAction::Builder::initActionResult() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionResult>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void GetMapAction::Builder::adoptActionResult( + ::capnp::Orphan< ::mrp::nav::GetMapActionResult>&& value) { + ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionResult>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::nav::GetMapActionResult> GetMapAction::Builder::disownActionResult() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionResult>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool GetMapAction::Reader::hasActionFeedback() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool GetMapAction::Builder::hasActionFeedback() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::nav::GetMapActionFeedback::Reader GetMapAction::Reader::getActionFeedback() const { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionFeedback>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::mrp::nav::GetMapActionFeedback::Builder GetMapAction::Builder::getActionFeedback() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionFeedback>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::nav::GetMapActionFeedback::Pipeline GetMapAction::Pipeline::getActionFeedback() { + return ::mrp::nav::GetMapActionFeedback::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void GetMapAction::Builder::setActionFeedback( ::mrp::nav::GetMapActionFeedback::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionFeedback>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::mrp::nav::GetMapActionFeedback::Builder GetMapAction::Builder::initActionFeedback() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionFeedback>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void GetMapAction::Builder::adoptActionFeedback( + ::capnp::Orphan< ::mrp::nav::GetMapActionFeedback>&& value) { + ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionFeedback>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::nav::GetMapActionFeedback> GetMapAction::Builder::disownActionFeedback() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapActionFeedback>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool GetMapActionFeedback::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool GetMapActionFeedback::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader GetMapActionFeedback::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder GetMapActionFeedback::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline GetMapActionFeedback::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void GetMapActionFeedback::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder GetMapActionFeedback::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void GetMapActionFeedback::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> GetMapActionFeedback::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool GetMapActionFeedback::Reader::hasStatus() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool GetMapActionFeedback::Builder::hasStatus() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::actionlib::GoalStatus::Reader GetMapActionFeedback::Reader::getStatus() const { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalStatus>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::actionlib::GoalStatus::Builder GetMapActionFeedback::Builder::getStatus() { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalStatus>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::actionlib::GoalStatus::Pipeline GetMapActionFeedback::Pipeline::getStatus() { + return ::mrp::actionlib::GoalStatus::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void GetMapActionFeedback::Builder::setStatus( ::mrp::actionlib::GoalStatus::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalStatus>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::actionlib::GoalStatus::Builder GetMapActionFeedback::Builder::initStatus() { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalStatus>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void GetMapActionFeedback::Builder::adoptStatus( + ::capnp::Orphan< ::mrp::actionlib::GoalStatus>&& value) { + ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalStatus>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::actionlib::GoalStatus> GetMapActionFeedback::Builder::disownStatus() { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalStatus>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool GetMapActionFeedback::Reader::hasFeedback() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool GetMapActionFeedback::Builder::hasFeedback() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::nav::GetMapFeedback::Reader GetMapActionFeedback::Reader::getFeedback() const { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapFeedback>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::mrp::nav::GetMapFeedback::Builder GetMapActionFeedback::Builder::getFeedback() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapFeedback>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::nav::GetMapFeedback::Pipeline GetMapActionFeedback::Pipeline::getFeedback() { + return ::mrp::nav::GetMapFeedback::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void GetMapActionFeedback::Builder::setFeedback( ::mrp::nav::GetMapFeedback::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::nav::GetMapFeedback>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::mrp::nav::GetMapFeedback::Builder GetMapActionFeedback::Builder::initFeedback() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapFeedback>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void GetMapActionFeedback::Builder::adoptFeedback( + ::capnp::Orphan< ::mrp::nav::GetMapFeedback>&& value) { + ::capnp::_::PointerHelpers< ::mrp::nav::GetMapFeedback>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::nav::GetMapFeedback> GetMapActionFeedback::Builder::disownFeedback() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapFeedback>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool GetMapActionGoal::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool GetMapActionGoal::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader GetMapActionGoal::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder GetMapActionGoal::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline GetMapActionGoal::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void GetMapActionGoal::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder GetMapActionGoal::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void GetMapActionGoal::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> GetMapActionGoal::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool GetMapActionGoal::Reader::hasGoalId() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool GetMapActionGoal::Builder::hasGoalId() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::actionlib::GoalID::Reader GetMapActionGoal::Reader::getGoalId() const { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalID>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::actionlib::GoalID::Builder GetMapActionGoal::Builder::getGoalId() { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalID>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::actionlib::GoalID::Pipeline GetMapActionGoal::Pipeline::getGoalId() { + return ::mrp::actionlib::GoalID::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void GetMapActionGoal::Builder::setGoalId( ::mrp::actionlib::GoalID::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalID>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::actionlib::GoalID::Builder GetMapActionGoal::Builder::initGoalId() { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalID>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void GetMapActionGoal::Builder::adoptGoalId( + ::capnp::Orphan< ::mrp::actionlib::GoalID>&& value) { + ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalID>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::actionlib::GoalID> GetMapActionGoal::Builder::disownGoalId() { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalID>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool GetMapActionGoal::Reader::hasGoal() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool GetMapActionGoal::Builder::hasGoal() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::nav::GetMapGoal::Reader GetMapActionGoal::Reader::getGoal() const { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapGoal>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::mrp::nav::GetMapGoal::Builder GetMapActionGoal::Builder::getGoal() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapGoal>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::nav::GetMapGoal::Pipeline GetMapActionGoal::Pipeline::getGoal() { + return ::mrp::nav::GetMapGoal::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void GetMapActionGoal::Builder::setGoal( ::mrp::nav::GetMapGoal::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::nav::GetMapGoal>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::mrp::nav::GetMapGoal::Builder GetMapActionGoal::Builder::initGoal() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapGoal>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void GetMapActionGoal::Builder::adoptGoal( + ::capnp::Orphan< ::mrp::nav::GetMapGoal>&& value) { + ::capnp::_::PointerHelpers< ::mrp::nav::GetMapGoal>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::nav::GetMapGoal> GetMapActionGoal::Builder::disownGoal() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapGoal>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool GetMapActionResult::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool GetMapActionResult::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader GetMapActionResult::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder GetMapActionResult::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline GetMapActionResult::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void GetMapActionResult::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder GetMapActionResult::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void GetMapActionResult::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> GetMapActionResult::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool GetMapActionResult::Reader::hasStatus() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool GetMapActionResult::Builder::hasStatus() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::actionlib::GoalStatus::Reader GetMapActionResult::Reader::getStatus() const { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalStatus>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::actionlib::GoalStatus::Builder GetMapActionResult::Builder::getStatus() { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalStatus>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::actionlib::GoalStatus::Pipeline GetMapActionResult::Pipeline::getStatus() { + return ::mrp::actionlib::GoalStatus::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void GetMapActionResult::Builder::setStatus( ::mrp::actionlib::GoalStatus::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalStatus>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::actionlib::GoalStatus::Builder GetMapActionResult::Builder::initStatus() { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalStatus>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void GetMapActionResult::Builder::adoptStatus( + ::capnp::Orphan< ::mrp::actionlib::GoalStatus>&& value) { + ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalStatus>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::actionlib::GoalStatus> GetMapActionResult::Builder::disownStatus() { + return ::capnp::_::PointerHelpers< ::mrp::actionlib::GoalStatus>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool GetMapActionResult::Reader::hasResult() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool GetMapActionResult::Builder::hasResult() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::nav::GetMapResult::Reader GetMapActionResult::Reader::getResult() const { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapResult>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::mrp::nav::GetMapResult::Builder GetMapActionResult::Builder::getResult() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapResult>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::nav::GetMapResult::Pipeline GetMapActionResult::Pipeline::getResult() { + return ::mrp::nav::GetMapResult::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void GetMapActionResult::Builder::setResult( ::mrp::nav::GetMapResult::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::nav::GetMapResult>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::mrp::nav::GetMapResult::Builder GetMapActionResult::Builder::initResult() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapResult>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void GetMapActionResult::Builder::adoptResult( + ::capnp::Orphan< ::mrp::nav::GetMapResult>&& value) { + ::capnp::_::PointerHelpers< ::mrp::nav::GetMapResult>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::nav::GetMapResult> GetMapActionResult::Builder::disownResult() { + return ::capnp::_::PointerHelpers< ::mrp::nav::GetMapResult>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool GetMapResult::Reader::hasMap() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool GetMapResult::Builder::hasMap() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::nav::OccupancyGrid::Reader GetMapResult::Reader::getMap() const { + return ::capnp::_::PointerHelpers< ::mrp::nav::OccupancyGrid>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::nav::OccupancyGrid::Builder GetMapResult::Builder::getMap() { + return ::capnp::_::PointerHelpers< ::mrp::nav::OccupancyGrid>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::nav::OccupancyGrid::Pipeline GetMapResult::Pipeline::getMap() { + return ::mrp::nav::OccupancyGrid::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void GetMapResult::Builder::setMap( ::mrp::nav::OccupancyGrid::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::nav::OccupancyGrid>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::nav::OccupancyGrid::Builder GetMapResult::Builder::initMap() { + return ::capnp::_::PointerHelpers< ::mrp::nav::OccupancyGrid>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void GetMapResult::Builder::adoptMap( + ::capnp::Orphan< ::mrp::nav::OccupancyGrid>&& value) { + ::capnp::_::PointerHelpers< ::mrp::nav::OccupancyGrid>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::nav::OccupancyGrid> GetMapResult::Builder::disownMap() { + return ::capnp::_::PointerHelpers< ::mrp::nav::OccupancyGrid>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool GridCells::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool GridCells::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader GridCells::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder GridCells::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline GridCells::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void GridCells::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder GridCells::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void GridCells::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> GridCells::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline float GridCells::Reader::getCellWidth() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline float GridCells::Builder::getCellWidth() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void GridCells::Builder::setCellWidth(float value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline float GridCells::Reader::getCellHeight() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline float GridCells::Builder::getCellHeight() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void GridCells::Builder::setCellHeight(float value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool GridCells::Reader::hasCells() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool GridCells::Builder::hasCells() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader GridCells::Reader::getCells() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder GridCells::Builder::getCells() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void GridCells::Builder::setCells( ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder GridCells::Builder::initCells(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void GridCells::Builder::adoptCells( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>> GridCells::Builder::disownCells() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool MapMetaData::Reader::hasMapLoadTime() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool MapMetaData::Builder::hasMapLoadTime() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Time::Reader MapMetaData::Reader::getMapLoadTime() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Time::Builder MapMetaData::Builder::getMapLoadTime() { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Time::Pipeline MapMetaData::Pipeline::getMapLoadTime() { + return ::mrp::std::Time::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void MapMetaData::Builder::setMapLoadTime( ::mrp::std::Time::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Time>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Time::Builder MapMetaData::Builder::initMapLoadTime() { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MapMetaData::Builder::adoptMapLoadTime( + ::capnp::Orphan< ::mrp::std::Time>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Time>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Time> MapMetaData::Builder::disownMapLoadTime() { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline float MapMetaData::Reader::getResolution() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline float MapMetaData::Builder::getResolution() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void MapMetaData::Builder::setResolution(float value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t MapMetaData::Reader::getWidth() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t MapMetaData::Builder::getWidth() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void MapMetaData::Builder::setWidth( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t MapMetaData::Reader::getHeight() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t MapMetaData::Builder::getHeight() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void MapMetaData::Builder::setHeight( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool MapMetaData::Reader::hasOrigin() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool MapMetaData::Builder::hasOrigin() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Pose::Reader MapMetaData::Reader::getOrigin() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Pose::Builder MapMetaData::Builder::getOrigin() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Pose::Pipeline MapMetaData::Pipeline::getOrigin() { + return ::mrp::geometry::Pose::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void MapMetaData::Builder::setOrigin( ::mrp::geometry::Pose::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Pose::Builder MapMetaData::Builder::initOrigin() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void MapMetaData::Builder::adoptOrigin( + ::capnp::Orphan< ::mrp::geometry::Pose>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Pose> MapMetaData::Builder::disownOrigin() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool OccupancyGrid::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool OccupancyGrid::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader OccupancyGrid::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder OccupancyGrid::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline OccupancyGrid::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void OccupancyGrid::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder OccupancyGrid::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void OccupancyGrid::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> OccupancyGrid::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool OccupancyGrid::Reader::hasInfo() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool OccupancyGrid::Builder::hasInfo() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::nav::MapMetaData::Reader OccupancyGrid::Reader::getInfo() const { + return ::capnp::_::PointerHelpers< ::mrp::nav::MapMetaData>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::nav::MapMetaData::Builder OccupancyGrid::Builder::getInfo() { + return ::capnp::_::PointerHelpers< ::mrp::nav::MapMetaData>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::nav::MapMetaData::Pipeline OccupancyGrid::Pipeline::getInfo() { + return ::mrp::nav::MapMetaData::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void OccupancyGrid::Builder::setInfo( ::mrp::nav::MapMetaData::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::nav::MapMetaData>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::nav::MapMetaData::Builder OccupancyGrid::Builder::initInfo() { + return ::capnp::_::PointerHelpers< ::mrp::nav::MapMetaData>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void OccupancyGrid::Builder::adoptInfo( + ::capnp::Orphan< ::mrp::nav::MapMetaData>&& value) { + ::capnp::_::PointerHelpers< ::mrp::nav::MapMetaData>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::nav::MapMetaData> OccupancyGrid::Builder::disownInfo() { + return ::capnp::_::PointerHelpers< ::mrp::nav::MapMetaData>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool OccupancyGrid::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool OccupancyGrid::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Data::Reader OccupancyGrid::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::Data::Builder OccupancyGrid::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void OccupancyGrid::Builder::setData( ::capnp::Data::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::Data::Builder OccupancyGrid::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Data>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void OccupancyGrid::Builder::adoptData( + ::capnp::Orphan< ::capnp::Data>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Data> OccupancyGrid::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool Odometry::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Odometry::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader Odometry::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder Odometry::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline Odometry::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Odometry::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder Odometry::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Odometry::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> Odometry::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Odometry::Reader::hasChildFrameId() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Odometry::Builder::hasChildFrameId() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Odometry::Reader::getChildFrameId() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Odometry::Builder::getChildFrameId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Odometry::Builder::setChildFrameId( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Odometry::Builder::initChildFrameId(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Odometry::Builder::adoptChildFrameId( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Odometry::Builder::disownChildFrameId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Odometry::Reader::hasPose() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool Odometry::Builder::hasPose() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::PoseWithCovariance::Reader Odometry::Reader::getPose() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::PoseWithCovariance>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::PoseWithCovariance::Builder Odometry::Builder::getPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::PoseWithCovariance>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::PoseWithCovariance::Pipeline Odometry::Pipeline::getPose() { + return ::mrp::geometry::PoseWithCovariance::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void Odometry::Builder::setPose( ::mrp::geometry::PoseWithCovariance::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::PoseWithCovariance>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::PoseWithCovariance::Builder Odometry::Builder::initPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::PoseWithCovariance>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void Odometry::Builder::adoptPose( + ::capnp::Orphan< ::mrp::geometry::PoseWithCovariance>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::PoseWithCovariance>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::PoseWithCovariance> Odometry::Builder::disownPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::PoseWithCovariance>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool Odometry::Reader::hasTwist() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Odometry::Builder::hasTwist() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::TwistWithCovariance::Reader Odometry::Reader::getTwist() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::TwistWithCovariance>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::TwistWithCovariance::Builder Odometry::Builder::getTwist() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::TwistWithCovariance>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::TwistWithCovariance::Pipeline Odometry::Pipeline::getTwist() { + return ::mrp::geometry::TwistWithCovariance::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void Odometry::Builder::setTwist( ::mrp::geometry::TwistWithCovariance::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::TwistWithCovariance>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::TwistWithCovariance::Builder Odometry::Builder::initTwist() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::TwistWithCovariance>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Odometry::Builder::adoptTwist( + ::capnp::Orphan< ::mrp::geometry::TwistWithCovariance>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::TwistWithCovariance>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::TwistWithCovariance> Odometry::Builder::disownTwist() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::TwistWithCovariance>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Path::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Path::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader Path::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder Path::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline Path::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Path::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder Path::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Path::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> Path::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Path::Reader::hasPoses() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Path::Builder::hasPoses() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>::Reader Path::Reader::getPoses() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>::Builder Path::Builder::getPoses() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Path::Builder::setPoses( ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>::Builder Path::Builder::initPoses(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Path::Builder::adoptPoses( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>> Path::Builder::disownPoses() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::PoseStamped, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +} // namespace +} // namespace + +CAPNP_END_HEADER + diff --git a/msg/src/fairomsg/cpp/sensor_msgs.capnp.c++ b/msg/src/fairomsg/cpp/sensor_msgs.capnp.c++ new file mode 100644 index 0000000000..dd38dfa041 --- /dev/null +++ b/msg/src/fairomsg/cpp/sensor_msgs.capnp.c++ @@ -0,0 +1,5417 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: sensor_msgs.capnp + +#include "sensor_msgs.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<405> b_bd15f4ee99b7c709 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 22, 0, 0, 0, 1, 0, 4, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 2, 0, 0, 135, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 84, 0, 0, 0, 1, 0, 1, 0, + 86, 76, 144, 4, 143, 177, 219, 246, + 161, 0, 0, 0, 210, 0, 0, 0, + 9, 181, 227, 204, 75, 193, 15, 159, + 169, 0, 0, 0, 218, 0, 0, 0, + 114, 186, 231, 186, 98, 93, 37, 136, + 177, 0, 0, 0, 242, 0, 0, 0, + 72, 101, 179, 125, 167, 9, 122, 227, + 185, 0, 0, 0, 242, 0, 0, 0, + 67, 191, 154, 52, 190, 174, 125, 247, + 193, 0, 0, 0, 186, 0, 0, 0, + 138, 104, 107, 77, 239, 66, 67, 217, + 197, 0, 0, 0, 210, 0, 0, 0, + 163, 217, 77, 64, 121, 4, 12, 146, + 205, 0, 0, 0, 186, 0, 0, 0, + 161, 156, 234, 203, 119, 83, 145, 129, + 209, 0, 0, 0, 218, 0, 0, 0, + 251, 203, 207, 243, 213, 254, 4, 199, + 217, 0, 0, 0, 186, 0, 0, 0, + 228, 122, 200, 222, 24, 95, 139, 132, + 221, 0, 0, 0, 242, 0, 0, 0, + 159, 191, 168, 43, 68, 21, 191, 224, + 229, 0, 0, 0, 2, 1, 0, 0, + 16, 118, 223, 245, 187, 239, 151, 152, + 237, 0, 0, 0, 186, 0, 0, 0, + 206, 226, 137, 200, 196, 53, 135, 220, + 241, 0, 0, 0, 50, 1, 0, 0, + 234, 202, 50, 7, 40, 205, 219, 233, + 253, 0, 0, 0, 34, 1, 0, 0, + 63, 153, 203, 95, 198, 147, 203, 235, + 9, 1, 0, 0, 242, 0, 0, 0, + 184, 196, 145, 187, 136, 245, 159, 164, + 17, 1, 0, 0, 218, 0, 0, 0, + 232, 255, 81, 99, 58, 105, 45, 200, + 25, 1, 0, 0, 218, 0, 0, 0, + 98, 209, 200, 145, 50, 97, 196, 187, + 33, 1, 0, 0, 218, 0, 0, 0, + 91, 153, 129, 209, 78, 45, 3, 243, + 41, 1, 0, 0, 218, 0, 0, 0, + 55, 189, 104, 53, 64, 220, 8, 240, + 49, 1, 0, 0, 218, 0, 0, 0, + 213, 77, 106, 157, 95, 251, 96, 147, + 57, 1, 0, 0, 218, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 83, 116, 97, 116, + 117, 115, 85, 110, 107, 110, 111, 119, + 110, 0, 0, 0, 0, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 83, 116, 97, 116, + 117, 115, 67, 104, 97, 114, 103, 105, + 110, 103, 0, 0, 0, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 83, 116, 97, 116, + 117, 115, 68, 105, 115, 99, 104, 97, + 114, 103, 105, 110, 103, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 83, 116, 97, 116, + 117, 115, 78, 111, 116, 67, 104, 97, + 114, 103, 105, 110, 103, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 83, 116, 97, 116, + 117, 115, 70, 117, 108, 108, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 72, 101, 97, 108, + 116, 104, 85, 110, 107, 110, 111, 119, + 110, 0, 0, 0, 0, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 72, 101, 97, 108, + 116, 104, 71, 111, 111, 100, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 72, 101, 97, 108, + 116, 104, 79, 118, 101, 114, 104, 101, + 97, 116, 0, 0, 0, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 72, 101, 97, 108, + 116, 104, 68, 101, 97, 100, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 72, 101, 97, 108, + 116, 104, 79, 118, 101, 114, 118, 111, + 108, 116, 97, 103, 101, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 72, 101, 97, 108, + 116, 104, 85, 110, 115, 112, 101, 99, + 70, 97, 105, 108, 117, 114, 101, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 72, 101, 97, 108, + 116, 104, 67, 111, 108, 100, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 72, 101, 97, 108, + 116, 104, 87, 97, 116, 99, 104, 100, + 111, 103, 84, 105, 109, 101, 114, 69, + 120, 112, 105, 114, 101, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 72, 101, 97, 108, + 116, 104, 83, 97, 102, 101, 116, 121, + 84, 105, 109, 101, 114, 69, 120, 112, + 105, 114, 101, 0, 0, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 84, 101, 99, 104, + 110, 111, 108, 111, 103, 121, 85, 110, + 107, 110, 111, 119, 110, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 84, 101, 99, 104, + 110, 111, 108, 111, 103, 121, 78, 105, + 109, 104, 0, 0, 0, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 84, 101, 99, 104, + 110, 111, 108, 111, 103, 121, 76, 105, + 111, 110, 0, 0, 0, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 84, 101, 99, 104, + 110, 111, 108, 111, 103, 121, 76, 105, + 112, 111, 0, 0, 0, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 84, 101, 99, 104, + 110, 111, 108, 111, 103, 121, 76, 105, + 102, 101, 0, 0, 0, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 84, 101, 99, 104, + 110, 111, 108, 111, 103, 121, 78, 105, + 99, 100, 0, 0, 0, 0, 0, 0, + 107, 80, 111, 119, 101, 114, 83, 117, + 112, 112, 108, 121, 84, 101, 99, 104, + 110, 111, 108, 111, 103, 121, 76, 105, + 109, 110, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 1, 0, 0, 3, 0, 1, 0, + 184, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 1, 0, 0, 3, 0, 1, 0, + 188, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 1, 0, 0, 3, 0, 1, 0, + 196, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 1, 0, 0, 3, 0, 1, 0, + 200, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 1, 0, 0, 3, 0, 1, 0, + 204, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 1, 0, 0, 3, 0, 1, 0, + 212, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 1, 0, 0, 3, 0, 1, 0, + 220, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 1, 0, 0, 3, 0, 1, 0, + 228, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 28, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 1, 0, 0, 3, 0, 1, 0, + 240, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 29, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 1, 0, 0, 3, 0, 1, 0, + 252, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 30, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 1, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 1, 0, 0, 3, 0, 1, 0, + 8, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 248, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 2, 0, 0, 3, 0, 1, 0, + 12, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 2, 0, 0, 3, 0, 1, 0, + 36, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 2, 0, 0, 3, 0, 1, 0, + 60, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 2, 0, 0, 3, 0, 1, 0, + 68, 2, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 2, 0, 0, 3, 0, 1, 0, + 76, 2, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 111, 108, 116, 97, 103, 101, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 109, 112, 101, 114, 97, 116, + 117, 114, 101, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 114, 101, 110, 116, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 104, 97, 114, 103, 101, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 112, 97, 99, 105, 116, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 105, 103, 110, 67, 97, + 112, 97, 99, 105, 116, 121, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 101, 114, 99, 101, 110, 116, 97, + 103, 101, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 119, 101, 114, 83, 117, 112, + 112, 108, 121, 83, 116, 97, 116, 117, + 115, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 119, 101, 114, 83, 117, 112, + 112, 108, 121, 72, 101, 97, 108, 116, + 104, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 119, 101, 114, 83, 117, 112, + 112, 108, 121, 84, 101, 99, 104, 110, + 111, 108, 111, 103, 121, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 101, 115, 101, 110, 116, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 101, 108, 108, 86, 111, 108, 116, + 97, 103, 101, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 101, 108, 108, 84, 101, 109, 112, + 101, 114, 97, 116, 117, 114, 101, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 97, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 114, 105, 97, 108, 78, 117, + 109, 98, 101, 114, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bd15f4ee99b7c709 = b_bd15f4ee99b7c709.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_bd15f4ee99b7c709[] = { + &s_cf9a8bcf03922937, +}; +static const uint16_t m_bd15f4ee99b7c709[] = {5, 13, 12, 4, 3, 6, 0, 14, 7, 9, 8, 10, 11, 15, 2, 1}; +static const uint16_t i_bd15f4ee99b7c709[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}; +const ::capnp::_::RawSchema s_bd15f4ee99b7c709 = { + 0xbd15f4ee99b7c709, b_bd15f4ee99b7c709.words, 405, d_bd15f4ee99b7c709, m_bd15f4ee99b7c709, + 1, 16, i_bd15f4ee99b7c709, nullptr, nullptr, { &s_bd15f4ee99b7c709, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_f6dbb18f04904c56 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 86, 76, 144, 4, 143, 177, 219, 246, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 83, + 116, 97, 116, 117, 115, 85, 110, 107, + 110, 111, 119, 110, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f6dbb18f04904c56 = b_f6dbb18f04904c56.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_f6dbb18f04904c56 = { + 0xf6dbb18f04904c56, b_f6dbb18f04904c56.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_f6dbb18f04904c56, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_9f0fc14bcce3b509 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 9, 181, 227, 204, 75, 193, 15, 159, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 83, + 116, 97, 116, 117, 115, 67, 104, 97, + 114, 103, 105, 110, 103, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9f0fc14bcce3b509 = b_9f0fc14bcce3b509.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_9f0fc14bcce3b509 = { + 0x9f0fc14bcce3b509, b_9f0fc14bcce3b509.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_9f0fc14bcce3b509, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_88255d62bae7ba72 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 114, 186, 231, 186, 98, 93, 37, 136, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 83, + 116, 97, 116, 117, 115, 68, 105, 115, + 99, 104, 97, 114, 103, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_88255d62bae7ba72 = b_88255d62bae7ba72.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_88255d62bae7ba72 = { + 0x88255d62bae7ba72, b_88255d62bae7ba72.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_88255d62bae7ba72, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_e37a09a77db36548 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 72, 101, 179, 125, 167, 9, 122, 227, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 83, + 116, 97, 116, 117, 115, 78, 111, 116, + 67, 104, 97, 114, 103, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e37a09a77db36548 = b_e37a09a77db36548.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_e37a09a77db36548 = { + 0xe37a09a77db36548, b_e37a09a77db36548.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_e37a09a77db36548, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_f77daebe349abf43 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 67, 191, 154, 52, 190, 174, 125, 247, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 83, + 116, 97, 116, 117, 115, 70, 117, 108, + 108, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 4, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f77daebe349abf43 = b_f77daebe349abf43.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_f77daebe349abf43 = { + 0xf77daebe349abf43, b_f77daebe349abf43.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_f77daebe349abf43, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_d94342ef4d6b688a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 138, 104, 107, 77, 239, 66, 67, 217, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 72, + 101, 97, 108, 116, 104, 85, 110, 107, + 110, 111, 119, 110, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d94342ef4d6b688a = b_d94342ef4d6b688a.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_d94342ef4d6b688a = { + 0xd94342ef4d6b688a, b_d94342ef4d6b688a.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_d94342ef4d6b688a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_920c0479404dd9a3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 163, 217, 77, 64, 121, 4, 12, 146, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 72, + 101, 97, 108, 116, 104, 71, 111, 111, + 100, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_920c0479404dd9a3 = b_920c0479404dd9a3.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_920c0479404dd9a3 = { + 0x920c0479404dd9a3, b_920c0479404dd9a3.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_920c0479404dd9a3, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_81915377cbea9ca1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 161, 156, 234, 203, 119, 83, 145, 129, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 72, + 101, 97, 108, 116, 104, 79, 118, 101, + 114, 104, 101, 97, 116, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_81915377cbea9ca1 = b_81915377cbea9ca1.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_81915377cbea9ca1 = { + 0x81915377cbea9ca1, b_81915377cbea9ca1.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_81915377cbea9ca1, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_c704fed5f3cfcbfb = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 251, 203, 207, 243, 213, 254, 4, 199, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 72, + 101, 97, 108, 116, 104, 68, 101, 97, + 100, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c704fed5f3cfcbfb = b_c704fed5f3cfcbfb.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c704fed5f3cfcbfb = { + 0xc704fed5f3cfcbfb, b_c704fed5f3cfcbfb.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c704fed5f3cfcbfb, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_848b5f18dec87ae4 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 228, 122, 200, 222, 24, 95, 139, 132, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 72, + 101, 97, 108, 116, 104, 79, 118, 101, + 114, 118, 111, 108, 116, 97, 103, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 4, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_848b5f18dec87ae4 = b_848b5f18dec87ae4.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_848b5f18dec87ae4 = { + 0x848b5f18dec87ae4, b_848b5f18dec87ae4.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_848b5f18dec87ae4, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_e0bf15442ba8bf9f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 159, 191, 168, 43, 68, 21, 191, 224, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 72, + 101, 97, 108, 116, 104, 85, 110, 115, + 112, 101, 99, 70, 97, 105, 108, 117, + 114, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 5, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e0bf15442ba8bf9f = b_e0bf15442ba8bf9f.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_e0bf15442ba8bf9f = { + 0xe0bf15442ba8bf9f, b_e0bf15442ba8bf9f.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_e0bf15442ba8bf9f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_9897efbbf5df7610 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 16, 118, 223, 245, 187, 239, 151, 152, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 72, + 101, 97, 108, 116, 104, 67, 111, 108, + 100, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 6, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9897efbbf5df7610 = b_9897efbbf5df7610.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_9897efbbf5df7610 = { + 0x9897efbbf5df7610, b_9897efbbf5df7610.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_9897efbbf5df7610, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<30> b_dc8735c4c889e2ce = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 206, 226, 137, 200, 196, 53, 135, 220, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 2, 0, 0, + 57, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 0, 0, 0, 3, 0, 1, 0, + 64, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 72, + 101, 97, 108, 116, 104, 87, 97, 116, + 99, 104, 100, 111, 103, 84, 105, 109, + 101, 114, 69, 120, 112, 105, 114, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_dc8735c4c889e2ce = b_dc8735c4c889e2ce.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_dc8735c4c889e2ce = { + 0xdc8735c4c889e2ce, b_dc8735c4c889e2ce.words, 30, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_dc8735c4c889e2ce, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_e9dbcd280732caea = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 234, 202, 50, 7, 40, 205, 219, 233, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 72, + 101, 97, 108, 116, 104, 83, 97, 102, + 101, 116, 121, 84, 105, 109, 101, 114, + 69, 120, 112, 105, 114, 101, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 8, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e9dbcd280732caea = b_e9dbcd280732caea.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_e9dbcd280732caea = { + 0xe9dbcd280732caea, b_e9dbcd280732caea.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_e9dbcd280732caea, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_ebcb93c65fcb993f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 63, 153, 203, 95, 198, 147, 203, 235, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 84, + 101, 99, 104, 110, 111, 108, 111, 103, + 121, 85, 110, 107, 110, 111, 119, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ebcb93c65fcb993f = b_ebcb93c65fcb993f.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_ebcb93c65fcb993f = { + 0xebcb93c65fcb993f, b_ebcb93c65fcb993f.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_ebcb93c65fcb993f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_a49ff588bb91c4b8 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 184, 196, 145, 187, 136, 245, 159, 164, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 84, + 101, 99, 104, 110, 111, 108, 111, 103, + 121, 78, 105, 109, 104, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a49ff588bb91c4b8 = b_a49ff588bb91c4b8.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_a49ff588bb91c4b8 = { + 0xa49ff588bb91c4b8, b_a49ff588bb91c4b8.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_a49ff588bb91c4b8, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_c82d693a6351ffe8 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 232, 255, 81, 99, 58, 105, 45, 200, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 84, + 101, 99, 104, 110, 111, 108, 111, 103, + 121, 76, 105, 111, 110, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c82d693a6351ffe8 = b_c82d693a6351ffe8.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c82d693a6351ffe8 = { + 0xc82d693a6351ffe8, b_c82d693a6351ffe8.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c82d693a6351ffe8, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_bbc4613291c8d162 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 98, 209, 200, 145, 50, 97, 196, 187, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 84, + 101, 99, 104, 110, 111, 108, 111, 103, + 121, 76, 105, 112, 111, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bbc4613291c8d162 = b_bbc4613291c8d162.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_bbc4613291c8d162 = { + 0xbbc4613291c8d162, b_bbc4613291c8d162.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_bbc4613291c8d162, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_f3032d4ed181995b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 91, 153, 129, 209, 78, 45, 3, 243, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 84, + 101, 99, 104, 110, 111, 108, 111, 103, + 121, 76, 105, 102, 101, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 4, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f3032d4ed181995b = b_f3032d4ed181995b.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_f3032d4ed181995b = { + 0xf3032d4ed181995b, b_f3032d4ed181995b.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_f3032d4ed181995b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_f008dc403568bd37 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 55, 189, 104, 53, 64, 220, 8, 240, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 84, + 101, 99, 104, 110, 111, 108, 111, 103, + 121, 78, 105, 99, 100, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 5, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f008dc403568bd37 = b_f008dc403568bd37.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_f008dc403568bd37 = { + 0xf008dc403568bd37, b_f008dc403568bd37.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_f008dc403568bd37, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_9360fb5f9d6a4dd5 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 213, 77, 106, 157, 95, 251, 96, 147, + 35, 0, 0, 0, 4, 0, 0, 0, + 9, 199, 183, 153, 238, 244, 21, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 66, 97, + 116, 116, 101, 114, 121, 83, 116, 97, + 116, 101, 46, 107, 80, 111, 119, 101, + 114, 83, 117, 112, 112, 108, 121, 84, + 101, 99, 104, 110, 111, 108, 111, 103, + 121, 76, 105, 109, 110, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 6, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9360fb5f9d6a4dd5 = b_9360fb5f9d6a4dd5.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_9360fb5f9d6a4dd5 = { + 0x9360fb5f9d6a4dd5, b_9360fb5f9d6a4dd5.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_9360fb5f9d6a4dd5, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<203> b_c77609d0af4c8586 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 134, 133, 76, 175, 208, 9, 118, 199, + 22, 0, 0, 0, 1, 0, 2, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 7, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 111, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 67, 97, + 109, 101, 114, 97, 73, 110, 102, 111, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 44, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 44, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 52, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 1, 0, 0, 3, 0, 1, 0, + 60, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 1, 0, 0, 3, 0, 1, 0, + 80, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 1, 0, 0, 3, 0, 1, 0, + 100, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 1, 0, 0, 3, 0, 1, 0, + 120, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 1, 0, 0, 3, 0, 1, 0, + 140, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 1, 0, 0, 3, 0, 1, 0, + 148, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 1, 0, 0, 3, 0, 1, 0, + 156, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 1, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 1, 0, 0, 3, 0, 1, 0, + 160, 1, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 105, 103, 104, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 100, 116, 104, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 111, 114, 116, 105, + 111, 110, 77, 111, 100, 101, 108, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 110, 110, 105, 110, 103, 88, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 110, 110, 105, 110, 103, 89, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 105, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 74, 170, 172, 113, 191, 219, 200, 208, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c77609d0af4c8586 = b_c77609d0af4c8586.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c77609d0af4c8586[] = { + &s_cf9a8bcf03922937, + &s_d0c8dbbf71acaa4a, +}; +static const uint16_t m_c77609d0af4c8586[] = {8, 9, 4, 3, 0, 1, 5, 7, 6, 10, 2}; +static const uint16_t i_c77609d0af4c8586[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; +const ::capnp::_::RawSchema s_c77609d0af4c8586 = { + 0xc77609d0af4c8586, b_c77609d0af4c8586.words, 203, d_c77609d0af4c8586, m_c77609d0af4c8586, + 2, 11, i_c77609d0af4c8586, nullptr, nullptr, { &s_c77609d0af4c8586, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_d762b9834e50891f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 31, 137, 80, 78, 131, 185, 98, 215, + 22, 0, 0, 0, 1, 0, 0, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 67, 104, + 97, 110, 110, 101, 108, 70, 108, 111, + 97, 116, 51, 50, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 108, 117, 101, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d762b9834e50891f = b_d762b9834e50891f.words; +#if !CAPNP_LITE +static const uint16_t m_d762b9834e50891f[] = {0, 1}; +static const uint16_t i_d762b9834e50891f[] = {0, 1}; +const ::capnp::_::RawSchema s_d762b9834e50891f = { + 0xd762b9834e50891f, b_d762b9834e50891f.words, 53, nullptr, m_d762b9834e50891f, + 0, 2, i_d762b9834e50891f, nullptr, nullptr, { &s_d762b9834e50891f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<64> b_af0080bb451e1c40 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 64, 28, 30, 69, 187, 128, 0, 175, + 22, 0, 0, 0, 1, 0, 0, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 67, 111, + 109, 112, 114, 101, 115, 115, 101, 100, + 73, 109, 97, 103, 101, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 111, 114, 109, 97, 116, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_af0080bb451e1c40 = b_af0080bb451e1c40.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_af0080bb451e1c40[] = { + &s_cf9a8bcf03922937, +}; +static const uint16_t m_af0080bb451e1c40[] = {2, 1, 0}; +static const uint16_t i_af0080bb451e1c40[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_af0080bb451e1c40 = { + 0xaf0080bb451e1c40, b_af0080bb451e1c40.words, 64, d_af0080bb451e1c40, m_af0080bb451e1c40, + 1, 3, i_af0080bb451e1c40, nullptr, nullptr, { &s_af0080bb451e1c40, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<66> b_81cfa0883626c106 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 6, 193, 38, 54, 136, 160, 207, 129, + 22, 0, 0, 0, 1, 0, 2, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 70, 108, + 117, 105, 100, 80, 114, 101, 115, 115, + 117, 114, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 108, 117, 105, 100, 80, 114, 101, + 115, 115, 117, 114, 101, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 114, 105, 97, 110, 99, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_81cfa0883626c106 = b_81cfa0883626c106.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_81cfa0883626c106[] = { + &s_cf9a8bcf03922937, +}; +static const uint16_t m_81cfa0883626c106[] = {1, 0, 2}; +static const uint16_t i_81cfa0883626c106[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_81cfa0883626c106 = { + 0x81cfa0883626c106, b_81cfa0883626c106.words, 66, d_81cfa0883626c106, m_81cfa0883626c106, + 1, 3, i_81cfa0883626c106, nullptr, nullptr, { &s_81cfa0883626c106, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<66> b_cc6e96bbfbc66489 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 137, 100, 198, 251, 187, 150, 110, 204, + 22, 0, 0, 0, 1, 0, 2, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 73, 108, + 108, 117, 109, 105, 110, 97, 110, 99, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 108, 108, 117, 109, 105, 110, 97, + 110, 99, 101, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 114, 105, 97, 110, 99, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cc6e96bbfbc66489 = b_cc6e96bbfbc66489.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_cc6e96bbfbc66489[] = { + &s_cf9a8bcf03922937, +}; +static const uint16_t m_cc6e96bbfbc66489[] = {0, 1, 2}; +static const uint16_t i_cc6e96bbfbc66489[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_cc6e96bbfbc66489 = { + 0xcc6e96bbfbc66489, b_cc6e96bbfbc66489.words, 66, d_cc6e96bbfbc66489, m_cc6e96bbfbc66489, + 1, 3, i_cc6e96bbfbc66489, nullptr, nullptr, { &s_cc6e96bbfbc66489, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<125> b_9e2aef0d448fbc0b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 11, 188, 143, 68, 13, 239, 42, 158, + 22, 0, 0, 0, 1, 0, 2, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 226, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 73, 109, + 97, 103, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 105, 103, 104, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 100, 116, 104, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 99, 111, 100, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 115, 66, 105, 103, 101, 110, 100, + 105, 97, 110, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 112, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9e2aef0d448fbc0b = b_9e2aef0d448fbc0b.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_9e2aef0d448fbc0b[] = { + &s_cf9a8bcf03922937, +}; +static const uint16_t m_9e2aef0d448fbc0b[] = {6, 3, 0, 1, 4, 5, 2}; +static const uint16_t i_9e2aef0d448fbc0b[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_9e2aef0d448fbc0b = { + 0x9e2aef0d448fbc0b, b_9e2aef0d448fbc0b.words, 125, d_9e2aef0d448fbc0b, m_9e2aef0d448fbc0b, + 1, 7, i_9e2aef0d448fbc0b, nullptr, nullptr, { &s_9e2aef0d448fbc0b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<147> b_c311a9e61266192f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 47, 25, 102, 18, 230, 169, 17, 195, + 22, 0, 0, 0, 1, 0, 0, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 7, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 73, 109, + 117, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 8, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 1, 0, 0, 3, 0, 1, 0, + 52, 1, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 101, 110, 116, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 100, 4, 183, 255, 76, 138, 17, 175, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 101, 110, 116, 97, 116, + 105, 111, 110, 67, 111, 118, 97, 114, + 105, 97, 110, 99, 101, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 117, 108, 97, 114, 86, + 101, 108, 111, 99, 105, 116, 121, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 117, 108, 97, 114, 86, + 101, 108, 111, 99, 105, 116, 121, 67, + 111, 118, 97, 114, 105, 97, 110, 99, + 101, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 110, 101, 97, 114, 65, 99, + 99, 101, 108, 101, 114, 97, 116, 105, + 111, 110, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 110, 101, 97, 114, 65, 99, + 99, 101, 108, 101, 114, 97, 116, 105, + 111, 110, 67, 111, 118, 97, 114, 105, + 97, 110, 99, 101, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c311a9e61266192f = b_c311a9e61266192f.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c311a9e61266192f[] = { + &s_89d716bb34f0209a, + &s_af118a4cffb70464, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_c311a9e61266192f[] = {3, 4, 0, 5, 6, 1, 2}; +static const uint16_t i_c311a9e61266192f[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_c311a9e61266192f = { + 0xc311a9e61266192f, b_c311a9e61266192f.words, 147, d_c311a9e61266192f, m_c311a9e61266192f, + 3, 7, i_c311a9e61266192f, nullptr, nullptr, { &s_c311a9e61266192f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<112> b_8cb30c6c01fcdcd1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 209, 220, 252, 1, 108, 12, 179, 140, + 22, 0, 0, 0, 1, 0, 0, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 74, 111, + 105, 110, 116, 83, 116, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 152, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 176, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 108, 111, 99, 105, 116, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 102, 102, 111, 114, 116, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8cb30c6c01fcdcd1 = b_8cb30c6c01fcdcd1.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_8cb30c6c01fcdcd1[] = { + &s_cf9a8bcf03922937, +}; +static const uint16_t m_8cb30c6c01fcdcd1[] = {4, 0, 1, 2, 3}; +static const uint16_t i_8cb30c6c01fcdcd1[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_8cb30c6c01fcdcd1 = { + 0x8cb30c6c01fcdcd1, b_8cb30c6c01fcdcd1.words, 112, d_8cb30c6c01fcdcd1, m_8cb30c6c01fcdcd1, + 1, 5, i_8cb30c6c01fcdcd1, nullptr, nullptr, { &s_8cb30c6c01fcdcd1, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<71> b_d53f12214f104108 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 8, 65, 16, 79, 33, 18, 63, 213, + 22, 0, 0, 0, 1, 0, 0, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 74, 111, + 121, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 96, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 120, 101, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 117, 116, 116, 111, 110, 115, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d53f12214f104108 = b_d53f12214f104108.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_d53f12214f104108[] = { + &s_cf9a8bcf03922937, +}; +static const uint16_t m_d53f12214f104108[] = {1, 2, 0}; +static const uint16_t i_d53f12214f104108[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_d53f12214f104108 = { + 0xd53f12214f104108, b_d53f12214f104108.words, 71, d_d53f12214f104108, m_d53f12214f104108, + 1, 3, i_d53f12214f104108, nullptr, nullptr, { &s_d53f12214f104108, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<77> b_ab14acd9dc0d006d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 109, 0, 13, 220, 217, 172, 20, 171, + 22, 0, 0, 0, 1, 0, 1, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 74, 111, + 121, 70, 101, 101, 100, 98, 97, 99, + 107, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 1, 0, 1, 0, + 2, 174, 149, 41, 40, 224, 202, 130, + 17, 0, 0, 0, 74, 0, 0, 0, + 186, 76, 57, 112, 3, 126, 92, 151, + 17, 0, 0, 0, 98, 0, 0, 0, + 81, 108, 157, 128, 132, 97, 107, 190, + 17, 0, 0, 0, 98, 0, 0, 0, + 107, 84, 121, 112, 101, 76, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 84, 121, 112, 101, 82, 117, 109, + 98, 108, 101, 0, 0, 0, 0, 0, + 107, 84, 121, 112, 101, 66, 117, 122, + 122, 101, 114, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 0, 0, 0, 3, 0, 1, 0, + 88, 0, 0, 0, 2, 0, 1, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 100, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 110, 115, 105, 116, + 121, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ab14acd9dc0d006d = b_ab14acd9dc0d006d.words; +#if !CAPNP_LITE +static const uint16_t m_ab14acd9dc0d006d[] = {1, 2, 0}; +static const uint16_t i_ab14acd9dc0d006d[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_ab14acd9dc0d006d = { + 0xab14acd9dc0d006d, b_ab14acd9dc0d006d.words, 77, nullptr, m_ab14acd9dc0d006d, + 0, 3, i_ab14acd9dc0d006d, nullptr, nullptr, { &s_ab14acd9dc0d006d, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_82cae0282995ae02 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 2, 174, 149, 41, 40, 224, 202, 130, + 34, 0, 0, 0, 4, 0, 0, 0, + 109, 0, 13, 220, 217, 172, 20, 171, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 74, 111, + 121, 70, 101, 101, 100, 98, 97, 99, + 107, 46, 107, 84, 121, 112, 101, 76, + 101, 100, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_82cae0282995ae02 = b_82cae0282995ae02.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_82cae0282995ae02 = { + 0x82cae0282995ae02, b_82cae0282995ae02.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_82cae0282995ae02, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_975c7e0370394cba = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 186, 76, 57, 112, 3, 126, 92, 151, + 34, 0, 0, 0, 4, 0, 0, 0, + 109, 0, 13, 220, 217, 172, 20, 171, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 114, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 74, 111, + 121, 70, 101, 101, 100, 98, 97, 99, + 107, 46, 107, 84, 121, 112, 101, 82, + 117, 109, 98, 108, 101, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_975c7e0370394cba = b_975c7e0370394cba.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_975c7e0370394cba = { + 0x975c7e0370394cba, b_975c7e0370394cba.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_975c7e0370394cba, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_be6b6184809d6c51 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 81, 108, 157, 128, 132, 97, 107, 190, + 34, 0, 0, 0, 4, 0, 0, 0, + 109, 0, 13, 220, 217, 172, 20, 171, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 114, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 74, 111, + 121, 70, 101, 101, 100, 98, 97, 99, + 107, 46, 107, 84, 121, 112, 101, 66, + 117, 122, 122, 101, 114, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_be6b6184809d6c51 = b_be6b6184809d6c51.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_be6b6184809d6c51 = { + 0xbe6b6184809d6c51, b_be6b6184809d6c51.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_be6b6184809d6c51, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<38> b_f642613fa1f4e6e0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 224, 230, 244, 161, 63, 97, 66, 246, + 22, 0, 0, 0, 1, 0, 0, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 74, 111, + 121, 70, 101, 101, 100, 98, 97, 99, + 107, 65, 114, 114, 97, 121, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 36, 0, 0, 0, 2, 0, 1, 0, + 97, 114, 114, 97, 121, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 13, 220, 217, 172, 20, 171, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f642613fa1f4e6e0 = b_f642613fa1f4e6e0.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f642613fa1f4e6e0[] = { + &s_ab14acd9dc0d006d, +}; +static const uint16_t m_f642613fa1f4e6e0[] = {0}; +static const uint16_t i_f642613fa1f4e6e0[] = {0}; +const ::capnp::_::RawSchema s_f642613fa1f4e6e0 = { + 0xf642613fa1f4e6e0, b_f642613fa1f4e6e0.words, 38, d_f642613fa1f4e6e0, m_f642613fa1f4e6e0, + 1, 1, i_f642613fa1f4e6e0, nullptr, nullptr, { &s_f642613fa1f4e6e0, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<37> b_bf4722c17bc19160 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 96, 145, 193, 123, 193, 34, 71, 191, + 22, 0, 0, 0, 1, 0, 0, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 76, 97, + 115, 101, 114, 69, 99, 104, 111, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 36, 0, 0, 0, 2, 0, 1, 0, + 101, 99, 104, 111, 101, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bf4722c17bc19160 = b_bf4722c17bc19160.words; +#if !CAPNP_LITE +static const uint16_t m_bf4722c17bc19160[] = {0}; +static const uint16_t i_bf4722c17bc19160[] = {0}; +const ::capnp::_::RawSchema s_bf4722c17bc19160 = { + 0xbf4722c17bc19160, b_bf4722c17bc19160.words, 37, nullptr, m_bf4722c17bc19160, + 0, 1, i_bf4722c17bc19160, nullptr, nullptr, { &s_bf4722c17bc19160, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<184> b_bf2ff955ecb97b19 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 25, 123, 185, 236, 85, 249, 47, 191, + 22, 0, 0, 0, 1, 0, 4, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 55, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 76, 97, + 115, 101, 114, 83, 99, 97, 110, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 40, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 1, 0, 0, 3, 0, 1, 0, + 40, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 1, 0, 0, 3, 0, 1, 0, + 56, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 1, 0, 0, 3, 0, 1, 0, + 64, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 1, 0, 0, 3, 0, 1, 0, + 92, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 1, 0, 0, 3, 0, 1, 0, + 116, 1, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 77, 105, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 77, 97, 120, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 73, 110, 99, + 114, 101, 109, 101, 110, 116, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 73, 110, 99, 114, + 101, 109, 101, 110, 116, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 99, 97, 110, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 110, 103, 101, 77, 105, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 110, 103, 101, 77, 97, 120, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 110, 103, 101, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 110, 115, 105, 116, + 105, 101, 115, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bf2ff955ecb97b19 = b_bf2ff955ecb97b19.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_bf2ff955ecb97b19[] = { + &s_cf9a8bcf03922937, +}; +static const uint16_t m_bf2ff955ecb97b19[] = {3, 2, 1, 0, 9, 7, 6, 8, 5, 4}; +static const uint16_t i_bf2ff955ecb97b19[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; +const ::capnp::_::RawSchema s_bf2ff955ecb97b19 = { + 0xbf2ff955ecb97b19, b_bf2ff955ecb97b19.words, 184, d_bf2ff955ecb97b19, m_bf2ff955ecb97b19, + 1, 10, i_bf2ff955ecb97b19, nullptr, nullptr, { &s_bf2ff955ecb97b19, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<71> b_a4113fd6a23d4ec2 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 194, 78, 61, 162, 214, 63, 17, 164, + 22, 0, 0, 0, 1, 0, 0, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 77, 97, + 103, 110, 101, 116, 105, 99, 70, 105, + 101, 108, 100, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 103, 110, 101, 116, 105, 99, + 70, 105, 101, 108, 100, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 103, 110, 101, 116, 105, 99, + 70, 105, 101, 108, 100, 67, 111, 118, + 97, 114, 105, 97, 110, 99, 101, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a4113fd6a23d4ec2 = b_a4113fd6a23d4ec2.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a4113fd6a23d4ec2[] = { + &s_89d716bb34f0209a, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_a4113fd6a23d4ec2[] = {0, 1, 2}; +static const uint16_t i_a4113fd6a23d4ec2[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_a4113fd6a23d4ec2 = { + 0xa4113fd6a23d4ec2, b_a4113fd6a23d4ec2.words, 71, d_a4113fd6a23d4ec2, m_a4113fd6a23d4ec2, + 2, 3, i_a4113fd6a23d4ec2, nullptr, nullptr, { &s_a4113fd6a23d4ec2, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<113> b_f1a736981c67827a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 122, 130, 103, 28, 152, 54, 167, 241, + 22, 0, 0, 0, 1, 0, 0, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 77, 117, + 108, 116, 105, 68, 79, 70, 74, 111, + 105, 110, 116, 83, 116, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 0, 0, 0, 3, 0, 1, 0, + 156, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 106, 111, 105, 110, 116, 78, 97, 109, + 101, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 110, 115, 102, 111, 114, + 109, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 188, 173, 16, 182, 50, 63, 34, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 119, 105, 115, 116, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 197, 5, 214, 69, 57, 245, 239, 227, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 114, 101, 110, 99, 104, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 172, 245, 110, 206, 103, 172, 194, 129, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f1a736981c67827a = b_f1a736981c67827a.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f1a736981c67827a[] = { + &s_81c2ac67ce6ef5ac, + &s_cf223f32b610adbc, + &s_cf9a8bcf03922937, + &s_e3eff53945d605c5, +}; +static const uint16_t m_f1a736981c67827a[] = {0, 1, 2, 3, 4}; +static const uint16_t i_f1a736981c67827a[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_f1a736981c67827a = { + 0xf1a736981c67827a, b_f1a736981c67827a.words, 113, d_f1a736981c67827a, m_f1a736981c67827a, + 4, 5, i_f1a736981c67827a, nullptr, nullptr, { &s_f1a736981c67827a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<186> b_b7bf766c793fcfe0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 224, 207, 63, 121, 108, 118, 191, 183, + 22, 0, 0, 0, 1, 0, 4, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 55, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 77, 117, + 108, 116, 105, 69, 99, 104, 111, 76, + 97, 115, 101, 114, 83, 99, 97, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 40, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 1, 0, 0, 3, 0, 1, 0, + 40, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 1, 0, 0, 3, 0, 1, 0, + 56, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 1, 0, 0, 3, 0, 1, 0, + 64, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 1, 0, 0, 3, 0, 1, 0, + 92, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 1, 0, 0, 3, 0, 1, 0, + 116, 1, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 77, 105, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 77, 97, 120, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 73, 110, 99, + 114, 101, 109, 101, 110, 116, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 73, 110, 99, 114, + 101, 109, 101, 110, 116, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 99, 97, 110, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 110, 103, 101, 77, 105, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 110, 103, 101, 77, 97, 120, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 110, 103, 101, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 96, 145, 193, 123, 193, 34, 71, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 110, 115, 105, 116, + 105, 101, 115, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 96, 145, 193, 123, 193, 34, 71, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b7bf766c793fcfe0 = b_b7bf766c793fcfe0.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_b7bf766c793fcfe0[] = { + &s_bf4722c17bc19160, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_b7bf766c793fcfe0[] = {3, 2, 1, 0, 9, 7, 6, 8, 5, 4}; +static const uint16_t i_b7bf766c793fcfe0[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; +const ::capnp::_::RawSchema s_b7bf766c793fcfe0 = { + 0xb7bf766c793fcfe0, b_b7bf766c793fcfe0.words, 186, d_b7bf766c793fcfe0, m_b7bf766c793fcfe0, + 2, 10, i_b7bf766c793fcfe0, nullptr, nullptr, { &s_b7bf766c793fcfe0, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<156> b_a97166f93e10128d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 141, 18, 16, 62, 249, 102, 113, 169, + 22, 0, 0, 0, 1, 0, 4, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 71, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 70, 105, 120, 0, + 16, 0, 0, 0, 1, 0, 1, 0, + 167, 189, 184, 124, 59, 109, 158, 152, + 25, 0, 0, 0, 186, 0, 0, 0, + 167, 180, 65, 106, 77, 29, 20, 253, + 29, 0, 0, 0, 226, 0, 0, 0, + 67, 12, 105, 168, 85, 244, 239, 178, + 37, 0, 0, 0, 234, 0, 0, 0, + 102, 121, 231, 97, 210, 113, 35, 206, + 45, 0, 0, 0, 170, 0, 0, 0, + 107, 67, 111, 118, 97, 114, 105, 97, + 110, 99, 101, 84, 121, 112, 101, 85, + 110, 107, 110, 111, 119, 110, 0, 0, + 107, 67, 111, 118, 97, 114, 105, 97, + 110, 99, 101, 84, 121, 112, 101, 65, + 112, 112, 114, 111, 120, 105, 109, 97, + 116, 101, 100, 0, 0, 0, 0, 0, + 107, 67, 111, 118, 97, 114, 105, 97, + 110, 99, 101, 84, 121, 112, 101, 68, + 105, 97, 103, 111, 110, 97, 108, 75, + 110, 111, 119, 110, 0, 0, 0, 0, + 107, 67, 111, 118, 97, 114, 105, 97, + 110, 99, 101, 84, 121, 112, 101, 75, + 110, 111, 119, 110, 0, 0, 0, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 0, 1, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 208, 242, 114, 206, 2, 183, 248, 153, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 105, 116, 117, 100, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 105, 116, 117, 100, + 101, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 116, 105, 116, 117, 100, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 67, 111, 118, 97, 114, 105, 97, 110, + 99, 101, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 67, 111, 118, 97, 114, 105, 97, 110, + 99, 101, 84, 121, 112, 101, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a97166f93e10128d = b_a97166f93e10128d.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a97166f93e10128d[] = { + &s_99f8b702ce72f2d0, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_a97166f93e10128d[] = {4, 0, 2, 3, 5, 6, 1}; +static const uint16_t i_a97166f93e10128d[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_a97166f93e10128d = { + 0xa97166f93e10128d, b_a97166f93e10128d.words, 156, d_a97166f93e10128d, m_a97166f93e10128d, + 2, 7, i_a97166f93e10128d, nullptr, nullptr, { &s_a97166f93e10128d, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_989e6d3b7cb8bda7 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 167, 189, 184, 124, 59, 109, 158, 152, + 32, 0, 0, 0, 4, 0, 0, 0, + 141, 18, 16, 62, 249, 102, 113, 169, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 186, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 70, 105, 120, 46, + 107, 67, 111, 118, 97, 114, 105, 97, + 110, 99, 101, 84, 121, 112, 101, 85, + 110, 107, 110, 111, 119, 110, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_989e6d3b7cb8bda7 = b_989e6d3b7cb8bda7.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_989e6d3b7cb8bda7 = { + 0x989e6d3b7cb8bda7, b_989e6d3b7cb8bda7.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_989e6d3b7cb8bda7, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_fd141d4d6a41b4a7 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 167, 180, 65, 106, 77, 29, 20, 253, + 32, 0, 0, 0, 4, 0, 0, 0, + 141, 18, 16, 62, 249, 102, 113, 169, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 226, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 70, 105, 120, 46, + 107, 67, 111, 118, 97, 114, 105, 97, + 110, 99, 101, 84, 121, 112, 101, 65, + 112, 112, 114, 111, 120, 105, 109, 97, + 116, 101, 100, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fd141d4d6a41b4a7 = b_fd141d4d6a41b4a7.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_fd141d4d6a41b4a7 = { + 0xfd141d4d6a41b4a7, b_fd141d4d6a41b4a7.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_fd141d4d6a41b4a7, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_b2eff455a8690c43 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 67, 12, 105, 168, 85, 244, 239, 178, + 32, 0, 0, 0, 4, 0, 0, 0, + 141, 18, 16, 62, 249, 102, 113, 169, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 70, 105, 120, 46, + 107, 67, 111, 118, 97, 114, 105, 97, + 110, 99, 101, 84, 121, 112, 101, 68, + 105, 97, 103, 111, 110, 97, 108, 75, + 110, 111, 119, 110, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b2eff455a8690c43 = b_b2eff455a8690c43.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_b2eff455a8690c43 = { + 0xb2eff455a8690c43, b_b2eff455a8690c43.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_b2eff455a8690c43, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_ce2371d261e77966 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 102, 121, 231, 97, 210, 113, 35, 206, + 32, 0, 0, 0, 4, 0, 0, 0, + 141, 18, 16, 62, 249, 102, 113, 169, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 70, 105, 120, 46, + 107, 67, 111, 118, 97, 114, 105, 97, + 110, 99, 101, 84, 121, 112, 101, 75, + 110, 111, 119, 110, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ce2371d261e77966 = b_ce2371d261e77966.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_ce2371d261e77966 = { + 0xce2371d261e77966, b_ce2371d261e77966.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_ce2371d261e77966, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<81> b_99f8b702ce72f2d0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 208, 242, 114, 206, 2, 183, 248, 153, + 22, 0, 0, 0, 1, 0, 1, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 135, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 83, 116, 97, 116, + 117, 115, 0, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 1, 0, 1, 0, + 151, 29, 133, 161, 136, 232, 29, 221, + 57, 0, 0, 0, 106, 0, 0, 0, + 43, 171, 193, 51, 101, 153, 92, 150, + 57, 0, 0, 0, 90, 0, 0, 0, + 31, 96, 2, 249, 14, 188, 118, 175, + 57, 0, 0, 0, 122, 0, 0, 0, + 253, 235, 10, 98, 22, 44, 136, 175, + 57, 0, 0, 0, 122, 0, 0, 0, + 16, 179, 213, 252, 17, 186, 145, 185, + 57, 0, 0, 0, 98, 0, 0, 0, + 60, 251, 224, 208, 70, 104, 201, 225, + 57, 0, 0, 0, 130, 0, 0, 0, + 4, 62, 59, 112, 67, 213, 151, 246, + 57, 0, 0, 0, 130, 0, 0, 0, + 82, 197, 220, 37, 42, 230, 54, 193, + 57, 0, 0, 0, 130, 0, 0, 0, + 107, 83, 116, 97, 116, 117, 115, 78, + 111, 70, 105, 120, 0, 0, 0, 0, + 107, 83, 116, 97, 116, 117, 115, 70, + 105, 120, 0, 0, 0, 0, 0, 0, + 107, 83, 116, 97, 116, 117, 115, 83, + 98, 97, 115, 70, 105, 120, 0, 0, + 107, 83, 116, 97, 116, 117, 115, 71, + 98, 97, 115, 70, 105, 120, 0, 0, + 107, 83, 101, 114, 118, 105, 99, 101, + 71, 112, 115, 0, 0, 0, 0, 0, + 107, 83, 101, 114, 118, 105, 99, 101, + 71, 108, 111, 110, 97, 115, 115, 0, + 107, 83, 101, 114, 118, 105, 99, 101, + 67, 111, 109, 112, 97, 115, 115, 0, + 107, 83, 101, 114, 118, 105, 99, 101, + 71, 97, 108, 105, 108, 101, 111, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 114, 118, 105, 99, 101, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_99f8b702ce72f2d0 = b_99f8b702ce72f2d0.words; +#if !CAPNP_LITE +static const uint16_t m_99f8b702ce72f2d0[] = {1, 0}; +static const uint16_t i_99f8b702ce72f2d0[] = {0, 1}; +const ::capnp::_::RawSchema s_99f8b702ce72f2d0 = { + 0x99f8b702ce72f2d0, b_99f8b702ce72f2d0.words, 81, nullptr, m_99f8b702ce72f2d0, + 0, 2, i_99f8b702ce72f2d0, nullptr, nullptr, { &s_99f8b702ce72f2d0, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_dd1de888a1851d97 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 151, 29, 133, 161, 136, 232, 29, 221, + 35, 0, 0, 0, 4, 0, 0, 0, + 208, 242, 114, 206, 2, 183, 248, 153, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 130, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 83, 116, 97, 116, + 117, 115, 46, 107, 83, 116, 97, 116, + 117, 115, 78, 111, 70, 105, 120, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_dd1de888a1851d97 = b_dd1de888a1851d97.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_dd1de888a1851d97 = { + 0xdd1de888a1851d97, b_dd1de888a1851d97.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_dd1de888a1851d97, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_965c996533c1ab2b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 43, 171, 193, 51, 101, 153, 92, 150, + 35, 0, 0, 0, 4, 0, 0, 0, + 208, 242, 114, 206, 2, 183, 248, 153, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 114, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 83, 116, 97, 116, + 117, 115, 46, 107, 83, 116, 97, 116, + 117, 115, 70, 105, 120, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_965c996533c1ab2b = b_965c996533c1ab2b.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_965c996533c1ab2b = { + 0x965c996533c1ab2b, b_965c996533c1ab2b.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_965c996533c1ab2b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_af76bc0ef902601f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 31, 96, 2, 249, 14, 188, 118, 175, + 35, 0, 0, 0, 4, 0, 0, 0, + 208, 242, 114, 206, 2, 183, 248, 153, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 83, 116, 97, 116, + 117, 115, 46, 107, 83, 116, 97, 116, + 117, 115, 83, 98, 97, 115, 70, 105, + 120, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_af76bc0ef902601f = b_af76bc0ef902601f.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_af76bc0ef902601f = { + 0xaf76bc0ef902601f, b_af76bc0ef902601f.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_af76bc0ef902601f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_af882c16620aebfd = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 253, 235, 10, 98, 22, 44, 136, 175, + 35, 0, 0, 0, 4, 0, 0, 0, + 208, 242, 114, 206, 2, 183, 248, 153, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 83, 116, 97, 116, + 117, 115, 46, 107, 83, 116, 97, 116, + 117, 115, 71, 98, 97, 115, 70, 105, + 120, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_af882c16620aebfd = b_af882c16620aebfd.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_af882c16620aebfd = { + 0xaf882c16620aebfd, b_af882c16620aebfd.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_af882c16620aebfd, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_b991ba11fcd5b310 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 16, 179, 213, 252, 17, 186, 145, 185, + 35, 0, 0, 0, 4, 0, 0, 0, + 208, 242, 114, 206, 2, 183, 248, 153, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 122, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 83, 116, 97, 116, + 117, 115, 46, 107, 83, 101, 114, 118, + 105, 99, 101, 71, 112, 115, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b991ba11fcd5b310 = b_b991ba11fcd5b310.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_b991ba11fcd5b310 = { + 0xb991ba11fcd5b310, b_b991ba11fcd5b310.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_b991ba11fcd5b310, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_e1c96846d0e0fb3c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 60, 251, 224, 208, 70, 104, 201, 225, + 35, 0, 0, 0, 4, 0, 0, 0, + 208, 242, 114, 206, 2, 183, 248, 153, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 83, 116, 97, 116, + 117, 115, 46, 107, 83, 101, 114, 118, + 105, 99, 101, 71, 108, 111, 110, 97, + 115, 115, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e1c96846d0e0fb3c = b_e1c96846d0e0fb3c.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_e1c96846d0e0fb3c = { + 0xe1c96846d0e0fb3c, b_e1c96846d0e0fb3c.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_e1c96846d0e0fb3c, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_f697d543703b3e04 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 4, 62, 59, 112, 67, 213, 151, 246, + 35, 0, 0, 0, 4, 0, 0, 0, + 208, 242, 114, 206, 2, 183, 248, 153, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 83, 116, 97, 116, + 117, 115, 46, 107, 83, 101, 114, 118, + 105, 99, 101, 67, 111, 109, 112, 97, + 115, 115, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 4, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f697d543703b3e04 = b_f697d543703b3e04.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_f697d543703b3e04 = { + 0xf697d543703b3e04, b_f697d543703b3e04.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_f697d543703b3e04, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_c136e62a25dcc552 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 82, 197, 220, 37, 42, 230, 54, 193, + 35, 0, 0, 0, 4, 0, 0, 0, + 208, 242, 114, 206, 2, 183, 248, 153, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 78, 97, + 118, 83, 97, 116, 83, 116, 97, 116, + 117, 115, 46, 107, 83, 101, 114, 118, + 105, 99, 101, 71, 97, 108, 105, 108, + 101, 111, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 8, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c136e62a25dcc552 = b_c136e62a25dcc552.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c136e62a25dcc552 = { + 0xc136e62a25dcc552, b_c136e62a25dcc552.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c136e62a25dcc552, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<73> b_e5f170372b28651b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 27, 101, 40, 43, 55, 112, 241, 229, + 22, 0, 0, 0, 1, 0, 0, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 80, 111, + 105, 110, 116, 67, 108, 111, 117, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 96, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 105, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 221, 163, 247, 98, 81, 48, 23, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 104, 97, 110, 110, 101, 108, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 31, 137, 80, 78, 131, 185, 98, 215, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e5f170372b28651b = b_e5f170372b28651b.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_e5f170372b28651b[] = { + &s_bd17305162f7a3dd, + &s_cf9a8bcf03922937, + &s_d762b9834e50891f, +}; +static const uint16_t m_e5f170372b28651b[] = {2, 0, 1}; +static const uint16_t i_e5f170372b28651b[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_e5f170372b28651b = { + 0xe5f170372b28651b, b_e5f170372b28651b.words, 73, d_e5f170372b28651b, m_e5f170372b28651b, + 3, 3, i_e5f170372b28651b, nullptr, nullptr, { &s_e5f170372b28651b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<160> b_c99d10e506253be5 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 229, 59, 37, 6, 229, 16, 157, 201, + 22, 0, 0, 0, 1, 0, 3, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 255, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 80, 111, + 105, 110, 116, 67, 108, 111, 117, 100, + 50, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 36, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 0, 0, 0, 3, 0, 1, 0, + 252, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 64, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 1, 0, 0, 3, 0, 1, 0, + 36, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 1, 0, 0, 3, 0, 1, 0, + 40, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 65, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 44, 1, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 105, 103, 104, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 100, 116, 104, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 101, 108, 100, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 58, 101, 187, 56, 183, 73, 22, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 115, 66, 105, 103, 101, 110, 100, + 105, 97, 110, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 105, 110, 116, 83, 116, 101, + 112, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 119, 83, 116, 101, 112, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 115, 68, 101, 110, 115, 101, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c99d10e506253be5 = b_c99d10e506253be5.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c99d10e506253be5[] = { + &s_cf9a8bcf03922937, + &s_f51649b738bb653a, +}; +static const uint16_t m_c99d10e506253be5[] = {7, 3, 0, 1, 4, 8, 5, 6, 2}; +static const uint16_t i_c99d10e506253be5[] = {0, 1, 2, 3, 4, 5, 6, 7, 8}; +const ::capnp::_::RawSchema s_c99d10e506253be5 = { + 0xc99d10e506253be5, b_c99d10e506253be5.words, 160, d_c99d10e506253be5, m_c99d10e506253be5, + 2, 9, i_c99d10e506253be5, nullptr, nullptr, { &s_c99d10e506253be5, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<106> b_f51649b738bb653a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 58, 101, 187, 56, 183, 73, 22, 245, + 22, 0, 0, 0, 1, 0, 2, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 135, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 80, 111, + 105, 110, 116, 70, 105, 101, 108, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 1, 0, 1, 0, + 31, 94, 124, 26, 187, 159, 44, 242, + 57, 0, 0, 0, 50, 0, 0, 0, + 202, 98, 161, 203, 20, 95, 116, 131, + 53, 0, 0, 0, 58, 0, 0, 0, + 171, 66, 188, 133, 200, 216, 182, 192, + 49, 0, 0, 0, 58, 0, 0, 0, + 180, 150, 114, 79, 76, 4, 139, 236, + 45, 0, 0, 0, 66, 0, 0, 0, + 197, 70, 219, 61, 208, 61, 140, 129, + 41, 0, 0, 0, 58, 0, 0, 0, + 149, 208, 211, 160, 247, 202, 148, 185, + 37, 0, 0, 0, 66, 0, 0, 0, + 157, 112, 3, 161, 75, 239, 228, 186, + 33, 0, 0, 0, 74, 0, 0, 0, + 182, 90, 61, 100, 239, 228, 208, 234, + 33, 0, 0, 0, 74, 0, 0, 0, + 107, 73, 110, 116, 56, 0, 0, 0, + 107, 85, 105, 110, 116, 56, 0, 0, + 107, 73, 110, 116, 49, 54, 0, 0, + 107, 85, 105, 110, 116, 49, 54, 0, + 107, 73, 110, 116, 51, 50, 0, 0, + 107, 85, 105, 110, 116, 51, 50, 0, + 107, 70, 108, 111, 97, 116, 51, 50, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 70, 108, 111, 97, 116, 54, 52, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 102, 102, 115, 101, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 116, 121, 112, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 117, 110, 116, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f51649b738bb653a = b_f51649b738bb653a.words; +#if !CAPNP_LITE +static const uint16_t m_f51649b738bb653a[] = {3, 2, 0, 1}; +static const uint16_t i_f51649b738bb653a[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_f51649b738bb653a = { + 0xf51649b738bb653a, b_f51649b738bb653a.words, 106, nullptr, m_f51649b738bb653a, + 0, 4, i_f51649b738bb653a, nullptr, nullptr, { &s_f51649b738bb653a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<25> b_f22c9fbb1a7c5e1f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 31, 94, 124, 26, 187, 159, 44, 242, + 33, 0, 0, 0, 4, 0, 0, 0, + 58, 101, 187, 56, 183, 73, 22, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 3, 0, 1, 0, + 44, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 80, 111, + 105, 110, 116, 70, 105, 101, 108, 100, + 46, 107, 73, 110, 116, 56, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f22c9fbb1a7c5e1f = b_f22c9fbb1a7c5e1f.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_f22c9fbb1a7c5e1f = { + 0xf22c9fbb1a7c5e1f, b_f22c9fbb1a7c5e1f.words, 25, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_f22c9fbb1a7c5e1f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<25> b_83745f14cba162ca = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 202, 98, 161, 203, 20, 95, 116, 131, + 33, 0, 0, 0, 4, 0, 0, 0, + 58, 101, 187, 56, 183, 73, 22, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 66, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 3, 0, 1, 0, + 44, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 80, 111, + 105, 110, 116, 70, 105, 101, 108, 100, + 46, 107, 85, 105, 110, 116, 56, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_83745f14cba162ca = b_83745f14cba162ca.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_83745f14cba162ca = { + 0x83745f14cba162ca, b_83745f14cba162ca.words, 25, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_83745f14cba162ca, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<25> b_c0b6d8c885bc42ab = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 171, 66, 188, 133, 200, 216, 182, 192, + 33, 0, 0, 0, 4, 0, 0, 0, + 58, 101, 187, 56, 183, 73, 22, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 66, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 3, 0, 1, 0, + 44, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 80, 111, + 105, 110, 116, 70, 105, 101, 108, 100, + 46, 107, 73, 110, 116, 49, 54, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c0b6d8c885bc42ab = b_c0b6d8c885bc42ab.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c0b6d8c885bc42ab = { + 0xc0b6d8c885bc42ab, b_c0b6d8c885bc42ab.words, 25, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c0b6d8c885bc42ab, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_ec8b044c4f7296b4 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 180, 150, 114, 79, 76, 4, 139, 236, + 33, 0, 0, 0, 4, 0, 0, 0, + 58, 101, 187, 56, 183, 73, 22, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 80, 111, + 105, 110, 116, 70, 105, 101, 108, 100, + 46, 107, 85, 105, 110, 116, 49, 54, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 4, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ec8b044c4f7296b4 = b_ec8b044c4f7296b4.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_ec8b044c4f7296b4 = { + 0xec8b044c4f7296b4, b_ec8b044c4f7296b4.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_ec8b044c4f7296b4, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<25> b_818c3dd03ddb46c5 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 197, 70, 219, 61, 208, 61, 140, 129, + 33, 0, 0, 0, 4, 0, 0, 0, + 58, 101, 187, 56, 183, 73, 22, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 66, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 3, 0, 1, 0, + 44, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 80, 111, + 105, 110, 116, 70, 105, 101, 108, 100, + 46, 107, 73, 110, 116, 51, 50, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 5, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_818c3dd03ddb46c5 = b_818c3dd03ddb46c5.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_818c3dd03ddb46c5 = { + 0x818c3dd03ddb46c5, b_818c3dd03ddb46c5.words, 25, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_818c3dd03ddb46c5, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_b994caf7a0d3d095 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 149, 208, 211, 160, 247, 202, 148, 185, + 33, 0, 0, 0, 4, 0, 0, 0, + 58, 101, 187, 56, 183, 73, 22, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 80, 111, + 105, 110, 116, 70, 105, 101, 108, 100, + 46, 107, 85, 105, 110, 116, 51, 50, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 6, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b994caf7a0d3d095 = b_b994caf7a0d3d095.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_b994caf7a0d3d095 = { + 0xb994caf7a0d3d095, b_b994caf7a0d3d095.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_b994caf7a0d3d095, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_bae4ef4ba103709d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 157, 112, 3, 161, 75, 239, 228, 186, + 33, 0, 0, 0, 4, 0, 0, 0, + 58, 101, 187, 56, 183, 73, 22, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 80, 111, + 105, 110, 116, 70, 105, 101, 108, 100, + 46, 107, 70, 108, 111, 97, 116, 51, + 50, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bae4ef4ba103709d = b_bae4ef4ba103709d.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_bae4ef4ba103709d = { + 0xbae4ef4ba103709d, b_bae4ef4ba103709d.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_bae4ef4ba103709d, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_ead0e4ef643d5ab6 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 182, 90, 61, 100, 239, 228, 208, 234, + 33, 0, 0, 0, 4, 0, 0, 0, + 58, 101, 187, 56, 183, 73, 22, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 80, 111, + 105, 110, 116, 70, 105, 101, 108, 100, + 46, 107, 70, 108, 111, 97, 116, 54, + 52, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 8, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ead0e4ef643d5ab6 = b_ead0e4ef643d5ab6.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_ead0e4ef643d5ab6 = { + 0xead0e4ef643d5ab6, b_ead0e4ef643d5ab6.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_ead0e4ef643d5ab6, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<120> b_9644795f70a86922 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 34, 105, 168, 112, 95, 121, 68, 150, + 22, 0, 0, 0, 1, 0, 3, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 226, 0, 0, 0, + 33, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 82, 97, + 110, 103, 101, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 82, 51, 251, 165, 98, 120, 39, 194, + 9, 0, 0, 0, 98, 0, 0, 0, + 19, 19, 213, 202, 111, 16, 84, 192, + 9, 0, 0, 0, 82, 0, 0, 0, + 107, 85, 108, 116, 114, 97, 115, 111, + 117, 110, 100, 0, 0, 0, 0, 0, + 107, 73, 110, 102, 114, 97, 114, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 0, 0, 0, 3, 0, 1, 0, + 168, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 0, 0, 0, 3, 0, 1, 0, + 176, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 0, 0, 0, 3, 0, 1, 0, + 184, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 100, 105, 97, 116, 105, 111, + 110, 84, 121, 112, 101, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 101, 108, 100, 79, 102, 86, + 105, 101, 119, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 105, 110, 82, 97, 110, 103, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 120, 82, 97, 110, 103, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 110, 103, 101, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9644795f70a86922 = b_9644795f70a86922.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_9644795f70a86922[] = { + &s_cf9a8bcf03922937, +}; +static const uint16_t m_9644795f70a86922[] = {2, 0, 4, 3, 1, 5}; +static const uint16_t i_9644795f70a86922[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_9644795f70a86922 = { + 0x9644795f70a86922, b_9644795f70a86922.words, 120, d_9644795f70a86922, m_9644795f70a86922, + 1, 6, i_9644795f70a86922, nullptr, nullptr, { &s_9644795f70a86922, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<25> b_c2277862a5fb3352 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 82, 51, 251, 165, 98, 120, 39, 194, + 28, 0, 0, 0, 4, 0, 0, 0, + 34, 105, 168, 112, 95, 121, 68, 150, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 66, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 3, 0, 1, 0, + 44, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 82, 97, + 110, 103, 101, 46, 107, 85, 108, 116, + 114, 97, 115, 111, 117, 110, 100, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c2277862a5fb3352 = b_c2277862a5fb3352.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c2277862a5fb3352 = { + 0xc2277862a5fb3352, b_c2277862a5fb3352.words, 25, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c2277862a5fb3352, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<25> b_c054106fcad51313 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 19, 19, 213, 202, 111, 16, 84, 192, + 28, 0, 0, 0, 4, 0, 0, 0, + 34, 105, 168, 112, 95, 121, 68, 150, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 3, 0, 1, 0, + 44, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 82, 97, + 110, 103, 101, 46, 107, 73, 110, 102, + 114, 97, 114, 101, 100, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c054106fcad51313 = b_c054106fcad51313.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c054106fcad51313 = { + 0xc054106fcad51313, b_c054106fcad51313.words, 25, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c054106fcad51313, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<95> b_d0c8dbbf71acaa4a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 74, 170, 172, 113, 191, 219, 200, 208, + 22, 0, 0, 0, 1, 0, 3, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 82, 101, + 103, 105, 111, 110, 79, 102, 73, 110, + 116, 101, 114, 101, 115, 116, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 128, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 0, 0, 0, 3, 0, 1, 0, + 152, 0, 0, 0, 2, 0, 1, 0, + 120, 79, 102, 102, 115, 101, 116, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 79, 102, 102, 115, 101, 116, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 105, 103, 104, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 100, 116, 104, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 111, 82, 101, 99, 116, 105, 102, + 121, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d0c8dbbf71acaa4a = b_d0c8dbbf71acaa4a.words; +#if !CAPNP_LITE +static const uint16_t m_d0c8dbbf71acaa4a[] = {4, 2, 3, 0, 1}; +static const uint16_t i_d0c8dbbf71acaa4a[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_d0c8dbbf71acaa4a = { + 0xd0c8dbbf71acaa4a, b_d0c8dbbf71acaa4a.words, 95, nullptr, m_d0c8dbbf71acaa4a, + 0, 5, i_d0c8dbbf71acaa4a, nullptr, nullptr, { &s_d0c8dbbf71acaa4a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<67> b_d7320ff4657e57fa = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 250, 87, 126, 101, 244, 15, 50, 215, + 22, 0, 0, 0, 1, 0, 2, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 82, 101, + 108, 97, 116, 105, 118, 101, 72, 117, + 109, 105, 100, 105, 116, 121, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 0, 0, 0, 3, 0, 1, 0, + 88, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 0, 0, 0, 3, 0, 1, 0, + 96, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 108, 97, 116, 105, 118, 101, + 72, 117, 109, 105, 100, 105, 116, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 114, 105, 97, 110, 99, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d7320ff4657e57fa = b_d7320ff4657e57fa.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_d7320ff4657e57fa[] = { + &s_cf9a8bcf03922937, +}; +static const uint16_t m_d7320ff4657e57fa[] = {0, 1, 2}; +static const uint16_t i_d7320ff4657e57fa[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_d7320ff4657e57fa = { + 0xd7320ff4657e57fa, b_d7320ff4657e57fa.words, 67, d_d7320ff4657e57fa, m_d7320ff4657e57fa, + 1, 3, i_d7320ff4657e57fa, nullptr, nullptr, { &s_d7320ff4657e57fa, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<66> b_98b9fb09555e515b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 91, 81, 94, 85, 9, 251, 185, 152, + 22, 0, 0, 0, 1, 0, 2, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 84, 101, + 109, 112, 101, 114, 97, 116, 117, 114, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 109, 112, 101, 114, 97, 116, + 117, 114, 101, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 114, 105, 97, 110, 99, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_98b9fb09555e515b = b_98b9fb09555e515b.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_98b9fb09555e515b[] = { + &s_cf9a8bcf03922937, +}; +static const uint16_t m_98b9fb09555e515b[] = {0, 1, 2}; +static const uint16_t i_98b9fb09555e515b[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_98b9fb09555e515b = { + 0x98b9fb09555e515b, b_98b9fb09555e515b.words, 66, d_98b9fb09555e515b, m_98b9fb09555e515b, + 1, 3, i_98b9fb09555e515b, nullptr, nullptr, { &s_98b9fb09555e515b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<64> b_d5e33cff46398867 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 103, 136, 57, 70, 255, 60, 227, 213, + 22, 0, 0, 0, 1, 0, 0, 0, + 145, 95, 183, 241, 95, 3, 171, 170, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 101, 110, 115, + 111, 114, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 84, 105, + 109, 101, 82, 101, 102, 101, 114, 101, + 110, 99, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 82, 101, 102, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 79, 12, 85, 207, 4, 92, 190, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 117, 114, 99, 101, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d5e33cff46398867 = b_d5e33cff46398867.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_d5e33cff46398867[] = { + &s_cf9a8bcf03922937, + &s_ebbe5c04cf550c4f, +}; +static const uint16_t m_d5e33cff46398867[] = {0, 2, 1}; +static const uint16_t i_d5e33cff46398867[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_d5e33cff46398867 = { + 0xd5e33cff46398867, b_d5e33cff46398867.words, 64, d_d5e33cff46398867, m_d5e33cff46398867, + 2, 3, i_d5e33cff46398867, nullptr, nullptr, { &s_d5e33cff46398867, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace mrp { +namespace sensor { + +// BatteryState +constexpr uint16_t BatteryState::_capnpPrivate::dataWordSize; +constexpr uint16_t BatteryState::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind BatteryState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* BatteryState::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_STATUS_UNKNOWN; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_STATUS_CHARGING; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_STATUS_DISCHARGING; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_STATUS_NOT_CHARGING; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_STATUS_FULL; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_HEALTH_UNKNOWN; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_HEALTH_GOOD; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_HEALTH_OVERHEAT; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_HEALTH_DEAD; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_HEALTH_OVERVOLTAGE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_HEALTH_UNSPEC_FAILURE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_HEALTH_COLD; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_TECHNOLOGY_UNKNOWN; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_TECHNOLOGY_NIMH; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_TECHNOLOGY_LION; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_TECHNOLOGY_LIPO; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_TECHNOLOGY_LIFE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_TECHNOLOGY_NICD; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t BatteryState::K_POWER_SUPPLY_TECHNOLOGY_LIMN; +#endif +// CameraInfo +constexpr uint16_t CameraInfo::_capnpPrivate::dataWordSize; +constexpr uint16_t CameraInfo::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind CameraInfo::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CameraInfo::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// ChannelFloat32 +constexpr uint16_t ChannelFloat32::_capnpPrivate::dataWordSize; +constexpr uint16_t ChannelFloat32::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind ChannelFloat32::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ChannelFloat32::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// CompressedImage +constexpr uint16_t CompressedImage::_capnpPrivate::dataWordSize; +constexpr uint16_t CompressedImage::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind CompressedImage::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CompressedImage::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// FluidPressure +constexpr uint16_t FluidPressure::_capnpPrivate::dataWordSize; +constexpr uint16_t FluidPressure::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind FluidPressure::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* FluidPressure::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Illuminance +constexpr uint16_t Illuminance::_capnpPrivate::dataWordSize; +constexpr uint16_t Illuminance::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Illuminance::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Illuminance::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Image +constexpr uint16_t Image::_capnpPrivate::dataWordSize; +constexpr uint16_t Image::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Image::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Image::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Imu +constexpr uint16_t Imu::_capnpPrivate::dataWordSize; +constexpr uint16_t Imu::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Imu::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Imu::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// JointState +constexpr uint16_t JointState::_capnpPrivate::dataWordSize; +constexpr uint16_t JointState::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind JointState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* JointState::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Joy +constexpr uint16_t Joy::_capnpPrivate::dataWordSize; +constexpr uint16_t Joy::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Joy::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Joy::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// JoyFeedback +constexpr uint16_t JoyFeedback::_capnpPrivate::dataWordSize; +constexpr uint16_t JoyFeedback::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind JoyFeedback::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* JoyFeedback::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t JoyFeedback::K_TYPE_LED; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t JoyFeedback::K_TYPE_RUMBLE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t JoyFeedback::K_TYPE_BUZZER; +#endif +// JoyFeedbackArray +constexpr uint16_t JoyFeedbackArray::_capnpPrivate::dataWordSize; +constexpr uint16_t JoyFeedbackArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind JoyFeedbackArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* JoyFeedbackArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// LaserEcho +constexpr uint16_t LaserEcho::_capnpPrivate::dataWordSize; +constexpr uint16_t LaserEcho::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind LaserEcho::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LaserEcho::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// LaserScan +constexpr uint16_t LaserScan::_capnpPrivate::dataWordSize; +constexpr uint16_t LaserScan::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind LaserScan::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LaserScan::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// MagneticField +constexpr uint16_t MagneticField::_capnpPrivate::dataWordSize; +constexpr uint16_t MagneticField::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind MagneticField::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* MagneticField::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// MultiDOFJointState +constexpr uint16_t MultiDOFJointState::_capnpPrivate::dataWordSize; +constexpr uint16_t MultiDOFJointState::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind MultiDOFJointState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* MultiDOFJointState::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// MultiEchoLaserScan +constexpr uint16_t MultiEchoLaserScan::_capnpPrivate::dataWordSize; +constexpr uint16_t MultiEchoLaserScan::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind MultiEchoLaserScan::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* MultiEchoLaserScan::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// NavSatFix +constexpr uint16_t NavSatFix::_capnpPrivate::dataWordSize; +constexpr uint16_t NavSatFix::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind NavSatFix::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavSatFix::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t NavSatFix::K_COVARIANCE_TYPE_UNKNOWN; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t NavSatFix::K_COVARIANCE_TYPE_APPROXIMATED; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t NavSatFix::K_COVARIANCE_TYPE_DIAGONAL_KNOWN; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t NavSatFix::K_COVARIANCE_TYPE_KNOWN; +#endif +// NavSatStatus +constexpr uint16_t NavSatStatus::_capnpPrivate::dataWordSize; +constexpr uint16_t NavSatStatus::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind NavSatStatus::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavSatStatus::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::int8_t NavSatStatus::K_STATUS_NO_FIX; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::int8_t NavSatStatus::K_STATUS_FIX; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::int8_t NavSatStatus::K_STATUS_SBAS_FIX; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::int8_t NavSatStatus::K_STATUS_GBAS_FIX; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint16_t NavSatStatus::K_SERVICE_GPS; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint16_t NavSatStatus::K_SERVICE_GLONASS; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint16_t NavSatStatus::K_SERVICE_COMPASS; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint16_t NavSatStatus::K_SERVICE_GALILEO; +#endif +// PointCloud +constexpr uint16_t PointCloud::_capnpPrivate::dataWordSize; +constexpr uint16_t PointCloud::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind PointCloud::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* PointCloud::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// PointCloud2 +constexpr uint16_t PointCloud2::_capnpPrivate::dataWordSize; +constexpr uint16_t PointCloud2::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind PointCloud2::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* PointCloud2::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// PointField +constexpr uint16_t PointField::_capnpPrivate::dataWordSize; +constexpr uint16_t PointField::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind PointField::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* PointField::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t PointField::K_INT8; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t PointField::K_UINT8; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t PointField::K_INT16; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t PointField::K_UINT16; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t PointField::K_INT32; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t PointField::K_UINT32; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t PointField::K_FLOAT32; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t PointField::K_FLOAT64; +#endif +// Range +constexpr uint16_t Range::_capnpPrivate::dataWordSize; +constexpr uint16_t Range::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Range::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Range::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Range::K_ULTRASOUND; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Range::K_INFRARED; +#endif +// RegionOfInterest +constexpr uint16_t RegionOfInterest::_capnpPrivate::dataWordSize; +constexpr uint16_t RegionOfInterest::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind RegionOfInterest::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* RegionOfInterest::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// RelativeHumidity +constexpr uint16_t RelativeHumidity::_capnpPrivate::dataWordSize; +constexpr uint16_t RelativeHumidity::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind RelativeHumidity::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* RelativeHumidity::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Temperature +constexpr uint16_t Temperature::_capnpPrivate::dataWordSize; +constexpr uint16_t Temperature::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Temperature::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Temperature::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// TimeReference +constexpr uint16_t TimeReference::_capnpPrivate::dataWordSize; +constexpr uint16_t TimeReference::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind TimeReference::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* TimeReference::_capnpPrivate::schema; +#endif // !CAPNP_LITE + + +} // namespace +} // namespace + diff --git a/msg/src/fairomsg/cpp/sensor_msgs.capnp.h b/msg/src/fairomsg/cpp/sensor_msgs.capnp.h new file mode 100644 index 0000000000..e929967d99 --- /dev/null +++ b/msg/src/fairomsg/cpp/sensor_msgs.capnp.h @@ -0,0 +1,7096 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: sensor_msgs.capnp + +#pragma once + +#include +#include + +#if CAPNP_VERSION != 9001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + +#include "geometry_msgs.capnp.h" +#include "std_msgs.capnp.h" + +CAPNP_BEGIN_HEADER + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(bd15f4ee99b7c709); +CAPNP_DECLARE_SCHEMA(f6dbb18f04904c56); +CAPNP_DECLARE_SCHEMA(9f0fc14bcce3b509); +CAPNP_DECLARE_SCHEMA(88255d62bae7ba72); +CAPNP_DECLARE_SCHEMA(e37a09a77db36548); +CAPNP_DECLARE_SCHEMA(f77daebe349abf43); +CAPNP_DECLARE_SCHEMA(d94342ef4d6b688a); +CAPNP_DECLARE_SCHEMA(920c0479404dd9a3); +CAPNP_DECLARE_SCHEMA(81915377cbea9ca1); +CAPNP_DECLARE_SCHEMA(c704fed5f3cfcbfb); +CAPNP_DECLARE_SCHEMA(848b5f18dec87ae4); +CAPNP_DECLARE_SCHEMA(e0bf15442ba8bf9f); +CAPNP_DECLARE_SCHEMA(9897efbbf5df7610); +CAPNP_DECLARE_SCHEMA(dc8735c4c889e2ce); +CAPNP_DECLARE_SCHEMA(e9dbcd280732caea); +CAPNP_DECLARE_SCHEMA(ebcb93c65fcb993f); +CAPNP_DECLARE_SCHEMA(a49ff588bb91c4b8); +CAPNP_DECLARE_SCHEMA(c82d693a6351ffe8); +CAPNP_DECLARE_SCHEMA(bbc4613291c8d162); +CAPNP_DECLARE_SCHEMA(f3032d4ed181995b); +CAPNP_DECLARE_SCHEMA(f008dc403568bd37); +CAPNP_DECLARE_SCHEMA(9360fb5f9d6a4dd5); +CAPNP_DECLARE_SCHEMA(c77609d0af4c8586); +CAPNP_DECLARE_SCHEMA(d762b9834e50891f); +CAPNP_DECLARE_SCHEMA(af0080bb451e1c40); +CAPNP_DECLARE_SCHEMA(81cfa0883626c106); +CAPNP_DECLARE_SCHEMA(cc6e96bbfbc66489); +CAPNP_DECLARE_SCHEMA(9e2aef0d448fbc0b); +CAPNP_DECLARE_SCHEMA(c311a9e61266192f); +CAPNP_DECLARE_SCHEMA(8cb30c6c01fcdcd1); +CAPNP_DECLARE_SCHEMA(d53f12214f104108); +CAPNP_DECLARE_SCHEMA(ab14acd9dc0d006d); +CAPNP_DECLARE_SCHEMA(82cae0282995ae02); +CAPNP_DECLARE_SCHEMA(975c7e0370394cba); +CAPNP_DECLARE_SCHEMA(be6b6184809d6c51); +CAPNP_DECLARE_SCHEMA(f642613fa1f4e6e0); +CAPNP_DECLARE_SCHEMA(bf4722c17bc19160); +CAPNP_DECLARE_SCHEMA(bf2ff955ecb97b19); +CAPNP_DECLARE_SCHEMA(a4113fd6a23d4ec2); +CAPNP_DECLARE_SCHEMA(f1a736981c67827a); +CAPNP_DECLARE_SCHEMA(b7bf766c793fcfe0); +CAPNP_DECLARE_SCHEMA(a97166f93e10128d); +CAPNP_DECLARE_SCHEMA(989e6d3b7cb8bda7); +CAPNP_DECLARE_SCHEMA(fd141d4d6a41b4a7); +CAPNP_DECLARE_SCHEMA(b2eff455a8690c43); +CAPNP_DECLARE_SCHEMA(ce2371d261e77966); +CAPNP_DECLARE_SCHEMA(99f8b702ce72f2d0); +CAPNP_DECLARE_SCHEMA(dd1de888a1851d97); +CAPNP_DECLARE_SCHEMA(965c996533c1ab2b); +CAPNP_DECLARE_SCHEMA(af76bc0ef902601f); +CAPNP_DECLARE_SCHEMA(af882c16620aebfd); +CAPNP_DECLARE_SCHEMA(b991ba11fcd5b310); +CAPNP_DECLARE_SCHEMA(e1c96846d0e0fb3c); +CAPNP_DECLARE_SCHEMA(f697d543703b3e04); +CAPNP_DECLARE_SCHEMA(c136e62a25dcc552); +CAPNP_DECLARE_SCHEMA(e5f170372b28651b); +CAPNP_DECLARE_SCHEMA(c99d10e506253be5); +CAPNP_DECLARE_SCHEMA(f51649b738bb653a); +CAPNP_DECLARE_SCHEMA(f22c9fbb1a7c5e1f); +CAPNP_DECLARE_SCHEMA(83745f14cba162ca); +CAPNP_DECLARE_SCHEMA(c0b6d8c885bc42ab); +CAPNP_DECLARE_SCHEMA(ec8b044c4f7296b4); +CAPNP_DECLARE_SCHEMA(818c3dd03ddb46c5); +CAPNP_DECLARE_SCHEMA(b994caf7a0d3d095); +CAPNP_DECLARE_SCHEMA(bae4ef4ba103709d); +CAPNP_DECLARE_SCHEMA(ead0e4ef643d5ab6); +CAPNP_DECLARE_SCHEMA(9644795f70a86922); +CAPNP_DECLARE_SCHEMA(c2277862a5fb3352); +CAPNP_DECLARE_SCHEMA(c054106fcad51313); +CAPNP_DECLARE_SCHEMA(d0c8dbbf71acaa4a); +CAPNP_DECLARE_SCHEMA(d7320ff4657e57fa); +CAPNP_DECLARE_SCHEMA(98b9fb09555e515b); +CAPNP_DECLARE_SCHEMA(d5e33cff46398867); + +} // namespace schemas +} // namespace capnp + +namespace mrp { +namespace sensor { + +struct BatteryState { + BatteryState() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_POWER_SUPPLY_STATUS_UNKNOWN = 0u; + static constexpr ::uint8_t K_POWER_SUPPLY_STATUS_CHARGING = 1u; + static constexpr ::uint8_t K_POWER_SUPPLY_STATUS_DISCHARGING = 2u; + static constexpr ::uint8_t K_POWER_SUPPLY_STATUS_NOT_CHARGING = 3u; + static constexpr ::uint8_t K_POWER_SUPPLY_STATUS_FULL = 4u; + static constexpr ::uint8_t K_POWER_SUPPLY_HEALTH_UNKNOWN = 0u; + static constexpr ::uint8_t K_POWER_SUPPLY_HEALTH_GOOD = 1u; + static constexpr ::uint8_t K_POWER_SUPPLY_HEALTH_OVERHEAT = 2u; + static constexpr ::uint8_t K_POWER_SUPPLY_HEALTH_DEAD = 3u; + static constexpr ::uint8_t K_POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4u; + static constexpr ::uint8_t K_POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5u; + static constexpr ::uint8_t K_POWER_SUPPLY_HEALTH_COLD = 6u; + static constexpr ::uint8_t K_POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7u; + static constexpr ::uint8_t K_POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8u; + static constexpr ::uint8_t K_POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0u; + static constexpr ::uint8_t K_POWER_SUPPLY_TECHNOLOGY_NIMH = 1u; + static constexpr ::uint8_t K_POWER_SUPPLY_TECHNOLOGY_LION = 2u; + static constexpr ::uint8_t K_POWER_SUPPLY_TECHNOLOGY_LIPO = 3u; + static constexpr ::uint8_t K_POWER_SUPPLY_TECHNOLOGY_LIFE = 4u; + static constexpr ::uint8_t K_POWER_SUPPLY_TECHNOLOGY_NICD = 5u; + static constexpr ::uint8_t K_POWER_SUPPLY_TECHNOLOGY_LIMN = 6u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bd15f4ee99b7c709, 4, 5) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct CameraInfo { + CameraInfo() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c77609d0af4c8586, 2, 7) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct ChannelFloat32 { + ChannelFloat32() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d762b9834e50891f, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct CompressedImage { + CompressedImage() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(af0080bb451e1c40, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct FluidPressure { + FluidPressure() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(81cfa0883626c106, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Illuminance { + Illuminance() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(cc6e96bbfbc66489, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Image { + Image() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9e2aef0d448fbc0b, 2, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Imu { + Imu() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c311a9e61266192f, 0, 7) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct JointState { + JointState() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8cb30c6c01fcdcd1, 0, 5) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Joy { + Joy() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d53f12214f104108, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct JoyFeedback { + JoyFeedback() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_TYPE_LED = 0u; + static constexpr ::uint8_t K_TYPE_RUMBLE = 1u; + static constexpr ::uint8_t K_TYPE_BUZZER = 2u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ab14acd9dc0d006d, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct JoyFeedbackArray { + JoyFeedbackArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f642613fa1f4e6e0, 0, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct LaserEcho { + LaserEcho() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bf4722c17bc19160, 0, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct LaserScan { + LaserScan() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(bf2ff955ecb97b19, 4, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct MagneticField { + MagneticField() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a4113fd6a23d4ec2, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct MultiDOFJointState { + MultiDOFJointState() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f1a736981c67827a, 0, 5) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct MultiEchoLaserScan { + MultiEchoLaserScan() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b7bf766c793fcfe0, 4, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct NavSatFix { + NavSatFix() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_COVARIANCE_TYPE_UNKNOWN = 0u; + static constexpr ::uint8_t K_COVARIANCE_TYPE_APPROXIMATED = 1u; + static constexpr ::uint8_t K_COVARIANCE_TYPE_DIAGONAL_KNOWN = 2u; + static constexpr ::uint8_t K_COVARIANCE_TYPE_KNOWN = 3u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a97166f93e10128d, 4, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct NavSatStatus { + NavSatStatus() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::int8_t K_STATUS_NO_FIX = 1; + static constexpr ::int8_t K_STATUS_FIX = 0; + static constexpr ::int8_t K_STATUS_SBAS_FIX = 1; + static constexpr ::int8_t K_STATUS_GBAS_FIX = 2; + static constexpr ::uint16_t K_SERVICE_GPS = 1u; + static constexpr ::uint16_t K_SERVICE_GLONASS = 2u; + static constexpr ::uint16_t K_SERVICE_COMPASS = 4u; + static constexpr ::uint16_t K_SERVICE_GALILEO = 8u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(99f8b702ce72f2d0, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct PointCloud { + PointCloud() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e5f170372b28651b, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct PointCloud2 { + PointCloud2() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c99d10e506253be5, 3, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct PointField { + PointField() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_INT8 = 1u; + static constexpr ::uint8_t K_UINT8 = 2u; + static constexpr ::uint8_t K_INT16 = 3u; + static constexpr ::uint8_t K_UINT16 = 4u; + static constexpr ::uint8_t K_INT32 = 5u; + static constexpr ::uint8_t K_UINT32 = 6u; + static constexpr ::uint8_t K_FLOAT32 = 7u; + static constexpr ::uint8_t K_FLOAT64 = 8u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f51649b738bb653a, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Range { + Range() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_ULTRASOUND = 0u; + static constexpr ::uint8_t K_INFRARED = 1u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9644795f70a86922, 3, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct RegionOfInterest { + RegionOfInterest() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d0c8dbbf71acaa4a, 3, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct RelativeHumidity { + RelativeHumidity() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d7320ff4657e57fa, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Temperature { + Temperature() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(98b9fb09555e515b, 2, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct TimeReference { + TimeReference() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d5e33cff46398867, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class BatteryState::Reader { +public: + typedef BatteryState Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline float getVoltage() const; + + inline float getTemperature() const; + + inline float getCurrent() const; + + inline float getCharge() const; + + inline float getCapacity() const; + + inline float getDesignCapacity() const; + + inline float getPercentage() const; + + inline ::uint8_t getPowerSupplyStatus() const; + + inline ::uint8_t getPowerSupplyHealth() const; + + inline ::uint8_t getPowerSupplyTechnology() const; + + inline bool getPresent() const; + + inline bool hasCellVoltage() const; + inline ::capnp::List::Reader getCellVoltage() const; + + inline bool hasCellTemperature() const; + inline ::capnp::List::Reader getCellTemperature() const; + + inline bool hasLocation() const; + inline ::capnp::Text::Reader getLocation() const; + + inline bool hasSerialNumber() const; + inline ::capnp::Text::Reader getSerialNumber() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class BatteryState::Builder { +public: + typedef BatteryState Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline float getVoltage(); + inline void setVoltage(float value); + + inline float getTemperature(); + inline void setTemperature(float value); + + inline float getCurrent(); + inline void setCurrent(float value); + + inline float getCharge(); + inline void setCharge(float value); + + inline float getCapacity(); + inline void setCapacity(float value); + + inline float getDesignCapacity(); + inline void setDesignCapacity(float value); + + inline float getPercentage(); + inline void setPercentage(float value); + + inline ::uint8_t getPowerSupplyStatus(); + inline void setPowerSupplyStatus( ::uint8_t value); + + inline ::uint8_t getPowerSupplyHealth(); + inline void setPowerSupplyHealth( ::uint8_t value); + + inline ::uint8_t getPowerSupplyTechnology(); + inline void setPowerSupplyTechnology( ::uint8_t value); + + inline bool getPresent(); + inline void setPresent(bool value); + + inline bool hasCellVoltage(); + inline ::capnp::List::Builder getCellVoltage(); + inline void setCellVoltage( ::capnp::List::Reader value); + inline void setCellVoltage(::kj::ArrayPtr value); + inline ::capnp::List::Builder initCellVoltage(unsigned int size); + inline void adoptCellVoltage(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownCellVoltage(); + + inline bool hasCellTemperature(); + inline ::capnp::List::Builder getCellTemperature(); + inline void setCellTemperature( ::capnp::List::Reader value); + inline void setCellTemperature(::kj::ArrayPtr value); + inline ::capnp::List::Builder initCellTemperature(unsigned int size); + inline void adoptCellTemperature(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownCellTemperature(); + + inline bool hasLocation(); + inline ::capnp::Text::Builder getLocation(); + inline void setLocation( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initLocation(unsigned int size); + inline void adoptLocation(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownLocation(); + + inline bool hasSerialNumber(); + inline ::capnp::Text::Builder getSerialNumber(); + inline void setSerialNumber( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initSerialNumber(unsigned int size); + inline void adoptSerialNumber(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownSerialNumber(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class BatteryState::Pipeline { +public: + typedef BatteryState Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CameraInfo::Reader { +public: + typedef CameraInfo Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline ::uint32_t getHeight() const; + + inline ::uint32_t getWidth() const; + + inline bool hasDistortionModel() const; + inline ::capnp::Text::Reader getDistortionModel() const; + + inline bool hasD() const; + inline ::capnp::List::Reader getD() const; + + inline bool hasK() const; + inline ::capnp::List::Reader getK() const; + + inline bool hasR() const; + inline ::capnp::List::Reader getR() const; + + inline bool hasP() const; + inline ::capnp::List::Reader getP() const; + + inline ::uint32_t getBinningX() const; + + inline ::uint32_t getBinningY() const; + + inline bool hasRoi() const; + inline ::mrp::sensor::RegionOfInterest::Reader getRoi() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CameraInfo::Builder { +public: + typedef CameraInfo Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline ::uint32_t getHeight(); + inline void setHeight( ::uint32_t value); + + inline ::uint32_t getWidth(); + inline void setWidth( ::uint32_t value); + + inline bool hasDistortionModel(); + inline ::capnp::Text::Builder getDistortionModel(); + inline void setDistortionModel( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initDistortionModel(unsigned int size); + inline void adoptDistortionModel(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownDistortionModel(); + + inline bool hasD(); + inline ::capnp::List::Builder getD(); + inline void setD( ::capnp::List::Reader value); + inline void setD(::kj::ArrayPtr value); + inline ::capnp::List::Builder initD(unsigned int size); + inline void adoptD(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownD(); + + inline bool hasK(); + inline ::capnp::List::Builder getK(); + inline void setK( ::capnp::List::Reader value); + inline void setK(::kj::ArrayPtr value); + inline ::capnp::List::Builder initK(unsigned int size); + inline void adoptK(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownK(); + + inline bool hasR(); + inline ::capnp::List::Builder getR(); + inline void setR( ::capnp::List::Reader value); + inline void setR(::kj::ArrayPtr value); + inline ::capnp::List::Builder initR(unsigned int size); + inline void adoptR(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownR(); + + inline bool hasP(); + inline ::capnp::List::Builder getP(); + inline void setP( ::capnp::List::Reader value); + inline void setP(::kj::ArrayPtr value); + inline ::capnp::List::Builder initP(unsigned int size); + inline void adoptP(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownP(); + + inline ::uint32_t getBinningX(); + inline void setBinningX( ::uint32_t value); + + inline ::uint32_t getBinningY(); + inline void setBinningY( ::uint32_t value); + + inline bool hasRoi(); + inline ::mrp::sensor::RegionOfInterest::Builder getRoi(); + inline void setRoi( ::mrp::sensor::RegionOfInterest::Reader value); + inline ::mrp::sensor::RegionOfInterest::Builder initRoi(); + inline void adoptRoi(::capnp::Orphan< ::mrp::sensor::RegionOfInterest>&& value); + inline ::capnp::Orphan< ::mrp::sensor::RegionOfInterest> disownRoi(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CameraInfo::Pipeline { +public: + typedef CameraInfo Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::sensor::RegionOfInterest::Pipeline getRoi(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ChannelFloat32::Reader { +public: + typedef ChannelFloat32 Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline bool hasValues() const; + inline ::capnp::List::Reader getValues() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ChannelFloat32::Builder { +public: + typedef ChannelFloat32 Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline bool hasValues(); + inline ::capnp::List::Builder getValues(); + inline void setValues( ::capnp::List::Reader value); + inline void setValues(::kj::ArrayPtr value); + inline ::capnp::List::Builder initValues(unsigned int size); + inline void adoptValues(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownValues(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ChannelFloat32::Pipeline { +public: + typedef ChannelFloat32 Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class CompressedImage::Reader { +public: + typedef CompressedImage Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasFormat() const; + inline ::capnp::Text::Reader getFormat() const; + + inline bool hasData() const; + inline ::capnp::Data::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class CompressedImage::Builder { +public: + typedef CompressedImage Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasFormat(); + inline ::capnp::Text::Builder getFormat(); + inline void setFormat( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initFormat(unsigned int size); + inline void adoptFormat(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownFormat(); + + inline bool hasData(); + inline ::capnp::Data::Builder getData(); + inline void setData( ::capnp::Data::Reader value); + inline ::capnp::Data::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::Data>&& value); + inline ::capnp::Orphan< ::capnp::Data> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class CompressedImage::Pipeline { +public: + typedef CompressedImage Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class FluidPressure::Reader { +public: + typedef FluidPressure Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline double getFluidPressure() const; + + inline double getVariance() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class FluidPressure::Builder { +public: + typedef FluidPressure Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline double getFluidPressure(); + inline void setFluidPressure(double value); + + inline double getVariance(); + inline void setVariance(double value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class FluidPressure::Pipeline { +public: + typedef FluidPressure Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Illuminance::Reader { +public: + typedef Illuminance Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline double getIlluminance() const; + + inline double getVariance() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Illuminance::Builder { +public: + typedef Illuminance Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline double getIlluminance(); + inline void setIlluminance(double value); + + inline double getVariance(); + inline void setVariance(double value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Illuminance::Pipeline { +public: + typedef Illuminance Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Image::Reader { +public: + typedef Image Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline ::uint32_t getHeight() const; + + inline ::uint32_t getWidth() const; + + inline bool hasEncoding() const; + inline ::capnp::Text::Reader getEncoding() const; + + inline ::uint8_t getIsBigendian() const; + + inline ::uint32_t getStep() const; + + inline bool hasData() const; + inline ::capnp::Data::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Image::Builder { +public: + typedef Image Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline ::uint32_t getHeight(); + inline void setHeight( ::uint32_t value); + + inline ::uint32_t getWidth(); + inline void setWidth( ::uint32_t value); + + inline bool hasEncoding(); + inline ::capnp::Text::Builder getEncoding(); + inline void setEncoding( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initEncoding(unsigned int size); + inline void adoptEncoding(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownEncoding(); + + inline ::uint8_t getIsBigendian(); + inline void setIsBigendian( ::uint8_t value); + + inline ::uint32_t getStep(); + inline void setStep( ::uint32_t value); + + inline bool hasData(); + inline ::capnp::Data::Builder getData(); + inline void setData( ::capnp::Data::Reader value); + inline ::capnp::Data::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::Data>&& value); + inline ::capnp::Orphan< ::capnp::Data> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Image::Pipeline { +public: + typedef Image Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Imu::Reader { +public: + typedef Imu Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasOrientation() const; + inline ::mrp::geometry::Quaternion::Reader getOrientation() const; + + inline bool hasOrientationCovariance() const; + inline ::capnp::List::Reader getOrientationCovariance() const; + + inline bool hasAngularVelocity() const; + inline ::mrp::geometry::Vector3::Reader getAngularVelocity() const; + + inline bool hasAngularVelocityCovariance() const; + inline ::capnp::List::Reader getAngularVelocityCovariance() const; + + inline bool hasLinearAcceleration() const; + inline ::mrp::geometry::Vector3::Reader getLinearAcceleration() const; + + inline bool hasLinearAccelerationCovariance() const; + inline ::capnp::List::Reader getLinearAccelerationCovariance() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Imu::Builder { +public: + typedef Imu Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasOrientation(); + inline ::mrp::geometry::Quaternion::Builder getOrientation(); + inline void setOrientation( ::mrp::geometry::Quaternion::Reader value); + inline ::mrp::geometry::Quaternion::Builder initOrientation(); + inline void adoptOrientation(::capnp::Orphan< ::mrp::geometry::Quaternion>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Quaternion> disownOrientation(); + + inline bool hasOrientationCovariance(); + inline ::capnp::List::Builder getOrientationCovariance(); + inline void setOrientationCovariance( ::capnp::List::Reader value); + inline void setOrientationCovariance(::kj::ArrayPtr value); + inline ::capnp::List::Builder initOrientationCovariance(unsigned int size); + inline void adoptOrientationCovariance(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownOrientationCovariance(); + + inline bool hasAngularVelocity(); + inline ::mrp::geometry::Vector3::Builder getAngularVelocity(); + inline void setAngularVelocity( ::mrp::geometry::Vector3::Reader value); + inline ::mrp::geometry::Vector3::Builder initAngularVelocity(); + inline void adoptAngularVelocity(::capnp::Orphan< ::mrp::geometry::Vector3>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Vector3> disownAngularVelocity(); + + inline bool hasAngularVelocityCovariance(); + inline ::capnp::List::Builder getAngularVelocityCovariance(); + inline void setAngularVelocityCovariance( ::capnp::List::Reader value); + inline void setAngularVelocityCovariance(::kj::ArrayPtr value); + inline ::capnp::List::Builder initAngularVelocityCovariance(unsigned int size); + inline void adoptAngularVelocityCovariance(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownAngularVelocityCovariance(); + + inline bool hasLinearAcceleration(); + inline ::mrp::geometry::Vector3::Builder getLinearAcceleration(); + inline void setLinearAcceleration( ::mrp::geometry::Vector3::Reader value); + inline ::mrp::geometry::Vector3::Builder initLinearAcceleration(); + inline void adoptLinearAcceleration(::capnp::Orphan< ::mrp::geometry::Vector3>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Vector3> disownLinearAcceleration(); + + inline bool hasLinearAccelerationCovariance(); + inline ::capnp::List::Builder getLinearAccelerationCovariance(); + inline void setLinearAccelerationCovariance( ::capnp::List::Reader value); + inline void setLinearAccelerationCovariance(::kj::ArrayPtr value); + inline ::capnp::List::Builder initLinearAccelerationCovariance(unsigned int size); + inline void adoptLinearAccelerationCovariance(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownLinearAccelerationCovariance(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Imu::Pipeline { +public: + typedef Imu Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Quaternion::Pipeline getOrientation(); + inline ::mrp::geometry::Vector3::Pipeline getAngularVelocity(); + inline ::mrp::geometry::Vector3::Pipeline getLinearAcceleration(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class JointState::Reader { +public: + typedef JointState Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasName() const; + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader getName() const; + + inline bool hasPosition() const; + inline ::capnp::List::Reader getPosition() const; + + inline bool hasVelocity() const; + inline ::capnp::List::Reader getVelocity() const; + + inline bool hasEffort() const; + inline ::capnp::List::Reader getEffort() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JointState::Builder { +public: + typedef JointState Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasName(); + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder getName(); + inline void setName( ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader value); + inline void setName(::kj::ArrayPtr value); + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>> disownName(); + + inline bool hasPosition(); + inline ::capnp::List::Builder getPosition(); + inline void setPosition( ::capnp::List::Reader value); + inline void setPosition(::kj::ArrayPtr value); + inline ::capnp::List::Builder initPosition(unsigned int size); + inline void adoptPosition(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownPosition(); + + inline bool hasVelocity(); + inline ::capnp::List::Builder getVelocity(); + inline void setVelocity( ::capnp::List::Reader value); + inline void setVelocity(::kj::ArrayPtr value); + inline ::capnp::List::Builder initVelocity(unsigned int size); + inline void adoptVelocity(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownVelocity(); + + inline bool hasEffort(); + inline ::capnp::List::Builder getEffort(); + inline void setEffort( ::capnp::List::Reader value); + inline void setEffort(::kj::ArrayPtr value); + inline ::capnp::List::Builder initEffort(unsigned int size); + inline void adoptEffort(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownEffort(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JointState::Pipeline { +public: + typedef JointState Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Joy::Reader { +public: + typedef Joy Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasAxes() const; + inline ::capnp::List::Reader getAxes() const; + + inline bool hasButtons() const; + inline ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Reader getButtons() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Joy::Builder { +public: + typedef Joy Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasAxes(); + inline ::capnp::List::Builder getAxes(); + inline void setAxes( ::capnp::List::Reader value); + inline void setAxes(::kj::ArrayPtr value); + inline ::capnp::List::Builder initAxes(unsigned int size); + inline void adoptAxes(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownAxes(); + + inline bool hasButtons(); + inline ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Builder getButtons(); + inline void setButtons( ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Reader value); + inline void setButtons(::kj::ArrayPtr value); + inline ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Builder initButtons(unsigned int size); + inline void adoptButtons(::capnp::Orphan< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>> disownButtons(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Joy::Pipeline { +public: + typedef Joy Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class JoyFeedback::Reader { +public: + typedef JoyFeedback Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint8_t getType() const; + + inline ::uint8_t getId() const; + + inline float getIntensity() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JoyFeedback::Builder { +public: + typedef JoyFeedback Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint8_t getType(); + inline void setType( ::uint8_t value); + + inline ::uint8_t getId(); + inline void setId( ::uint8_t value); + + inline float getIntensity(); + inline void setIntensity(float value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JoyFeedback::Pipeline { +public: + typedef JoyFeedback Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class JoyFeedbackArray::Reader { +public: + typedef JoyFeedbackArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasArray() const; + inline ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>::Reader getArray() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JoyFeedbackArray::Builder { +public: + typedef JoyFeedbackArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasArray(); + inline ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>::Builder getArray(); + inline void setArray( ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>::Builder initArray(unsigned int size); + inline void adoptArray(::capnp::Orphan< ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>> disownArray(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JoyFeedbackArray::Pipeline { +public: + typedef JoyFeedbackArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class LaserEcho::Reader { +public: + typedef LaserEcho Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasEchoes() const; + inline ::capnp::List::Reader getEchoes() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class LaserEcho::Builder { +public: + typedef LaserEcho Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasEchoes(); + inline ::capnp::List::Builder getEchoes(); + inline void setEchoes( ::capnp::List::Reader value); + inline void setEchoes(::kj::ArrayPtr value); + inline ::capnp::List::Builder initEchoes(unsigned int size); + inline void adoptEchoes(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownEchoes(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class LaserEcho::Pipeline { +public: + typedef LaserEcho Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class LaserScan::Reader { +public: + typedef LaserScan Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline float getAngleMin() const; + + inline float getAngleMax() const; + + inline float getAngleIncrement() const; + + inline float getTimeIncrement() const; + + inline float getScanTime() const; + + inline float getRangeMin() const; + + inline float getRangeMax() const; + + inline bool hasRanges() const; + inline ::capnp::List::Reader getRanges() const; + + inline bool hasIntensities() const; + inline ::capnp::List::Reader getIntensities() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class LaserScan::Builder { +public: + typedef LaserScan Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline float getAngleMin(); + inline void setAngleMin(float value); + + inline float getAngleMax(); + inline void setAngleMax(float value); + + inline float getAngleIncrement(); + inline void setAngleIncrement(float value); + + inline float getTimeIncrement(); + inline void setTimeIncrement(float value); + + inline float getScanTime(); + inline void setScanTime(float value); + + inline float getRangeMin(); + inline void setRangeMin(float value); + + inline float getRangeMax(); + inline void setRangeMax(float value); + + inline bool hasRanges(); + inline ::capnp::List::Builder getRanges(); + inline void setRanges( ::capnp::List::Reader value); + inline void setRanges(::kj::ArrayPtr value); + inline ::capnp::List::Builder initRanges(unsigned int size); + inline void adoptRanges(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownRanges(); + + inline bool hasIntensities(); + inline ::capnp::List::Builder getIntensities(); + inline void setIntensities( ::capnp::List::Reader value); + inline void setIntensities(::kj::ArrayPtr value); + inline ::capnp::List::Builder initIntensities(unsigned int size); + inline void adoptIntensities(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownIntensities(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class LaserScan::Pipeline { +public: + typedef LaserScan Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class MagneticField::Reader { +public: + typedef MagneticField Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasMagneticField() const; + inline ::mrp::geometry::Vector3::Reader getMagneticField() const; + + inline bool hasMagneticFieldCovariance() const; + inline ::capnp::List::Reader getMagneticFieldCovariance() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class MagneticField::Builder { +public: + typedef MagneticField Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasMagneticField(); + inline ::mrp::geometry::Vector3::Builder getMagneticField(); + inline void setMagneticField( ::mrp::geometry::Vector3::Reader value); + inline ::mrp::geometry::Vector3::Builder initMagneticField(); + inline void adoptMagneticField(::capnp::Orphan< ::mrp::geometry::Vector3>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Vector3> disownMagneticField(); + + inline bool hasMagneticFieldCovariance(); + inline ::capnp::List::Builder getMagneticFieldCovariance(); + inline void setMagneticFieldCovariance( ::capnp::List::Reader value); + inline void setMagneticFieldCovariance(::kj::ArrayPtr value); + inline ::capnp::List::Builder initMagneticFieldCovariance(unsigned int size); + inline void adoptMagneticFieldCovariance(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownMagneticFieldCovariance(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class MagneticField::Pipeline { +public: + typedef MagneticField Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Vector3::Pipeline getMagneticField(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class MultiDOFJointState::Reader { +public: + typedef MultiDOFJointState Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasJointNames() const; + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader getJointNames() const; + + inline bool hasTransforms() const; + inline ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Reader getTransforms() const; + + inline bool hasTwist() const; + inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Reader getTwist() const; + + inline bool hasWrench() const; + inline ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>::Reader getWrench() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class MultiDOFJointState::Builder { +public: + typedef MultiDOFJointState Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasJointNames(); + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder getJointNames(); + inline void setJointNames( ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader value); + inline void setJointNames(::kj::ArrayPtr value); + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder initJointNames(unsigned int size); + inline void adoptJointNames(::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>> disownJointNames(); + + inline bool hasTransforms(); + inline ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Builder getTransforms(); + inline void setTransforms( ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Builder initTransforms(unsigned int size); + inline void adoptTransforms(::capnp::Orphan< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>> disownTransforms(); + + inline bool hasTwist(); + inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Builder getTwist(); + inline void setTwist( ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Builder initTwist(unsigned int size); + inline void adoptTwist(::capnp::Orphan< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>> disownTwist(); + + inline bool hasWrench(); + inline ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>::Builder getWrench(); + inline void setWrench( ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>::Builder initWrench(unsigned int size); + inline void adoptWrench(::capnp::Orphan< ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>> disownWrench(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class MultiDOFJointState::Pipeline { +public: + typedef MultiDOFJointState Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class MultiEchoLaserScan::Reader { +public: + typedef MultiEchoLaserScan Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline float getAngleMin() const; + + inline float getAngleMax() const; + + inline float getAngleIncrement() const; + + inline float getTimeIncrement() const; + + inline float getScanTime() const; + + inline float getRangeMin() const; + + inline float getRangeMax() const; + + inline bool hasRanges() const; + inline ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Reader getRanges() const; + + inline bool hasIntensities() const; + inline ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Reader getIntensities() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class MultiEchoLaserScan::Builder { +public: + typedef MultiEchoLaserScan Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline float getAngleMin(); + inline void setAngleMin(float value); + + inline float getAngleMax(); + inline void setAngleMax(float value); + + inline float getAngleIncrement(); + inline void setAngleIncrement(float value); + + inline float getTimeIncrement(); + inline void setTimeIncrement(float value); + + inline float getScanTime(); + inline void setScanTime(float value); + + inline float getRangeMin(); + inline void setRangeMin(float value); + + inline float getRangeMax(); + inline void setRangeMax(float value); + + inline bool hasRanges(); + inline ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Builder getRanges(); + inline void setRanges( ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Builder initRanges(unsigned int size); + inline void adoptRanges(::capnp::Orphan< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>> disownRanges(); + + inline bool hasIntensities(); + inline ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Builder getIntensities(); + inline void setIntensities( ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Builder initIntensities(unsigned int size); + inline void adoptIntensities(::capnp::Orphan< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>> disownIntensities(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class MultiEchoLaserScan::Pipeline { +public: + typedef MultiEchoLaserScan Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class NavSatFix::Reader { +public: + typedef NavSatFix Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasStatus() const; + inline ::mrp::sensor::NavSatStatus::Reader getStatus() const; + + inline double getLatitude() const; + + inline double getLongitude() const; + + inline double getAltitude() const; + + inline bool hasPositionCovariance() const; + inline ::capnp::List::Reader getPositionCovariance() const; + + inline ::uint8_t getPositionCovarianceType() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class NavSatFix::Builder { +public: + typedef NavSatFix Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasStatus(); + inline ::mrp::sensor::NavSatStatus::Builder getStatus(); + inline void setStatus( ::mrp::sensor::NavSatStatus::Reader value); + inline ::mrp::sensor::NavSatStatus::Builder initStatus(); + inline void adoptStatus(::capnp::Orphan< ::mrp::sensor::NavSatStatus>&& value); + inline ::capnp::Orphan< ::mrp::sensor::NavSatStatus> disownStatus(); + + inline double getLatitude(); + inline void setLatitude(double value); + + inline double getLongitude(); + inline void setLongitude(double value); + + inline double getAltitude(); + inline void setAltitude(double value); + + inline bool hasPositionCovariance(); + inline ::capnp::List::Builder getPositionCovariance(); + inline void setPositionCovariance( ::capnp::List::Reader value); + inline void setPositionCovariance(::kj::ArrayPtr value); + inline ::capnp::List::Builder initPositionCovariance(unsigned int size); + inline void adoptPositionCovariance(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownPositionCovariance(); + + inline ::uint8_t getPositionCovarianceType(); + inline void setPositionCovarianceType( ::uint8_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class NavSatFix::Pipeline { +public: + typedef NavSatFix Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::sensor::NavSatStatus::Pipeline getStatus(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class NavSatStatus::Reader { +public: + typedef NavSatStatus Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::int8_t getStatus() const; + + inline ::uint16_t getService() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class NavSatStatus::Builder { +public: + typedef NavSatStatus Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::int8_t getStatus(); + inline void setStatus( ::int8_t value); + + inline ::uint16_t getService(); + inline void setService( ::uint16_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class NavSatStatus::Pipeline { +public: + typedef NavSatStatus Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class PointCloud::Reader { +public: + typedef PointCloud Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasPoints() const; + inline ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Reader getPoints() const; + + inline bool hasChannels() const; + inline ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>::Reader getChannels() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class PointCloud::Builder { +public: + typedef PointCloud Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasPoints(); + inline ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Builder getPoints(); + inline void setPoints( ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Builder initPoints(unsigned int size); + inline void adoptPoints(::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>> disownPoints(); + + inline bool hasChannels(); + inline ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>::Builder getChannels(); + inline void setChannels( ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>::Builder initChannels(unsigned int size); + inline void adoptChannels(::capnp::Orphan< ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>> disownChannels(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class PointCloud::Pipeline { +public: + typedef PointCloud Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class PointCloud2::Reader { +public: + typedef PointCloud2 Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline ::uint32_t getHeight() const; + + inline ::uint32_t getWidth() const; + + inline bool hasFields() const; + inline ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>::Reader getFields() const; + + inline bool getIsBigendian() const; + + inline ::uint32_t getPointStep() const; + + inline ::uint32_t getRowStep() const; + + inline bool hasData() const; + inline ::capnp::Data::Reader getData() const; + + inline bool getIsDense() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class PointCloud2::Builder { +public: + typedef PointCloud2 Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline ::uint32_t getHeight(); + inline void setHeight( ::uint32_t value); + + inline ::uint32_t getWidth(); + inline void setWidth( ::uint32_t value); + + inline bool hasFields(); + inline ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>::Builder getFields(); + inline void setFields( ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>::Builder initFields(unsigned int size); + inline void adoptFields(::capnp::Orphan< ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>> disownFields(); + + inline bool getIsBigendian(); + inline void setIsBigendian(bool value); + + inline ::uint32_t getPointStep(); + inline void setPointStep( ::uint32_t value); + + inline ::uint32_t getRowStep(); + inline void setRowStep( ::uint32_t value); + + inline bool hasData(); + inline ::capnp::Data::Builder getData(); + inline void setData( ::capnp::Data::Reader value); + inline ::capnp::Data::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::Data>&& value); + inline ::capnp::Orphan< ::capnp::Data> disownData(); + + inline bool getIsDense(); + inline void setIsDense(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class PointCloud2::Pipeline { +public: + typedef PointCloud2 Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class PointField::Reader { +public: + typedef PointField Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline ::uint32_t getOffset() const; + + inline ::uint8_t getDatatype() const; + + inline ::uint32_t getCount() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class PointField::Builder { +public: + typedef PointField Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline ::uint32_t getOffset(); + inline void setOffset( ::uint32_t value); + + inline ::uint8_t getDatatype(); + inline void setDatatype( ::uint8_t value); + + inline ::uint32_t getCount(); + inline void setCount( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class PointField::Pipeline { +public: + typedef PointField Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Range::Reader { +public: + typedef Range Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline ::uint8_t getRadiationType() const; + + inline float getFieldOfView() const; + + inline float getMinRange() const; + + inline float getMaxRange() const; + + inline float getRange() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Range::Builder { +public: + typedef Range Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline ::uint8_t getRadiationType(); + inline void setRadiationType( ::uint8_t value); + + inline float getFieldOfView(); + inline void setFieldOfView(float value); + + inline float getMinRange(); + inline void setMinRange(float value); + + inline float getMaxRange(); + inline void setMaxRange(float value); + + inline float getRange(); + inline void setRange(float value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Range::Pipeline { +public: + typedef Range Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class RegionOfInterest::Reader { +public: + typedef RegionOfInterest Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getXOffset() const; + + inline ::uint32_t getYOffset() const; + + inline ::uint32_t getHeight() const; + + inline ::uint32_t getWidth() const; + + inline bool getDoRectify() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class RegionOfInterest::Builder { +public: + typedef RegionOfInterest Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getXOffset(); + inline void setXOffset( ::uint32_t value); + + inline ::uint32_t getYOffset(); + inline void setYOffset( ::uint32_t value); + + inline ::uint32_t getHeight(); + inline void setHeight( ::uint32_t value); + + inline ::uint32_t getWidth(); + inline void setWidth( ::uint32_t value); + + inline bool getDoRectify(); + inline void setDoRectify(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class RegionOfInterest::Pipeline { +public: + typedef RegionOfInterest Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class RelativeHumidity::Reader { +public: + typedef RelativeHumidity Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline double getRelativeHumidity() const; + + inline double getVariance() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class RelativeHumidity::Builder { +public: + typedef RelativeHumidity Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline double getRelativeHumidity(); + inline void setRelativeHumidity(double value); + + inline double getVariance(); + inline void setVariance(double value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class RelativeHumidity::Pipeline { +public: + typedef RelativeHumidity Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Temperature::Reader { +public: + typedef Temperature Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline double getTemperature() const; + + inline double getVariance() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Temperature::Builder { +public: + typedef Temperature Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline double getTemperature(); + inline void setTemperature(double value); + + inline double getVariance(); + inline void setVariance(double value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Temperature::Pipeline { +public: + typedef Temperature Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class TimeReference::Reader { +public: + typedef TimeReference Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasTimeRef() const; + inline ::mrp::std::Time::Reader getTimeRef() const; + + inline bool hasSource() const; + inline ::capnp::Text::Reader getSource() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class TimeReference::Builder { +public: + typedef TimeReference Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasTimeRef(); + inline ::mrp::std::Time::Builder getTimeRef(); + inline void setTimeRef( ::mrp::std::Time::Reader value); + inline ::mrp::std::Time::Builder initTimeRef(); + inline void adoptTimeRef(::capnp::Orphan< ::mrp::std::Time>&& value); + inline ::capnp::Orphan< ::mrp::std::Time> disownTimeRef(); + + inline bool hasSource(); + inline ::capnp::Text::Builder getSource(); + inline void setSource( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initSource(unsigned int size); + inline void adoptSource(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownSource(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class TimeReference::Pipeline { +public: + typedef TimeReference Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::std::Time::Pipeline getTimeRef(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline bool BatteryState::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool BatteryState::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader BatteryState::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder BatteryState::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline BatteryState::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void BatteryState::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder BatteryState::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void BatteryState::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> BatteryState::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline float BatteryState::Reader::getVoltage() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline float BatteryState::Builder::getVoltage() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void BatteryState::Builder::setVoltage(float value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline float BatteryState::Reader::getTemperature() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline float BatteryState::Builder::getTemperature() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void BatteryState::Builder::setTemperature(float value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline float BatteryState::Reader::getCurrent() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline float BatteryState::Builder::getCurrent() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void BatteryState::Builder::setCurrent(float value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline float BatteryState::Reader::getCharge() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline float BatteryState::Builder::getCharge() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void BatteryState::Builder::setCharge(float value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline float BatteryState::Reader::getCapacity() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline float BatteryState::Builder::getCapacity() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline void BatteryState::Builder::setCapacity(float value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); +} + +inline float BatteryState::Reader::getDesignCapacity() const { + return _reader.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline float BatteryState::Builder::getDesignCapacity() { + return _builder.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline void BatteryState::Builder::setDesignCapacity(float value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); +} + +inline float BatteryState::Reader::getPercentage() const { + return _reader.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} + +inline float BatteryState::Builder::getPercentage() { + return _builder.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} +inline void BatteryState::Builder::setPercentage(float value) { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t BatteryState::Reader::getPowerSupplyStatus() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<28>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t BatteryState::Builder::getPowerSupplyStatus() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<28>() * ::capnp::ELEMENTS); +} +inline void BatteryState::Builder::setPowerSupplyStatus( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<28>() * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t BatteryState::Reader::getPowerSupplyHealth() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<29>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t BatteryState::Builder::getPowerSupplyHealth() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<29>() * ::capnp::ELEMENTS); +} +inline void BatteryState::Builder::setPowerSupplyHealth( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<29>() * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t BatteryState::Reader::getPowerSupplyTechnology() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<30>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t BatteryState::Builder::getPowerSupplyTechnology() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<30>() * ::capnp::ELEMENTS); +} +inline void BatteryState::Builder::setPowerSupplyTechnology( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<30>() * ::capnp::ELEMENTS, value); +} + +inline bool BatteryState::Reader::getPresent() const { + return _reader.getDataField( + ::capnp::bounded<248>() * ::capnp::ELEMENTS); +} + +inline bool BatteryState::Builder::getPresent() { + return _builder.getDataField( + ::capnp::bounded<248>() * ::capnp::ELEMENTS); +} +inline void BatteryState::Builder::setPresent(bool value) { + _builder.setDataField( + ::capnp::bounded<248>() * ::capnp::ELEMENTS, value); +} + +inline bool BatteryState::Reader::hasCellVoltage() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool BatteryState::Builder::hasCellVoltage() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader BatteryState::Reader::getCellVoltage() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder BatteryState::Builder::getCellVoltage() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void BatteryState::Builder::setCellVoltage( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void BatteryState::Builder::setCellVoltage(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder BatteryState::Builder::initCellVoltage(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void BatteryState::Builder::adoptCellVoltage( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> BatteryState::Builder::disownCellVoltage() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool BatteryState::Reader::hasCellTemperature() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool BatteryState::Builder::hasCellTemperature() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader BatteryState::Reader::getCellTemperature() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder BatteryState::Builder::getCellTemperature() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void BatteryState::Builder::setCellTemperature( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline void BatteryState::Builder::setCellTemperature(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder BatteryState::Builder::initCellTemperature(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void BatteryState::Builder::adoptCellTemperature( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> BatteryState::Builder::disownCellTemperature() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool BatteryState::Reader::hasLocation() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool BatteryState::Builder::hasLocation() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader BatteryState::Reader::getLocation() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder BatteryState::Builder::getLocation() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void BatteryState::Builder::setLocation( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder BatteryState::Builder::initLocation(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void BatteryState::Builder::adoptLocation( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> BatteryState::Builder::disownLocation() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool BatteryState::Reader::hasSerialNumber() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool BatteryState::Builder::hasSerialNumber() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader BatteryState::Reader::getSerialNumber() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder BatteryState::Builder::getSerialNumber() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void BatteryState::Builder::setSerialNumber( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder BatteryState::Builder::initSerialNumber(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), size); +} +inline void BatteryState::Builder::adoptSerialNumber( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> BatteryState::Builder::disownSerialNumber() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline bool CameraInfo::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool CameraInfo::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader CameraInfo::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder CameraInfo::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline CameraInfo::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void CameraInfo::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder CameraInfo::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CameraInfo::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> CameraInfo::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t CameraInfo::Reader::getHeight() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t CameraInfo::Builder::getHeight() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void CameraInfo::Builder::setHeight( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t CameraInfo::Reader::getWidth() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t CameraInfo::Builder::getWidth() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void CameraInfo::Builder::setWidth( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool CameraInfo::Reader::hasDistortionModel() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool CameraInfo::Builder::hasDistortionModel() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader CameraInfo::Reader::getDistortionModel() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder CameraInfo::Builder::getDistortionModel() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void CameraInfo::Builder::setDistortionModel( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder CameraInfo::Builder::initDistortionModel(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void CameraInfo::Builder::adoptDistortionModel( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> CameraInfo::Builder::disownDistortionModel() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool CameraInfo::Reader::hasD() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool CameraInfo::Builder::hasD() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader CameraInfo::Reader::getD() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder CameraInfo::Builder::getD() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void CameraInfo::Builder::setD( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline void CameraInfo::Builder::setD(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder CameraInfo::Builder::initD(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void CameraInfo::Builder::adoptD( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> CameraInfo::Builder::disownD() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool CameraInfo::Reader::hasK() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool CameraInfo::Builder::hasK() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader CameraInfo::Reader::getK() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder CameraInfo::Builder::getK() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void CameraInfo::Builder::setK( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline void CameraInfo::Builder::setK(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder CameraInfo::Builder::initK(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void CameraInfo::Builder::adoptK( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> CameraInfo::Builder::disownK() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool CameraInfo::Reader::hasR() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool CameraInfo::Builder::hasR() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader CameraInfo::Reader::getR() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder CameraInfo::Builder::getR() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void CameraInfo::Builder::setR( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline void CameraInfo::Builder::setR(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder CameraInfo::Builder::initR(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), size); +} +inline void CameraInfo::Builder::adoptR( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> CameraInfo::Builder::disownR() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline bool CameraInfo::Reader::hasP() const { + return !_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline bool CameraInfo::Builder::hasP() { + return !_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader CameraInfo::Reader::getP() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder CameraInfo::Builder::getP() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline void CameraInfo::Builder::setP( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), value); +} +inline void CameraInfo::Builder::setP(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder CameraInfo::Builder::initP(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), size); +} +inline void CameraInfo::Builder::adoptP( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> CameraInfo::Builder::disownP() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} + +inline ::uint32_t CameraInfo::Reader::getBinningX() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t CameraInfo::Builder::getBinningX() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void CameraInfo::Builder::setBinningX( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t CameraInfo::Reader::getBinningY() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t CameraInfo::Builder::getBinningY() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void CameraInfo::Builder::setBinningY( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline bool CameraInfo::Reader::hasRoi() const { + return !_reader.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS).isNull(); +} +inline bool CameraInfo::Builder::hasRoi() { + return !_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::sensor::RegionOfInterest::Reader CameraInfo::Reader::getRoi() const { + return ::capnp::_::PointerHelpers< ::mrp::sensor::RegionOfInterest>::get(_reader.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS)); +} +inline ::mrp::sensor::RegionOfInterest::Builder CameraInfo::Builder::getRoi() { + return ::capnp::_::PointerHelpers< ::mrp::sensor::RegionOfInterest>::get(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::sensor::RegionOfInterest::Pipeline CameraInfo::Pipeline::getRoi() { + return ::mrp::sensor::RegionOfInterest::Pipeline(_typeless.getPointerField(6)); +} +#endif // !CAPNP_LITE +inline void CameraInfo::Builder::setRoi( ::mrp::sensor::RegionOfInterest::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::sensor::RegionOfInterest>::set(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS), value); +} +inline ::mrp::sensor::RegionOfInterest::Builder CameraInfo::Builder::initRoi() { + return ::capnp::_::PointerHelpers< ::mrp::sensor::RegionOfInterest>::init(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS)); +} +inline void CameraInfo::Builder::adoptRoi( + ::capnp::Orphan< ::mrp::sensor::RegionOfInterest>&& value) { + ::capnp::_::PointerHelpers< ::mrp::sensor::RegionOfInterest>::adopt(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::sensor::RegionOfInterest> CameraInfo::Builder::disownRoi() { + return ::capnp::_::PointerHelpers< ::mrp::sensor::RegionOfInterest>::disown(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS)); +} + +inline bool ChannelFloat32::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool ChannelFloat32::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader ChannelFloat32::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder ChannelFloat32::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void ChannelFloat32::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder ChannelFloat32::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void ChannelFloat32::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> ChannelFloat32::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool ChannelFloat32::Reader::hasValues() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool ChannelFloat32::Builder::hasValues() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader ChannelFloat32::Reader::getValues() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder ChannelFloat32::Builder::getValues() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void ChannelFloat32::Builder::setValues( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void ChannelFloat32::Builder::setValues(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder ChannelFloat32::Builder::initValues(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void ChannelFloat32::Builder::adoptValues( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> ChannelFloat32::Builder::disownValues() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool CompressedImage::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool CompressedImage::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader CompressedImage::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder CompressedImage::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline CompressedImage::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void CompressedImage::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder CompressedImage::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void CompressedImage::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> CompressedImage::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool CompressedImage::Reader::hasFormat() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool CompressedImage::Builder::hasFormat() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader CompressedImage::Reader::getFormat() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder CompressedImage::Builder::getFormat() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void CompressedImage::Builder::setFormat( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder CompressedImage::Builder::initFormat(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void CompressedImage::Builder::adoptFormat( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> CompressedImage::Builder::disownFormat() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool CompressedImage::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool CompressedImage::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Data::Reader CompressedImage::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::Data::Builder CompressedImage::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void CompressedImage::Builder::setData( ::capnp::Data::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::Data::Builder CompressedImage::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Data>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void CompressedImage::Builder::adoptData( + ::capnp::Orphan< ::capnp::Data>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Data> CompressedImage::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool FluidPressure::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool FluidPressure::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader FluidPressure::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder FluidPressure::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline FluidPressure::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void FluidPressure::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder FluidPressure::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void FluidPressure::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> FluidPressure::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline double FluidPressure::Reader::getFluidPressure() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline double FluidPressure::Builder::getFluidPressure() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void FluidPressure::Builder::setFluidPressure(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline double FluidPressure::Reader::getVariance() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double FluidPressure::Builder::getVariance() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void FluidPressure::Builder::setVariance(double value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Illuminance::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Illuminance::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader Illuminance::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder Illuminance::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline Illuminance::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Illuminance::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder Illuminance::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Illuminance::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> Illuminance::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline double Illuminance::Reader::getIlluminance() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline double Illuminance::Builder::getIlluminance() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Illuminance::Builder::setIlluminance(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline double Illuminance::Reader::getVariance() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double Illuminance::Builder::getVariance() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Illuminance::Builder::setVariance(double value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Image::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Image::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader Image::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder Image::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline Image::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Image::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder Image::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Image::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> Image::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t Image::Reader::getHeight() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Image::Builder::getHeight() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Image::Builder::setHeight( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t Image::Reader::getWidth() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Image::Builder::getWidth() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Image::Builder::setWidth( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Image::Reader::hasEncoding() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Image::Builder::hasEncoding() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Image::Reader::getEncoding() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Image::Builder::getEncoding() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Image::Builder::setEncoding( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Image::Builder::initEncoding(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Image::Builder::adoptEncoding( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Image::Builder::disownEncoding() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::uint8_t Image::Reader::getIsBigendian() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t Image::Builder::getIsBigendian() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} +inline void Image::Builder::setIsBigendian( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t Image::Reader::getStep() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Image::Builder::getStep() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void Image::Builder::setStep( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline bool Image::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool Image::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Data::Reader Image::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::Data::Builder Image::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void Image::Builder::setData( ::capnp::Data::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::Data::Builder Image::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Data>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void Image::Builder::adoptData( + ::capnp::Orphan< ::capnp::Data>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Data> Image::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool Imu::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Imu::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader Imu::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder Imu::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline Imu::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Imu::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder Imu::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Imu::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> Imu::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Imu::Reader::hasOrientation() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Imu::Builder::hasOrientation() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Quaternion::Reader Imu::Reader::getOrientation() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Quaternion::Builder Imu::Builder::getOrientation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Quaternion::Pipeline Imu::Pipeline::getOrientation() { + return ::mrp::geometry::Quaternion::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void Imu::Builder::setOrientation( ::mrp::geometry::Quaternion::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Quaternion::Builder Imu::Builder::initOrientation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Imu::Builder::adoptOrientation( + ::capnp::Orphan< ::mrp::geometry::Quaternion>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Quaternion> Imu::Builder::disownOrientation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Imu::Reader::hasOrientationCovariance() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool Imu::Builder::hasOrientationCovariance() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader Imu::Reader::getOrientationCovariance() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder Imu::Builder::getOrientationCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void Imu::Builder::setOrientationCovariance( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline void Imu::Builder::setOrientationCovariance(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder Imu::Builder::initOrientationCovariance(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void Imu::Builder::adoptOrientationCovariance( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> Imu::Builder::disownOrientationCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool Imu::Reader::hasAngularVelocity() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Imu::Builder::hasAngularVelocity() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Vector3::Reader Imu::Reader::getAngularVelocity() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Vector3::Builder Imu::Builder::getAngularVelocity() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Vector3::Pipeline Imu::Pipeline::getAngularVelocity() { + return ::mrp::geometry::Vector3::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void Imu::Builder::setAngularVelocity( ::mrp::geometry::Vector3::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Vector3::Builder Imu::Builder::initAngularVelocity() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Imu::Builder::adoptAngularVelocity( + ::capnp::Orphan< ::mrp::geometry::Vector3>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Vector3> Imu::Builder::disownAngularVelocity() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Imu::Reader::hasAngularVelocityCovariance() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool Imu::Builder::hasAngularVelocityCovariance() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader Imu::Reader::getAngularVelocityCovariance() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder Imu::Builder::getAngularVelocityCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void Imu::Builder::setAngularVelocityCovariance( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline void Imu::Builder::setAngularVelocityCovariance(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder Imu::Builder::initAngularVelocityCovariance(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), size); +} +inline void Imu::Builder::adoptAngularVelocityCovariance( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> Imu::Builder::disownAngularVelocityCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline bool Imu::Reader::hasLinearAcceleration() const { + return !_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline bool Imu::Builder::hasLinearAcceleration() { + return !_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Vector3::Reader Imu::Reader::getLinearAcceleration() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Vector3::Builder Imu::Builder::getLinearAcceleration() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Vector3::Pipeline Imu::Pipeline::getLinearAcceleration() { + return ::mrp::geometry::Vector3::Pipeline(_typeless.getPointerField(5)); +} +#endif // !CAPNP_LITE +inline void Imu::Builder::setLinearAcceleration( ::mrp::geometry::Vector3::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::set(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Vector3::Builder Imu::Builder::initLinearAcceleration() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::init(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline void Imu::Builder::adoptLinearAcceleration( + ::capnp::Orphan< ::mrp::geometry::Vector3>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::adopt(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Vector3> Imu::Builder::disownLinearAcceleration() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::disown(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} + +inline bool Imu::Reader::hasLinearAccelerationCovariance() const { + return !_reader.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS).isNull(); +} +inline bool Imu::Builder::hasLinearAccelerationCovariance() { + return !_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader Imu::Reader::getLinearAccelerationCovariance() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder Imu::Builder::getLinearAccelerationCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS)); +} +inline void Imu::Builder::setLinearAccelerationCovariance( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS), value); +} +inline void Imu::Builder::setLinearAccelerationCovariance(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder Imu::Builder::initLinearAccelerationCovariance(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS), size); +} +inline void Imu::Builder::adoptLinearAccelerationCovariance( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> Imu::Builder::disownLinearAccelerationCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS)); +} + +inline bool JointState::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JointState::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader JointState::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder JointState::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline JointState::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void JointState::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder JointState::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JointState::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> JointState::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JointState::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool JointState::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader JointState::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder JointState::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void JointState::Builder::setName( ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void JointState::Builder::setName(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder JointState::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void JointState::Builder::adoptName( + ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>> JointState::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool JointState::Reader::hasPosition() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool JointState::Builder::hasPosition() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader JointState::Reader::getPosition() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder JointState::Builder::getPosition() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void JointState::Builder::setPosition( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline void JointState::Builder::setPosition(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder JointState::Builder::initPosition(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void JointState::Builder::adoptPosition( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> JointState::Builder::disownPosition() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool JointState::Reader::hasVelocity() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool JointState::Builder::hasVelocity() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader JointState::Reader::getVelocity() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder JointState::Builder::getVelocity() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void JointState::Builder::setVelocity( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline void JointState::Builder::setVelocity(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder JointState::Builder::initVelocity(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void JointState::Builder::adoptVelocity( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> JointState::Builder::disownVelocity() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool JointState::Reader::hasEffort() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool JointState::Builder::hasEffort() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader JointState::Reader::getEffort() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder JointState::Builder::getEffort() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void JointState::Builder::setEffort( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline void JointState::Builder::setEffort(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder JointState::Builder::initEffort(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), size); +} +inline void JointState::Builder::adoptEffort( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> JointState::Builder::disownEffort() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline bool Joy::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Joy::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader Joy::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder Joy::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline Joy::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Joy::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder Joy::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Joy::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> Joy::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Joy::Reader::hasAxes() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Joy::Builder::hasAxes() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader Joy::Reader::getAxes() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder Joy::Builder::getAxes() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Joy::Builder::setAxes( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void Joy::Builder::setAxes(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder Joy::Builder::initAxes(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Joy::Builder::adoptAxes( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> Joy::Builder::disownAxes() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Joy::Reader::hasButtons() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool Joy::Builder::hasButtons() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Reader Joy::Reader::getButtons() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Builder Joy::Builder::getButtons() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void Joy::Builder::setButtons( ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline void Joy::Builder::setButtons(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Builder Joy::Builder::initButtons(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void Joy::Builder::adoptButtons( + ::capnp::Orphan< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>> Joy::Builder::disownButtons() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline ::uint8_t JoyFeedback::Reader::getType() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t JoyFeedback::Builder::getType() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void JoyFeedback::Builder::setType( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t JoyFeedback::Reader::getId() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t JoyFeedback::Builder::getId() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void JoyFeedback::Builder::setId( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline float JoyFeedback::Reader::getIntensity() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline float JoyFeedback::Builder::getIntensity() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void JoyFeedback::Builder::setIntensity(float value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool JoyFeedbackArray::Reader::hasArray() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JoyFeedbackArray::Builder::hasArray() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>::Reader JoyFeedbackArray::Reader::getArray() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>::Builder JoyFeedbackArray::Builder::getArray() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JoyFeedbackArray::Builder::setArray( ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>::Builder JoyFeedbackArray::Builder::initArray(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void JoyFeedbackArray::Builder::adoptArray( + ::capnp::Orphan< ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>> JoyFeedbackArray::Builder::disownArray() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::JoyFeedback, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool LaserEcho::Reader::hasEchoes() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool LaserEcho::Builder::hasEchoes() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader LaserEcho::Reader::getEchoes() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder LaserEcho::Builder::getEchoes() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void LaserEcho::Builder::setEchoes( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline void LaserEcho::Builder::setEchoes(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder LaserEcho::Builder::initEchoes(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void LaserEcho::Builder::adoptEchoes( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> LaserEcho::Builder::disownEchoes() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool LaserScan::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool LaserScan::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader LaserScan::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder LaserScan::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline LaserScan::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void LaserScan::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder LaserScan::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void LaserScan::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> LaserScan::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline float LaserScan::Reader::getAngleMin() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline float LaserScan::Builder::getAngleMin() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void LaserScan::Builder::setAngleMin(float value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline float LaserScan::Reader::getAngleMax() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline float LaserScan::Builder::getAngleMax() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void LaserScan::Builder::setAngleMax(float value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline float LaserScan::Reader::getAngleIncrement() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline float LaserScan::Builder::getAngleIncrement() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void LaserScan::Builder::setAngleIncrement(float value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline float LaserScan::Reader::getTimeIncrement() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline float LaserScan::Builder::getTimeIncrement() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void LaserScan::Builder::setTimeIncrement(float value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline float LaserScan::Reader::getScanTime() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline float LaserScan::Builder::getScanTime() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline void LaserScan::Builder::setScanTime(float value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); +} + +inline float LaserScan::Reader::getRangeMin() const { + return _reader.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline float LaserScan::Builder::getRangeMin() { + return _builder.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline void LaserScan::Builder::setRangeMin(float value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); +} + +inline float LaserScan::Reader::getRangeMax() const { + return _reader.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} + +inline float LaserScan::Builder::getRangeMax() { + return _builder.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} +inline void LaserScan::Builder::setRangeMax(float value) { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, value); +} + +inline bool LaserScan::Reader::hasRanges() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool LaserScan::Builder::hasRanges() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader LaserScan::Reader::getRanges() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder LaserScan::Builder::getRanges() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void LaserScan::Builder::setRanges( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void LaserScan::Builder::setRanges(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder LaserScan::Builder::initRanges(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void LaserScan::Builder::adoptRanges( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> LaserScan::Builder::disownRanges() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool LaserScan::Reader::hasIntensities() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool LaserScan::Builder::hasIntensities() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader LaserScan::Reader::getIntensities() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder LaserScan::Builder::getIntensities() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void LaserScan::Builder::setIntensities( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline void LaserScan::Builder::setIntensities(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder LaserScan::Builder::initIntensities(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void LaserScan::Builder::adoptIntensities( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> LaserScan::Builder::disownIntensities() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool MagneticField::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool MagneticField::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader MagneticField::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder MagneticField::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline MagneticField::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void MagneticField::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder MagneticField::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MagneticField::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> MagneticField::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool MagneticField::Reader::hasMagneticField() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool MagneticField::Builder::hasMagneticField() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Vector3::Reader MagneticField::Reader::getMagneticField() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Vector3::Builder MagneticField::Builder::getMagneticField() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Vector3::Pipeline MagneticField::Pipeline::getMagneticField() { + return ::mrp::geometry::Vector3::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void MagneticField::Builder::setMagneticField( ::mrp::geometry::Vector3::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Vector3::Builder MagneticField::Builder::initMagneticField() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void MagneticField::Builder::adoptMagneticField( + ::capnp::Orphan< ::mrp::geometry::Vector3>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Vector3> MagneticField::Builder::disownMagneticField() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool MagneticField::Reader::hasMagneticFieldCovariance() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool MagneticField::Builder::hasMagneticFieldCovariance() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader MagneticField::Reader::getMagneticFieldCovariance() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder MagneticField::Builder::getMagneticFieldCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void MagneticField::Builder::setMagneticFieldCovariance( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline void MagneticField::Builder::setMagneticFieldCovariance(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder MagneticField::Builder::initMagneticFieldCovariance(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void MagneticField::Builder::adoptMagneticFieldCovariance( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> MagneticField::Builder::disownMagneticFieldCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool MultiDOFJointState::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiDOFJointState::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader MultiDOFJointState::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder MultiDOFJointState::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline MultiDOFJointState::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void MultiDOFJointState::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder MultiDOFJointState::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MultiDOFJointState::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> MultiDOFJointState::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool MultiDOFJointState::Reader::hasJointNames() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiDOFJointState::Builder::hasJointNames() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader MultiDOFJointState::Reader::getJointNames() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder MultiDOFJointState::Builder::getJointNames() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void MultiDOFJointState::Builder::setJointNames( ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void MultiDOFJointState::Builder::setJointNames(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder MultiDOFJointState::Builder::initJointNames(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void MultiDOFJointState::Builder::adoptJointNames( + ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>> MultiDOFJointState::Builder::disownJointNames() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool MultiDOFJointState::Reader::hasTransforms() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiDOFJointState::Builder::hasTransforms() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Reader MultiDOFJointState::Reader::getTransforms() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Builder MultiDOFJointState::Builder::getTransforms() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void MultiDOFJointState::Builder::setTransforms( ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Builder MultiDOFJointState::Builder::initTransforms(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void MultiDOFJointState::Builder::adoptTransforms( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>> MultiDOFJointState::Builder::disownTransforms() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool MultiDOFJointState::Reader::hasTwist() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiDOFJointState::Builder::hasTwist() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Reader MultiDOFJointState::Reader::getTwist() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Builder MultiDOFJointState::Builder::getTwist() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void MultiDOFJointState::Builder::setTwist( ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Builder MultiDOFJointState::Builder::initTwist(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void MultiDOFJointState::Builder::adoptTwist( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>> MultiDOFJointState::Builder::disownTwist() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool MultiDOFJointState::Reader::hasWrench() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiDOFJointState::Builder::hasWrench() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>::Reader MultiDOFJointState::Reader::getWrench() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>::Builder MultiDOFJointState::Builder::getWrench() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void MultiDOFJointState::Builder::setWrench( ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>::Builder MultiDOFJointState::Builder::initWrench(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), size); +} +inline void MultiDOFJointState::Builder::adoptWrench( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>> MultiDOFJointState::Builder::disownWrench() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Wrench, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline bool MultiEchoLaserScan::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiEchoLaserScan::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader MultiEchoLaserScan::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder MultiEchoLaserScan::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline MultiEchoLaserScan::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void MultiEchoLaserScan::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder MultiEchoLaserScan::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MultiEchoLaserScan::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> MultiEchoLaserScan::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline float MultiEchoLaserScan::Reader::getAngleMin() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline float MultiEchoLaserScan::Builder::getAngleMin() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void MultiEchoLaserScan::Builder::setAngleMin(float value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline float MultiEchoLaserScan::Reader::getAngleMax() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline float MultiEchoLaserScan::Builder::getAngleMax() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void MultiEchoLaserScan::Builder::setAngleMax(float value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline float MultiEchoLaserScan::Reader::getAngleIncrement() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline float MultiEchoLaserScan::Builder::getAngleIncrement() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void MultiEchoLaserScan::Builder::setAngleIncrement(float value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline float MultiEchoLaserScan::Reader::getTimeIncrement() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline float MultiEchoLaserScan::Builder::getTimeIncrement() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void MultiEchoLaserScan::Builder::setTimeIncrement(float value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline float MultiEchoLaserScan::Reader::getScanTime() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline float MultiEchoLaserScan::Builder::getScanTime() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline void MultiEchoLaserScan::Builder::setScanTime(float value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); +} + +inline float MultiEchoLaserScan::Reader::getRangeMin() const { + return _reader.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} + +inline float MultiEchoLaserScan::Builder::getRangeMin() { + return _builder.getDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS); +} +inline void MultiEchoLaserScan::Builder::setRangeMin(float value) { + _builder.setDataField( + ::capnp::bounded<5>() * ::capnp::ELEMENTS, value); +} + +inline float MultiEchoLaserScan::Reader::getRangeMax() const { + return _reader.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} + +inline float MultiEchoLaserScan::Builder::getRangeMax() { + return _builder.getDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS); +} +inline void MultiEchoLaserScan::Builder::setRangeMax(float value) { + _builder.setDataField( + ::capnp::bounded<6>() * ::capnp::ELEMENTS, value); +} + +inline bool MultiEchoLaserScan::Reader::hasRanges() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiEchoLaserScan::Builder::hasRanges() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Reader MultiEchoLaserScan::Reader::getRanges() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Builder MultiEchoLaserScan::Builder::getRanges() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void MultiEchoLaserScan::Builder::setRanges( ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Builder MultiEchoLaserScan::Builder::initRanges(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void MultiEchoLaserScan::Builder::adoptRanges( + ::capnp::Orphan< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>> MultiEchoLaserScan::Builder::disownRanges() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool MultiEchoLaserScan::Reader::hasIntensities() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiEchoLaserScan::Builder::hasIntensities() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Reader MultiEchoLaserScan::Reader::getIntensities() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Builder MultiEchoLaserScan::Builder::getIntensities() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void MultiEchoLaserScan::Builder::setIntensities( ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>::Builder MultiEchoLaserScan::Builder::initIntensities(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void MultiEchoLaserScan::Builder::adoptIntensities( + ::capnp::Orphan< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>> MultiEchoLaserScan::Builder::disownIntensities() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::LaserEcho, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool NavSatFix::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool NavSatFix::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader NavSatFix::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder NavSatFix::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline NavSatFix::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void NavSatFix::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder NavSatFix::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void NavSatFix::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> NavSatFix::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool NavSatFix::Reader::hasStatus() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool NavSatFix::Builder::hasStatus() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::sensor::NavSatStatus::Reader NavSatFix::Reader::getStatus() const { + return ::capnp::_::PointerHelpers< ::mrp::sensor::NavSatStatus>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::sensor::NavSatStatus::Builder NavSatFix::Builder::getStatus() { + return ::capnp::_::PointerHelpers< ::mrp::sensor::NavSatStatus>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::sensor::NavSatStatus::Pipeline NavSatFix::Pipeline::getStatus() { + return ::mrp::sensor::NavSatStatus::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void NavSatFix::Builder::setStatus( ::mrp::sensor::NavSatStatus::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::sensor::NavSatStatus>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::sensor::NavSatStatus::Builder NavSatFix::Builder::initStatus() { + return ::capnp::_::PointerHelpers< ::mrp::sensor::NavSatStatus>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void NavSatFix::Builder::adoptStatus( + ::capnp::Orphan< ::mrp::sensor::NavSatStatus>&& value) { + ::capnp::_::PointerHelpers< ::mrp::sensor::NavSatStatus>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::sensor::NavSatStatus> NavSatFix::Builder::disownStatus() { + return ::capnp::_::PointerHelpers< ::mrp::sensor::NavSatStatus>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline double NavSatFix::Reader::getLatitude() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline double NavSatFix::Builder::getLatitude() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void NavSatFix::Builder::setLatitude(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline double NavSatFix::Reader::getLongitude() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double NavSatFix::Builder::getLongitude() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void NavSatFix::Builder::setLongitude(double value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline double NavSatFix::Reader::getAltitude() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline double NavSatFix::Builder::getAltitude() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void NavSatFix::Builder::setAltitude(double value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool NavSatFix::Reader::hasPositionCovariance() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool NavSatFix::Builder::hasPositionCovariance() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader NavSatFix::Reader::getPositionCovariance() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder NavSatFix::Builder::getPositionCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void NavSatFix::Builder::setPositionCovariance( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline void NavSatFix::Builder::setPositionCovariance(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder NavSatFix::Builder::initPositionCovariance(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void NavSatFix::Builder::adoptPositionCovariance( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> NavSatFix::Builder::disownPositionCovariance() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline ::uint8_t NavSatFix::Reader::getPositionCovarianceType() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<24>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t NavSatFix::Builder::getPositionCovarianceType() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<24>() * ::capnp::ELEMENTS); +} +inline void NavSatFix::Builder::setPositionCovarianceType( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<24>() * ::capnp::ELEMENTS, value); +} + +inline ::int8_t NavSatStatus::Reader::getStatus() const { + return _reader.getDataField< ::int8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::int8_t NavSatStatus::Builder::getStatus() { + return _builder.getDataField< ::int8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void NavSatStatus::Builder::setStatus( ::int8_t value) { + _builder.setDataField< ::int8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint16_t NavSatStatus::Reader::getService() const { + return _reader.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint16_t NavSatStatus::Builder::getService() { + return _builder.getDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void NavSatStatus::Builder::setService( ::uint16_t value) { + _builder.setDataField< ::uint16_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool PointCloud::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool PointCloud::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader PointCloud::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder PointCloud::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline PointCloud::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void PointCloud::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder PointCloud::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void PointCloud::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> PointCloud::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool PointCloud::Reader::hasPoints() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool PointCloud::Builder::hasPoints() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Reader PointCloud::Reader::getPoints() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Builder PointCloud::Builder::getPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void PointCloud::Builder::setPoints( ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>::Builder PointCloud::Builder::initPoints(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void PointCloud::Builder::adoptPoints( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>> PointCloud::Builder::disownPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point32, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool PointCloud::Reader::hasChannels() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool PointCloud::Builder::hasChannels() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>::Reader PointCloud::Reader::getChannels() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>::Builder PointCloud::Builder::getChannels() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void PointCloud::Builder::setChannels( ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>::Builder PointCloud::Builder::initChannels(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void PointCloud::Builder::adoptChannels( + ::capnp::Orphan< ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>> PointCloud::Builder::disownChannels() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::ChannelFloat32, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool PointCloud2::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool PointCloud2::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader PointCloud2::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder PointCloud2::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline PointCloud2::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void PointCloud2::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder PointCloud2::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void PointCloud2::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> PointCloud2::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t PointCloud2::Reader::getHeight() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t PointCloud2::Builder::getHeight() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void PointCloud2::Builder::setHeight( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t PointCloud2::Reader::getWidth() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t PointCloud2::Builder::getWidth() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void PointCloud2::Builder::setWidth( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool PointCloud2::Reader::hasFields() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool PointCloud2::Builder::hasFields() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>::Reader PointCloud2::Reader::getFields() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>::Builder PointCloud2::Builder::getFields() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void PointCloud2::Builder::setFields( ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>::Builder PointCloud2::Builder::initFields(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void PointCloud2::Builder::adoptFields( + ::capnp::Orphan< ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>> PointCloud2::Builder::disownFields() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::sensor::PointField, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool PointCloud2::Reader::getIsBigendian() const { + return _reader.getDataField( + ::capnp::bounded<64>() * ::capnp::ELEMENTS); +} + +inline bool PointCloud2::Builder::getIsBigendian() { + return _builder.getDataField( + ::capnp::bounded<64>() * ::capnp::ELEMENTS); +} +inline void PointCloud2::Builder::setIsBigendian(bool value) { + _builder.setDataField( + ::capnp::bounded<64>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t PointCloud2::Reader::getPointStep() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t PointCloud2::Builder::getPointStep() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void PointCloud2::Builder::setPointStep( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t PointCloud2::Reader::getRowStep() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t PointCloud2::Builder::getRowStep() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline void PointCloud2::Builder::setRowStep( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); +} + +inline bool PointCloud2::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool PointCloud2::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Data::Reader PointCloud2::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::Data::Builder PointCloud2::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void PointCloud2::Builder::setData( ::capnp::Data::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::Data::Builder PointCloud2::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Data>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void PointCloud2::Builder::adoptData( + ::capnp::Orphan< ::capnp::Data>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Data> PointCloud2::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool PointCloud2::Reader::getIsDense() const { + return _reader.getDataField( + ::capnp::bounded<65>() * ::capnp::ELEMENTS); +} + +inline bool PointCloud2::Builder::getIsDense() { + return _builder.getDataField( + ::capnp::bounded<65>() * ::capnp::ELEMENTS); +} +inline void PointCloud2::Builder::setIsDense(bool value) { + _builder.setDataField( + ::capnp::bounded<65>() * ::capnp::ELEMENTS, value); +} + +inline bool PointField::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool PointField::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader PointField::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder PointField::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void PointField::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder PointField::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void PointField::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> PointField::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t PointField::Reader::getOffset() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t PointField::Builder::getOffset() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void PointField::Builder::setOffset( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t PointField::Reader::getDatatype() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t PointField::Builder::getDatatype() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline void PointField::Builder::setDatatype( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t PointField::Reader::getCount() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t PointField::Builder::getCount() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void PointField::Builder::setCount( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Range::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Range::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader Range::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder Range::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline Range::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Range::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder Range::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Range::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> Range::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint8_t Range::Reader::getRadiationType() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t Range::Builder::getRadiationType() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Range::Builder::setRadiationType( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline float Range::Reader::getFieldOfView() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline float Range::Builder::getFieldOfView() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Range::Builder::setFieldOfView(float value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline float Range::Reader::getMinRange() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline float Range::Builder::getMinRange() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Range::Builder::setMinRange(float value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline float Range::Reader::getMaxRange() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline float Range::Builder::getMaxRange() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void Range::Builder::setMaxRange(float value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline float Range::Reader::getRange() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline float Range::Builder::getRange() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline void Range::Builder::setRange(float value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t RegionOfInterest::Reader::getXOffset() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t RegionOfInterest::Builder::getXOffset() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void RegionOfInterest::Builder::setXOffset( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t RegionOfInterest::Reader::getYOffset() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t RegionOfInterest::Builder::getYOffset() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void RegionOfInterest::Builder::setYOffset( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t RegionOfInterest::Reader::getHeight() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t RegionOfInterest::Builder::getHeight() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void RegionOfInterest::Builder::setHeight( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t RegionOfInterest::Reader::getWidth() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t RegionOfInterest::Builder::getWidth() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void RegionOfInterest::Builder::setWidth( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline bool RegionOfInterest::Reader::getDoRectify() const { + return _reader.getDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS); +} + +inline bool RegionOfInterest::Builder::getDoRectify() { + return _builder.getDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS); +} +inline void RegionOfInterest::Builder::setDoRectify(bool value) { + _builder.setDataField( + ::capnp::bounded<128>() * ::capnp::ELEMENTS, value); +} + +inline bool RelativeHumidity::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool RelativeHumidity::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader RelativeHumidity::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder RelativeHumidity::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline RelativeHumidity::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void RelativeHumidity::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder RelativeHumidity::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void RelativeHumidity::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> RelativeHumidity::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline double RelativeHumidity::Reader::getRelativeHumidity() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline double RelativeHumidity::Builder::getRelativeHumidity() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void RelativeHumidity::Builder::setRelativeHumidity(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline double RelativeHumidity::Reader::getVariance() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double RelativeHumidity::Builder::getVariance() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void RelativeHumidity::Builder::setVariance(double value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Temperature::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Temperature::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader Temperature::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder Temperature::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline Temperature::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Temperature::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder Temperature::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Temperature::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> Temperature::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline double Temperature::Reader::getTemperature() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline double Temperature::Builder::getTemperature() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Temperature::Builder::setTemperature(double value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline double Temperature::Reader::getVariance() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline double Temperature::Builder::getVariance() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Temperature::Builder::setVariance(double value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool TimeReference::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool TimeReference::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader TimeReference::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder TimeReference::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline TimeReference::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void TimeReference::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder TimeReference::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void TimeReference::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> TimeReference::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool TimeReference::Reader::hasTimeRef() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool TimeReference::Builder::hasTimeRef() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Time::Reader TimeReference::Reader::getTimeRef() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Time::Builder TimeReference::Builder::getTimeRef() { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Time::Pipeline TimeReference::Pipeline::getTimeRef() { + return ::mrp::std::Time::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void TimeReference::Builder::setTimeRef( ::mrp::std::Time::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Time>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Time::Builder TimeReference::Builder::initTimeRef() { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void TimeReference::Builder::adoptTimeRef( + ::capnp::Orphan< ::mrp::std::Time>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Time>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Time> TimeReference::Builder::disownTimeRef() { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool TimeReference::Reader::hasSource() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool TimeReference::Builder::hasSource() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader TimeReference::Reader::getSource() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder TimeReference::Builder::getSource() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void TimeReference::Builder::setSource( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder TimeReference::Builder::initSource(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void TimeReference::Builder::adoptSource( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> TimeReference::Builder::disownSource() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +} // namespace +} // namespace + +CAPNP_END_HEADER + diff --git a/msg/src/fairomsg/cpp/shape_msgs.capnp.c++ b/msg/src/fairomsg/cpp/shape_msgs.capnp.c++ new file mode 100644 index 0000000000..5da0d4d194 --- /dev/null +++ b/msg/src/fairomsg/cpp/shape_msgs.capnp.c++ @@ -0,0 +1,788 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: shape_msgs.capnp + +#include "shape_msgs.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<58> b_c3765e3fa5ab25e0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 224, 37, 171, 165, 63, 94, 118, 195, + 21, 0, 0, 0, 1, 0, 0, 0, + 233, 219, 189, 155, 201, 175, 113, 207, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 101, 115, + 104, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 116, 114, 105, 97, 110, 103, 108, 101, + 115, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 169, 24, 211, 171, 253, 178, 133, 234, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 114, 116, 105, 99, 101, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 68, 59, 77, 248, 154, 89, 171, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c3765e3fa5ab25e0 = b_c3765e3fa5ab25e0.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c3765e3fa5ab25e0[] = { + &s_ea85b2fdabd318a9, + &s_ebab599af84d3b44, +}; +static const uint16_t m_c3765e3fa5ab25e0[] = {0, 1}; +static const uint16_t i_c3765e3fa5ab25e0[] = {0, 1}; +const ::capnp::_::RawSchema s_c3765e3fa5ab25e0 = { + 0xc3765e3fa5ab25e0, b_c3765e3fa5ab25e0.words, 58, d_c3765e3fa5ab25e0, m_c3765e3fa5ab25e0, + 2, 2, i_c3765e3fa5ab25e0, nullptr, nullptr, { &s_c3765e3fa5ab25e0, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<39> b_ea85b2fdabd318a9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 169, 24, 211, 171, 253, 178, 133, 234, + 21, 0, 0, 0, 1, 0, 0, 0, + 233, 219, 189, 155, 201, 175, 113, 207, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 101, 115, + 104, 84, 114, 105, 97, 110, 103, 108, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 3, 0, 1, 0, + 40, 0, 0, 0, 2, 0, 1, 0, + 118, 101, 114, 116, 101, 120, 73, 110, + 100, 105, 99, 101, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ea85b2fdabd318a9 = b_ea85b2fdabd318a9.words; +#if !CAPNP_LITE +static const uint16_t m_ea85b2fdabd318a9[] = {0}; +static const uint16_t i_ea85b2fdabd318a9[] = {0}; +const ::capnp::_::RawSchema s_ea85b2fdabd318a9 = { + 0xea85b2fdabd318a9, b_ea85b2fdabd318a9.words, 39, nullptr, m_ea85b2fdabd318a9, + 0, 1, i_ea85b2fdabd318a9, nullptr, nullptr, { &s_ea85b2fdabd318a9, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<37> b_b387280c4001ecbf = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 191, 236, 1, 64, 12, 40, 135, 179, + 21, 0, 0, 0, 1, 0, 0, 0, + 233, 219, 189, 155, 201, 175, 113, 207, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 218, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 80, 108, 97, + 110, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 36, 0, 0, 0, 2, 0, 1, 0, + 99, 111, 101, 102, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b387280c4001ecbf = b_b387280c4001ecbf.words; +#if !CAPNP_LITE +static const uint16_t m_b387280c4001ecbf[] = {0}; +static const uint16_t i_b387280c4001ecbf[] = {0}; +const ::capnp::_::RawSchema s_b387280c4001ecbf = { + 0xb387280c4001ecbf, b_b387280c4001ecbf.words, 37, nullptr, m_b387280c4001ecbf, + 0, 1, i_b387280c4001ecbf, nullptr, nullptr, { &s_b387280c4001ecbf, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<96> b_d8943cb5e3be8b29 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 41, 139, 190, 227, 181, 60, 148, 216, + 21, 0, 0, 0, 1, 0, 1, 0, + 233, 219, 189, 155, 201, 175, 113, 207, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 199, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 83, 111, 108, + 105, 100, 80, 114, 105, 109, 105, 116, + 105, 118, 101, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 1, 0, 1, 0, + 192, 64, 155, 184, 29, 112, 9, 205, + 89, 0, 0, 0, 42, 0, 0, 0, + 4, 186, 6, 245, 9, 153, 233, 203, + 85, 0, 0, 0, 66, 0, 0, 0, + 247, 4, 167, 59, 120, 134, 214, 203, + 81, 0, 0, 0, 82, 0, 0, 0, + 73, 7, 82, 174, 175, 224, 20, 205, + 81, 0, 0, 0, 50, 0, 0, 0, + 231, 194, 252, 204, 100, 86, 213, 244, + 77, 0, 0, 0, 50, 0, 0, 0, + 171, 102, 142, 101, 93, 76, 196, 217, + 73, 0, 0, 0, 50, 0, 0, 0, + 190, 199, 139, 144, 120, 78, 177, 223, + 69, 0, 0, 0, 50, 0, 0, 0, + 40, 90, 213, 166, 78, 204, 36, 129, + 65, 0, 0, 0, 114, 0, 0, 0, + 241, 226, 54, 117, 189, 173, 117, 155, + 65, 0, 0, 0, 130, 0, 0, 0, + 49, 45, 184, 212, 72, 163, 248, 192, + 65, 0, 0, 0, 130, 0, 0, 0, + 214, 101, 168, 78, 112, 49, 157, 224, + 65, 0, 0, 0, 98, 0, 0, 0, + 22, 189, 79, 122, 2, 84, 159, 247, + 65, 0, 0, 0, 98, 0, 0, 0, + 107, 66, 111, 120, 0, 0, 0, 0, + 107, 83, 112, 104, 101, 114, 101, 0, + 107, 67, 121, 108, 105, 110, 100, 101, + 114, 0, 0, 0, 0, 0, 0, 0, + 107, 67, 111, 110, 101, 0, 0, 0, + 107, 66, 111, 120, 88, 0, 0, 0, + 107, 66, 111, 120, 89, 0, 0, 0, + 107, 66, 111, 120, 90, 0, 0, 0, + 107, 83, 112, 104, 101, 114, 101, 82, + 97, 100, 105, 117, 115, 0, 0, 0, + 107, 67, 121, 108, 105, 110, 100, 101, + 114, 72, 101, 105, 103, 104, 116, 0, + 107, 67, 121, 108, 105, 110, 100, 101, + 114, 82, 97, 100, 105, 117, 115, 0, + 107, 67, 111, 110, 101, 72, 101, 105, + 103, 104, 116, 0, 0, 0, 0, 0, + 107, 67, 111, 110, 101, 82, 97, 100, + 105, 117, 115, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 72, 0, 0, 0, 2, 0, 1, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 109, 101, 110, 115, 105, 111, + 110, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d8943cb5e3be8b29 = b_d8943cb5e3be8b29.words; +#if !CAPNP_LITE +static const uint16_t m_d8943cb5e3be8b29[] = {1, 0}; +static const uint16_t i_d8943cb5e3be8b29[] = {0, 1}; +const ::capnp::_::RawSchema s_d8943cb5e3be8b29 = { + 0xd8943cb5e3be8b29, b_d8943cb5e3be8b29.words, 96, nullptr, m_d8943cb5e3be8b29, + 0, 2, i_d8943cb5e3be8b29, nullptr, nullptr, { &s_d8943cb5e3be8b29, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_cd09701db89b40c0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 192, 64, 155, 184, 29, 112, 9, 205, + 36, 0, 0, 0, 4, 0, 0, 0, + 41, 139, 190, 227, 181, 60, 148, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 83, 111, 108, + 105, 100, 80, 114, 105, 109, 105, 116, + 105, 118, 101, 46, 107, 66, 111, 120, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cd09701db89b40c0 = b_cd09701db89b40c0.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_cd09701db89b40c0 = { + 0xcd09701db89b40c0, b_cd09701db89b40c0.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_cd09701db89b40c0, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_cbe99909f506ba04 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 4, 186, 6, 245, 9, 153, 233, 203, + 36, 0, 0, 0, 4, 0, 0, 0, + 41, 139, 190, 227, 181, 60, 148, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 98, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 83, 111, 108, + 105, 100, 80, 114, 105, 109, 105, 116, + 105, 118, 101, 46, 107, 83, 112, 104, + 101, 114, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cbe99909f506ba04 = b_cbe99909f506ba04.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_cbe99909f506ba04 = { + 0xcbe99909f506ba04, b_cbe99909f506ba04.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_cbe99909f506ba04, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_cbd686783ba704f7 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 247, 4, 167, 59, 120, 134, 214, 203, + 36, 0, 0, 0, 4, 0, 0, 0, + 41, 139, 190, 227, 181, 60, 148, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 114, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 83, 111, 108, + 105, 100, 80, 114, 105, 109, 105, 116, + 105, 118, 101, 46, 107, 67, 121, 108, + 105, 110, 100, 101, 114, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cbd686783ba704f7 = b_cbd686783ba704f7.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_cbd686783ba704f7 = { + 0xcbd686783ba704f7, b_cbd686783ba704f7.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_cbd686783ba704f7, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_cd14e0afae520749 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 73, 7, 82, 174, 175, 224, 20, 205, + 36, 0, 0, 0, 4, 0, 0, 0, + 41, 139, 190, 227, 181, 60, 148, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 83, 111, 108, + 105, 100, 80, 114, 105, 109, 105, 116, + 105, 118, 101, 46, 107, 67, 111, 110, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 4, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cd14e0afae520749 = b_cd14e0afae520749.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_cd14e0afae520749 = { + 0xcd14e0afae520749, b_cd14e0afae520749.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_cd14e0afae520749, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_f4d55664ccfcc2e7 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 231, 194, 252, 204, 100, 86, 213, 244, + 36, 0, 0, 0, 4, 0, 0, 0, + 41, 139, 190, 227, 181, 60, 148, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 83, 111, 108, + 105, 100, 80, 114, 105, 109, 105, 116, + 105, 118, 101, 46, 107, 66, 111, 120, + 88, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f4d55664ccfcc2e7 = b_f4d55664ccfcc2e7.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_f4d55664ccfcc2e7 = { + 0xf4d55664ccfcc2e7, b_f4d55664ccfcc2e7.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_f4d55664ccfcc2e7, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_d9c44c5d658e66ab = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 171, 102, 142, 101, 93, 76, 196, 217, + 36, 0, 0, 0, 4, 0, 0, 0, + 41, 139, 190, 227, 181, 60, 148, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 83, 111, 108, + 105, 100, 80, 114, 105, 109, 105, 116, + 105, 118, 101, 46, 107, 66, 111, 120, + 89, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d9c44c5d658e66ab = b_d9c44c5d658e66ab.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_d9c44c5d658e66ab = { + 0xd9c44c5d658e66ab, b_d9c44c5d658e66ab.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_d9c44c5d658e66ab, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_dfb14e78908bc7be = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 190, 199, 139, 144, 120, 78, 177, 223, + 36, 0, 0, 0, 4, 0, 0, 0, + 41, 139, 190, 227, 181, 60, 148, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 83, 111, 108, + 105, 100, 80, 114, 105, 109, 105, 116, + 105, 118, 101, 46, 107, 66, 111, 120, + 90, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_dfb14e78908bc7be = b_dfb14e78908bc7be.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_dfb14e78908bc7be = { + 0xdfb14e78908bc7be, b_dfb14e78908bc7be.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_dfb14e78908bc7be, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_8124cc4ea6d55a28 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 40, 90, 213, 166, 78, 204, 36, 129, + 36, 0, 0, 0, 4, 0, 0, 0, + 41, 139, 190, 227, 181, 60, 148, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 83, 111, 108, + 105, 100, 80, 114, 105, 109, 105, 116, + 105, 118, 101, 46, 107, 83, 112, 104, + 101, 114, 101, 82, 97, 100, 105, 117, + 115, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8124cc4ea6d55a28 = b_8124cc4ea6d55a28.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_8124cc4ea6d55a28 = { + 0x8124cc4ea6d55a28, b_8124cc4ea6d55a28.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_8124cc4ea6d55a28, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_9b75adbd7536e2f1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 241, 226, 54, 117, 189, 173, 117, 155, + 36, 0, 0, 0, 4, 0, 0, 0, + 41, 139, 190, 227, 181, 60, 148, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 83, 111, 108, + 105, 100, 80, 114, 105, 109, 105, 116, + 105, 118, 101, 46, 107, 67, 121, 108, + 105, 110, 100, 101, 114, 72, 101, 105, + 103, 104, 116, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9b75adbd7536e2f1 = b_9b75adbd7536e2f1.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_9b75adbd7536e2f1 = { + 0x9b75adbd7536e2f1, b_9b75adbd7536e2f1.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_9b75adbd7536e2f1, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_c0f8a348d4b82d31 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 49, 45, 184, 212, 72, 163, 248, 192, + 36, 0, 0, 0, 4, 0, 0, 0, + 41, 139, 190, 227, 181, 60, 148, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 83, 111, 108, + 105, 100, 80, 114, 105, 109, 105, 116, + 105, 118, 101, 46, 107, 67, 121, 108, + 105, 110, 100, 101, 114, 82, 97, 100, + 105, 117, 115, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c0f8a348d4b82d31 = b_c0f8a348d4b82d31.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c0f8a348d4b82d31 = { + 0xc0f8a348d4b82d31, b_c0f8a348d4b82d31.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c0f8a348d4b82d31, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_e09d31704ea865d6 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 214, 101, 168, 78, 112, 49, 157, 224, + 36, 0, 0, 0, 4, 0, 0, 0, + 41, 139, 190, 227, 181, 60, 148, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 130, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 83, 111, 108, + 105, 100, 80, 114, 105, 109, 105, 116, + 105, 118, 101, 46, 107, 67, 111, 110, + 101, 72, 101, 105, 103, 104, 116, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e09d31704ea865d6 = b_e09d31704ea865d6.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_e09d31704ea865d6 = { + 0xe09d31704ea865d6, b_e09d31704ea865d6.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_e09d31704ea865d6, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_f79f54027a4fbd16 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 22, 189, 79, 122, 2, 84, 159, 247, + 36, 0, 0, 0, 4, 0, 0, 0, + 41, 139, 190, 227, 181, 60, 148, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 130, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 104, 97, 112, + 101, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 83, 111, 108, + 105, 100, 80, 114, 105, 109, 105, 116, + 105, 118, 101, 46, 107, 67, 111, 110, + 101, 82, 97, 100, 105, 117, 115, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f79f54027a4fbd16 = b_f79f54027a4fbd16.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_f79f54027a4fbd16 = { + 0xf79f54027a4fbd16, b_f79f54027a4fbd16.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_f79f54027a4fbd16, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace mrp { +namespace shape { + +// Mesh +constexpr uint16_t Mesh::_capnpPrivate::dataWordSize; +constexpr uint16_t Mesh::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Mesh::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Mesh::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// MeshTriangle +constexpr uint16_t MeshTriangle::_capnpPrivate::dataWordSize; +constexpr uint16_t MeshTriangle::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind MeshTriangle::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* MeshTriangle::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Plane +constexpr uint16_t Plane::_capnpPrivate::dataWordSize; +constexpr uint16_t Plane::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Plane::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Plane::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// SolidPrimitive +constexpr uint16_t SolidPrimitive::_capnpPrivate::dataWordSize; +constexpr uint16_t SolidPrimitive::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind SolidPrimitive::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* SolidPrimitive::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t SolidPrimitive::K_BOX; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t SolidPrimitive::K_SPHERE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t SolidPrimitive::K_CYLINDER; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t SolidPrimitive::K_CONE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t SolidPrimitive::K_BOX_X; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t SolidPrimitive::K_BOX_Y; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t SolidPrimitive::K_BOX_Z; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t SolidPrimitive::K_SPHERE_RADIUS; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t SolidPrimitive::K_CYLINDER_HEIGHT; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t SolidPrimitive::K_CYLINDER_RADIUS; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t SolidPrimitive::K_CONE_HEIGHT; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t SolidPrimitive::K_CONE_RADIUS; +#endif + +} // namespace +} // namespace + diff --git a/msg/src/fairomsg/cpp/shape_msgs.capnp.h b/msg/src/fairomsg/cpp/shape_msgs.capnp.h new file mode 100644 index 0000000000..884474c84a --- /dev/null +++ b/msg/src/fairomsg/cpp/shape_msgs.capnp.h @@ -0,0 +1,661 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: shape_msgs.capnp + +#pragma once + +#include +#include + +#if CAPNP_VERSION != 9001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + +#include "geometry_msgs.capnp.h" + +CAPNP_BEGIN_HEADER + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(c3765e3fa5ab25e0); +CAPNP_DECLARE_SCHEMA(ea85b2fdabd318a9); +CAPNP_DECLARE_SCHEMA(b387280c4001ecbf); +CAPNP_DECLARE_SCHEMA(d8943cb5e3be8b29); +CAPNP_DECLARE_SCHEMA(cd09701db89b40c0); +CAPNP_DECLARE_SCHEMA(cbe99909f506ba04); +CAPNP_DECLARE_SCHEMA(cbd686783ba704f7); +CAPNP_DECLARE_SCHEMA(cd14e0afae520749); +CAPNP_DECLARE_SCHEMA(f4d55664ccfcc2e7); +CAPNP_DECLARE_SCHEMA(d9c44c5d658e66ab); +CAPNP_DECLARE_SCHEMA(dfb14e78908bc7be); +CAPNP_DECLARE_SCHEMA(8124cc4ea6d55a28); +CAPNP_DECLARE_SCHEMA(9b75adbd7536e2f1); +CAPNP_DECLARE_SCHEMA(c0f8a348d4b82d31); +CAPNP_DECLARE_SCHEMA(e09d31704ea865d6); +CAPNP_DECLARE_SCHEMA(f79f54027a4fbd16); + +} // namespace schemas +} // namespace capnp + +namespace mrp { +namespace shape { + +struct Mesh { + Mesh() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c3765e3fa5ab25e0, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct MeshTriangle { + MeshTriangle() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ea85b2fdabd318a9, 0, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Plane { + Plane() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b387280c4001ecbf, 0, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct SolidPrimitive { + SolidPrimitive() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_BOX = 1u; + static constexpr ::uint8_t K_SPHERE = 2u; + static constexpr ::uint8_t K_CYLINDER = 3u; + static constexpr ::uint8_t K_CONE = 4u; + static constexpr ::uint8_t K_BOX_X = 0u; + static constexpr ::uint8_t K_BOX_Y = 1u; + static constexpr ::uint8_t K_BOX_Z = 2u; + static constexpr ::uint8_t K_SPHERE_RADIUS = 0u; + static constexpr ::uint8_t K_CYLINDER_HEIGHT = 0u; + static constexpr ::uint8_t K_CYLINDER_RADIUS = 1u; + static constexpr ::uint8_t K_CONE_HEIGHT = 0u; + static constexpr ::uint8_t K_CONE_RADIUS = 1u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d8943cb5e3be8b29, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class Mesh::Reader { +public: + typedef Mesh Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasTriangles() const; + inline ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>::Reader getTriangles() const; + + inline bool hasVertices() const; + inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader getVertices() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Mesh::Builder { +public: + typedef Mesh Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasTriangles(); + inline ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>::Builder getTriangles(); + inline void setTriangles( ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>::Builder initTriangles(unsigned int size); + inline void adoptTriangles(::capnp::Orphan< ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>> disownTriangles(); + + inline bool hasVertices(); + inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder getVertices(); + inline void setVertices( ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder initVertices(unsigned int size); + inline void adoptVertices(::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>> disownVertices(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Mesh::Pipeline { +public: + typedef Mesh Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class MeshTriangle::Reader { +public: + typedef MeshTriangle Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasVertexIndices() const; + inline ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Reader getVertexIndices() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class MeshTriangle::Builder { +public: + typedef MeshTriangle Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasVertexIndices(); + inline ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Builder getVertexIndices(); + inline void setVertexIndices( ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Reader value); + inline void setVertexIndices(::kj::ArrayPtr value); + inline ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Builder initVertexIndices(unsigned int size); + inline void adoptVertexIndices(::capnp::Orphan< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>> disownVertexIndices(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class MeshTriangle::Pipeline { +public: + typedef MeshTriangle Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Plane::Reader { +public: + typedef Plane Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasCoef() const; + inline ::capnp::List::Reader getCoef() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Plane::Builder { +public: + typedef Plane Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasCoef(); + inline ::capnp::List::Builder getCoef(); + inline void setCoef( ::capnp::List::Reader value); + inline void setCoef(::kj::ArrayPtr value); + inline ::capnp::List::Builder initCoef(unsigned int size); + inline void adoptCoef(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownCoef(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Plane::Pipeline { +public: + typedef Plane Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class SolidPrimitive::Reader { +public: + typedef SolidPrimitive Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint8_t getType() const; + + inline bool hasDimensions() const; + inline ::capnp::List::Reader getDimensions() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class SolidPrimitive::Builder { +public: + typedef SolidPrimitive Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint8_t getType(); + inline void setType( ::uint8_t value); + + inline bool hasDimensions(); + inline ::capnp::List::Builder getDimensions(); + inline void setDimensions( ::capnp::List::Reader value); + inline void setDimensions(::kj::ArrayPtr value); + inline ::capnp::List::Builder initDimensions(unsigned int size); + inline void adoptDimensions(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownDimensions(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class SolidPrimitive::Pipeline { +public: + typedef SolidPrimitive Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline bool Mesh::Reader::hasTriangles() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Mesh::Builder::hasTriangles() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>::Reader Mesh::Reader::getTriangles() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>::Builder Mesh::Builder::getTriangles() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Mesh::Builder::setTriangles( ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>::Builder Mesh::Builder::initTriangles(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Mesh::Builder::adoptTriangles( + ::capnp::Orphan< ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>> Mesh::Builder::disownTriangles() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::shape::MeshTriangle, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Mesh::Reader::hasVertices() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Mesh::Builder::hasVertices() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader Mesh::Reader::getVertices() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder Mesh::Builder::getVertices() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Mesh::Builder::setVertices( ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder Mesh::Builder::initVertices(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Mesh::Builder::adoptVertices( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>> Mesh::Builder::disownVertices() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool MeshTriangle::Reader::hasVertexIndices() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool MeshTriangle::Builder::hasVertexIndices() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Reader MeshTriangle::Reader::getVertexIndices() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Builder MeshTriangle::Builder::getVertexIndices() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MeshTriangle::Builder::setVertexIndices( ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline void MeshTriangle::Builder::setVertexIndices(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Builder MeshTriangle::Builder::initVertexIndices(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void MeshTriangle::Builder::adoptVertexIndices( + ::capnp::Orphan< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>> MeshTriangle::Builder::disownVertexIndices() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Plane::Reader::hasCoef() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Plane::Builder::hasCoef() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader Plane::Reader::getCoef() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder Plane::Builder::getCoef() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Plane::Builder::setCoef( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline void Plane::Builder::setCoef(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder Plane::Builder::initCoef(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void Plane::Builder::adoptCoef( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> Plane::Builder::disownCoef() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint8_t SolidPrimitive::Reader::getType() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t SolidPrimitive::Builder::getType() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void SolidPrimitive::Builder::setType( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool SolidPrimitive::Reader::hasDimensions() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool SolidPrimitive::Builder::hasDimensions() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader SolidPrimitive::Reader::getDimensions() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder SolidPrimitive::Builder::getDimensions() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void SolidPrimitive::Builder::setDimensions( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline void SolidPrimitive::Builder::setDimensions(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder SolidPrimitive::Builder::initDimensions(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void SolidPrimitive::Builder::adoptDimensions( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> SolidPrimitive::Builder::disownDimensions() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +} // namespace +} // namespace + +CAPNP_END_HEADER + diff --git a/msg/src/fairomsg/cpp/std_msgs.capnp.c++ b/msg/src/fairomsg/cpp/std_msgs.capnp.c++ new file mode 100644 index 0000000000..5900f35e60 --- /dev/null +++ b/msg/src/fairomsg/cpp/std_msgs.capnp.c++ @@ -0,0 +1,1494 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: std_msgs.capnp + +#include "std_msgs.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<32> b_aae043d52a4e8c60 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 96, 140, 78, 42, 213, 67, 224, 170, + 19, 0, 0, 0, 1, 0, 1, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 194, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 66, 121, 116, 101, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 20, 0, 0, 0, 2, 0, 1, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_aae043d52a4e8c60 = b_aae043d52a4e8c60.words; +#if !CAPNP_LITE +static const uint16_t m_aae043d52a4e8c60[] = {0}; +static const uint16_t i_aae043d52a4e8c60[] = {0}; +const ::capnp::_::RawSchema s_aae043d52a4e8c60 = { + 0xaae043d52a4e8c60, b_aae043d52a4e8c60.words, 32, nullptr, m_aae043d52a4e8c60, + 0, 1, i_aae043d52a4e8c60, nullptr, nullptr, { &s_aae043d52a4e8c60, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_b67e2ec602362112 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 18, 33, 54, 2, 198, 46, 126, 182, + 19, 0, 0, 0, 1, 0, 0, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 66, 121, 116, 101, 77, + 117, 108, 116, 105, 65, 114, 114, 97, + 121, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 121, 111, 117, 116, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 172, 9, 237, 155, 184, 32, 134, 242, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b67e2ec602362112 = b_b67e2ec602362112.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_b67e2ec602362112[] = { + &s_f28620b89bed09ac, +}; +static const uint16_t m_b67e2ec602362112[] = {1, 0}; +static const uint16_t i_b67e2ec602362112[] = {0, 1}; +const ::capnp::_::RawSchema s_b67e2ec602362112 = { + 0xb67e2ec602362112, b_b67e2ec602362112.words, 49, d_b67e2ec602362112, m_b67e2ec602362112, + 1, 2, i_b67e2ec602362112, nullptr, nullptr, { &s_b67e2ec602362112, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<32> b_98a0a20f340bb6c8 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 200, 182, 11, 52, 15, 162, 160, 152, + 19, 0, 0, 0, 1, 0, 1, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 194, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 67, 104, 97, 114, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 20, 0, 0, 0, 2, 0, 1, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_98a0a20f340bb6c8 = b_98a0a20f340bb6c8.words; +#if !CAPNP_LITE +static const uint16_t m_98a0a20f340bb6c8[] = {0}; +static const uint16_t i_98a0a20f340bb6c8[] = {0}; +const ::capnp::_::RawSchema s_98a0a20f340bb6c8 = { + 0x98a0a20f340bb6c8, b_98a0a20f340bb6c8.words, 32, nullptr, m_98a0a20f340bb6c8, + 0, 1, i_98a0a20f340bb6c8, nullptr, nullptr, { &s_98a0a20f340bb6c8, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<78> b_fcddd22e31ab4f70 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 112, 79, 171, 49, 46, 210, 221, 252, + 19, 0, 0, 0, 1, 0, 2, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 67, 111, 108, 111, 114, + 82, 71, 66, 65, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 114, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fcddd22e31ab4f70 = b_fcddd22e31ab4f70.words; +#if !CAPNP_LITE +static const uint16_t m_fcddd22e31ab4f70[] = {3, 2, 1, 0}; +static const uint16_t i_fcddd22e31ab4f70[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_fcddd22e31ab4f70 = { + 0xfcddd22e31ab4f70, b_fcddd22e31ab4f70.words, 78, nullptr, m_fcddd22e31ab4f70, + 0, 4, i_fcddd22e31ab4f70, nullptr, nullptr, { &s_fcddd22e31ab4f70, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<48> b_8fba5bceec2d81ff = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 255, 129, 45, 236, 206, 91, 186, 143, + 19, 0, 0, 0, 1, 0, 1, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 226, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 68, 117, 114, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 115, 101, 99, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 115, 101, 99, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8fba5bceec2d81ff = b_8fba5bceec2d81ff.words; +#if !CAPNP_LITE +static const uint16_t m_8fba5bceec2d81ff[] = {1, 0}; +static const uint16_t i_8fba5bceec2d81ff[] = {0, 1}; +const ::capnp::_::RawSchema s_8fba5bceec2d81ff = { + 0x8fba5bceec2d81ff, b_8fba5bceec2d81ff.words, 48, nullptr, m_8fba5bceec2d81ff, + 0, 2, i_8fba5bceec2d81ff, nullptr, nullptr, { &s_8fba5bceec2d81ff, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<17> b_91883f029b2592f8 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 248, 146, 37, 155, 2, 63, 136, 145, + 19, 0, 0, 0, 1, 0, 0, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 202, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 69, 109, 112, 116, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, } +}; +::capnp::word const* const bp_91883f029b2592f8 = b_91883f029b2592f8.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_91883f029b2592f8 = { + 0x91883f029b2592f8, b_91883f029b2592f8.words, 17, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_91883f029b2592f8, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_a1ada55891f92fbc = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 188, 47, 249, 145, 88, 165, 173, 161, + 19, 0, 0, 0, 1, 0, 0, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 70, 108, 111, 97, 116, + 51, 50, 77, 117, 108, 116, 105, 65, + 114, 114, 97, 121, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 121, 111, 117, 116, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 172, 9, 237, 155, 184, 32, 134, 242, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a1ada55891f92fbc = b_a1ada55891f92fbc.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a1ada55891f92fbc[] = { + &s_f28620b89bed09ac, +}; +static const uint16_t m_a1ada55891f92fbc[] = {1, 0}; +static const uint16_t i_a1ada55891f92fbc[] = {0, 1}; +const ::capnp::_::RawSchema s_a1ada55891f92fbc = { + 0xa1ada55891f92fbc, b_a1ada55891f92fbc.words, 53, d_a1ada55891f92fbc, m_a1ada55891f92fbc, + 1, 2, i_a1ada55891f92fbc, nullptr, nullptr, { &s_a1ada55891f92fbc, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_f26e720fc35cd246 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 70, 210, 92, 195, 15, 114, 110, 242, + 19, 0, 0, 0, 1, 0, 0, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 70, 108, 111, 97, 116, + 54, 52, 77, 117, 108, 116, 105, 65, + 114, 114, 97, 121, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 121, 111, 117, 116, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 172, 9, 237, 155, 184, 32, 134, 242, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f26e720fc35cd246 = b_f26e720fc35cd246.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f26e720fc35cd246[] = { + &s_f28620b89bed09ac, +}; +static const uint16_t m_f26e720fc35cd246[] = {1, 0}; +static const uint16_t i_f26e720fc35cd246[] = {0, 1}; +const ::capnp::_::RawSchema s_f26e720fc35cd246 = { + 0xf26e720fc35cd246, b_f26e720fc35cd246.words, 53, d_f26e720fc35cd246, m_f26e720fc35cd246, + 1, 2, i_f26e720fc35cd246, nullptr, nullptr, { &s_f26e720fc35cd246, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<63> b_cf9a8bcf03922937 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 19, 0, 0, 0, 1, 0, 1, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 72, 101, 97, 100, 101, + 114, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 115, 101, 113, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 109, 112, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 79, 12, 85, 207, 4, 92, 190, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cf9a8bcf03922937 = b_cf9a8bcf03922937.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_cf9a8bcf03922937[] = { + &s_ebbe5c04cf550c4f, +}; +static const uint16_t m_cf9a8bcf03922937[] = {2, 0, 1}; +static const uint16_t i_cf9a8bcf03922937[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_cf9a8bcf03922937 = { + 0xcf9a8bcf03922937, b_cf9a8bcf03922937.words, 63, d_cf9a8bcf03922937, m_cf9a8bcf03922937, + 1, 3, i_cf9a8bcf03922937, nullptr, nullptr, { &s_cf9a8bcf03922937, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_cce4456a438dfada = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 218, 250, 141, 67, 106, 69, 228, 204, + 19, 0, 0, 0, 1, 0, 0, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 73, 110, 116, 49, 54, + 77, 117, 108, 116, 105, 65, 114, 114, + 97, 121, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 121, 111, 117, 116, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 172, 9, 237, 155, 184, 32, 134, 242, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cce4456a438dfada = b_cce4456a438dfada.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_cce4456a438dfada[] = { + &s_f28620b89bed09ac, +}; +static const uint16_t m_cce4456a438dfada[] = {1, 0}; +static const uint16_t i_cce4456a438dfada[] = {0, 1}; +const ::capnp::_::RawSchema s_cce4456a438dfada = { + 0xcce4456a438dfada, b_cce4456a438dfada.words, 53, d_cce4456a438dfada, m_cce4456a438dfada, + 1, 2, i_cce4456a438dfada, nullptr, nullptr, { &s_cce4456a438dfada, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_97220a0c9cee8e22 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 34, 142, 238, 156, 12, 10, 34, 151, + 19, 0, 0, 0, 1, 0, 0, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 73, 110, 116, 51, 50, + 77, 117, 108, 116, 105, 65, 114, 114, + 97, 121, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 121, 111, 117, 116, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 172, 9, 237, 155, 184, 32, 134, 242, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_97220a0c9cee8e22 = b_97220a0c9cee8e22.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_97220a0c9cee8e22[] = { + &s_f28620b89bed09ac, +}; +static const uint16_t m_97220a0c9cee8e22[] = {1, 0}; +static const uint16_t i_97220a0c9cee8e22[] = {0, 1}; +const ::capnp::_::RawSchema s_97220a0c9cee8e22 = { + 0x97220a0c9cee8e22, b_97220a0c9cee8e22.words, 53, d_97220a0c9cee8e22, m_97220a0c9cee8e22, + 1, 2, i_97220a0c9cee8e22, nullptr, nullptr, { &s_97220a0c9cee8e22, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_895053609043e89a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 154, 232, 67, 144, 96, 83, 80, 137, + 19, 0, 0, 0, 1, 0, 0, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 73, 110, 116, 54, 52, + 77, 117, 108, 116, 105, 65, 114, 114, + 97, 121, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 121, 111, 117, 116, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 172, 9, 237, 155, 184, 32, 134, 242, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_895053609043e89a = b_895053609043e89a.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_895053609043e89a[] = { + &s_f28620b89bed09ac, +}; +static const uint16_t m_895053609043e89a[] = {1, 0}; +static const uint16_t i_895053609043e89a[] = {0, 1}; +const ::capnp::_::RawSchema s_895053609043e89a = { + 0x895053609043e89a, b_895053609043e89a.words, 53, d_895053609043e89a, m_895053609043e89a, + 1, 2, i_895053609043e89a, nullptr, nullptr, { &s_895053609043e89a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_8454977525614501 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 1, 69, 97, 37, 117, 151, 84, 132, + 19, 0, 0, 0, 1, 0, 0, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 73, 110, 116, 56, 77, + 117, 108, 116, 105, 65, 114, 114, 97, + 121, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 121, 111, 117, 116, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 172, 9, 237, 155, 184, 32, 134, 242, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8454977525614501 = b_8454977525614501.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_8454977525614501[] = { + &s_f28620b89bed09ac, +}; +static const uint16_t m_8454977525614501[] = {1, 0}; +static const uint16_t i_8454977525614501[] = {0, 1}; +const ::capnp::_::RawSchema s_8454977525614501 = { + 0x8454977525614501, b_8454977525614501.words, 49, d_8454977525614501, m_8454977525614501, + 1, 2, i_8454977525614501, nullptr, nullptr, { &s_8454977525614501, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<64> b_da16d19a39e3c483 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 131, 196, 227, 57, 154, 209, 22, 218, + 19, 0, 0, 0, 1, 0, 1, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 77, 117, 108, 116, 105, + 65, 114, 114, 97, 121, 68, 105, 109, + 101, 110, 115, 105, 111, 110, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 98, 101, 108, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 105, 122, 101, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 114, 105, 100, 101, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_da16d19a39e3c483 = b_da16d19a39e3c483.words; +#if !CAPNP_LITE +static const uint16_t m_da16d19a39e3c483[] = {0, 1, 2}; +static const uint16_t i_da16d19a39e3c483[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_da16d19a39e3c483 = { + 0xda16d19a39e3c483, b_da16d19a39e3c483.words, 64, nullptr, m_da16d19a39e3c483, + 0, 3, i_da16d19a39e3c483, nullptr, nullptr, { &s_da16d19a39e3c483, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<54> b_f28620b89bed09ac = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 172, 9, 237, 155, 184, 32, 134, 242, + 19, 0, 0, 0, 1, 0, 1, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 77, 117, 108, 116, 105, + 65, 114, 114, 97, 121, 76, 97, 121, + 111, 117, 116, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 64, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 0, 0, 0, 3, 0, 1, 0, + 72, 0, 0, 0, 2, 0, 1, 0, + 100, 105, 109, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 131, 196, 227, 57, 154, 209, 22, 218, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 79, 102, 102, 115, + 101, 116, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f28620b89bed09ac = b_f28620b89bed09ac.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f28620b89bed09ac[] = { + &s_da16d19a39e3c483, +}; +static const uint16_t m_f28620b89bed09ac[] = {1, 0}; +static const uint16_t i_f28620b89bed09ac[] = {0, 1}; +const ::capnp::_::RawSchema s_f28620b89bed09ac = { + 0xf28620b89bed09ac, b_f28620b89bed09ac.words, 54, d_f28620b89bed09ac, m_f28620b89bed09ac, + 1, 2, i_f28620b89bed09ac, nullptr, nullptr, { &s_f28620b89bed09ac, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<33> b_da572a7d156dda3a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 58, 218, 109, 21, 125, 42, 87, 218, + 19, 0, 0, 0, 1, 0, 0, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 83, 116, 114, 105, 110, + 103, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 20, 0, 0, 0, 2, 0, 1, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_da572a7d156dda3a = b_da572a7d156dda3a.words; +#if !CAPNP_LITE +static const uint16_t m_da572a7d156dda3a[] = {0}; +static const uint16_t i_da572a7d156dda3a[] = {0}; +const ::capnp::_::RawSchema s_da572a7d156dda3a = { + 0xda572a7d156dda3a, b_da572a7d156dda3a.words, 33, nullptr, m_da572a7d156dda3a, + 0, 1, i_da572a7d156dda3a, nullptr, nullptr, { &s_da572a7d156dda3a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<47> b_ebbe5c04cf550c4f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 79, 12, 85, 207, 4, 92, 190, 235, + 19, 0, 0, 0, 1, 0, 1, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 194, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 84, 105, 109, 101, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 115, 101, 99, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 115, 101, 99, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ebbe5c04cf550c4f = b_ebbe5c04cf550c4f.words; +#if !CAPNP_LITE +static const uint16_t m_ebbe5c04cf550c4f[] = {1, 0}; +static const uint16_t i_ebbe5c04cf550c4f[] = {0, 1}; +const ::capnp::_::RawSchema s_ebbe5c04cf550c4f = { + 0xebbe5c04cf550c4f, b_ebbe5c04cf550c4f.words, 47, nullptr, m_ebbe5c04cf550c4f, + 0, 2, i_ebbe5c04cf550c4f, nullptr, nullptr, { &s_ebbe5c04cf550c4f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_a505ca401d1e8578 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 120, 133, 30, 29, 64, 202, 5, 165, + 19, 0, 0, 0, 1, 0, 0, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 85, 73, 110, 116, 49, + 54, 77, 117, 108, 116, 105, 65, 114, + 114, 97, 121, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 121, 111, 117, 116, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 172, 9, 237, 155, 184, 32, 134, 242, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a505ca401d1e8578 = b_a505ca401d1e8578.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a505ca401d1e8578[] = { + &s_f28620b89bed09ac, +}; +static const uint16_t m_a505ca401d1e8578[] = {1, 0}; +static const uint16_t i_a505ca401d1e8578[] = {0, 1}; +const ::capnp::_::RawSchema s_a505ca401d1e8578 = { + 0xa505ca401d1e8578, b_a505ca401d1e8578.words, 53, d_a505ca401d1e8578, m_a505ca401d1e8578, + 1, 2, i_a505ca401d1e8578, nullptr, nullptr, { &s_a505ca401d1e8578, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_e1bd799bdfa95af3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 243, 90, 169, 223, 155, 121, 189, 225, + 19, 0, 0, 0, 1, 0, 0, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 85, 73, 110, 116, 51, + 50, 77, 117, 108, 116, 105, 65, 114, + 114, 97, 121, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 121, 111, 117, 116, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 172, 9, 237, 155, 184, 32, 134, 242, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e1bd799bdfa95af3 = b_e1bd799bdfa95af3.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_e1bd799bdfa95af3[] = { + &s_f28620b89bed09ac, +}; +static const uint16_t m_e1bd799bdfa95af3[] = {1, 0}; +static const uint16_t i_e1bd799bdfa95af3[] = {0, 1}; +const ::capnp::_::RawSchema s_e1bd799bdfa95af3 = { + 0xe1bd799bdfa95af3, b_e1bd799bdfa95af3.words, 53, d_e1bd799bdfa95af3, m_e1bd799bdfa95af3, + 1, 2, i_e1bd799bdfa95af3, nullptr, nullptr, { &s_e1bd799bdfa95af3, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_a3fc446486ff277b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 123, 39, 255, 134, 100, 68, 252, 163, + 19, 0, 0, 0, 1, 0, 0, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 85, 73, 110, 116, 54, + 52, 77, 117, 108, 116, 105, 65, 114, + 114, 97, 121, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 121, 111, 117, 116, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 172, 9, 237, 155, 184, 32, 134, 242, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a3fc446486ff277b = b_a3fc446486ff277b.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a3fc446486ff277b[] = { + &s_f28620b89bed09ac, +}; +static const uint16_t m_a3fc446486ff277b[] = {1, 0}; +static const uint16_t i_a3fc446486ff277b[] = {0, 1}; +const ::capnp::_::RawSchema s_a3fc446486ff277b = { + 0xa3fc446486ff277b, b_a3fc446486ff277b.words, 53, d_a3fc446486ff277b, m_a3fc446486ff277b, + 1, 2, i_a3fc446486ff277b, nullptr, nullptr, { &s_a3fc446486ff277b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_a590f4103f797b9b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 155, 123, 121, 63, 16, 244, 144, 165, + 19, 0, 0, 0, 1, 0, 0, 0, + 105, 197, 201, 222, 103, 205, 99, 250, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 100, 95, + 109, 115, 103, 115, 46, 99, 97, 112, + 110, 112, 58, 85, 73, 110, 116, 56, + 77, 117, 108, 116, 105, 65, 114, 114, + 97, 121, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 121, 111, 117, 116, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 172, 9, 237, 155, 184, 32, 134, 242, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a590f4103f797b9b = b_a590f4103f797b9b.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a590f4103f797b9b[] = { + &s_f28620b89bed09ac, +}; +static const uint16_t m_a590f4103f797b9b[] = {1, 0}; +static const uint16_t i_a590f4103f797b9b[] = {0, 1}; +const ::capnp::_::RawSchema s_a590f4103f797b9b = { + 0xa590f4103f797b9b, b_a590f4103f797b9b.words, 49, d_a590f4103f797b9b, m_a590f4103f797b9b, + 1, 2, i_a590f4103f797b9b, nullptr, nullptr, { &s_a590f4103f797b9b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace mrp { +namespace std { + +// Byte +constexpr uint16_t Byte::_capnpPrivate::dataWordSize; +constexpr uint16_t Byte::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Byte::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Byte::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// ByteMultiArray +constexpr uint16_t ByteMultiArray::_capnpPrivate::dataWordSize; +constexpr uint16_t ByteMultiArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind ByteMultiArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ByteMultiArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Char +constexpr uint16_t Char::_capnpPrivate::dataWordSize; +constexpr uint16_t Char::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Char::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Char::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// ColorRGBA +constexpr uint16_t ColorRGBA::_capnpPrivate::dataWordSize; +constexpr uint16_t ColorRGBA::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind ColorRGBA::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ColorRGBA::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Duration +constexpr uint16_t Duration::_capnpPrivate::dataWordSize; +constexpr uint16_t Duration::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Duration::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Duration::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Empty +constexpr uint16_t Empty::_capnpPrivate::dataWordSize; +constexpr uint16_t Empty::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Empty::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Empty::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Float32MultiArray +constexpr uint16_t Float32MultiArray::_capnpPrivate::dataWordSize; +constexpr uint16_t Float32MultiArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Float32MultiArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Float32MultiArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Float64MultiArray +constexpr uint16_t Float64MultiArray::_capnpPrivate::dataWordSize; +constexpr uint16_t Float64MultiArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Float64MultiArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Float64MultiArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Header +constexpr uint16_t Header::_capnpPrivate::dataWordSize; +constexpr uint16_t Header::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Header::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Header::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Int16MultiArray +constexpr uint16_t Int16MultiArray::_capnpPrivate::dataWordSize; +constexpr uint16_t Int16MultiArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Int16MultiArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Int16MultiArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Int32MultiArray +constexpr uint16_t Int32MultiArray::_capnpPrivate::dataWordSize; +constexpr uint16_t Int32MultiArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Int32MultiArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Int32MultiArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Int64MultiArray +constexpr uint16_t Int64MultiArray::_capnpPrivate::dataWordSize; +constexpr uint16_t Int64MultiArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Int64MultiArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Int64MultiArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Int8MultiArray +constexpr uint16_t Int8MultiArray::_capnpPrivate::dataWordSize; +constexpr uint16_t Int8MultiArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Int8MultiArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Int8MultiArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// MultiArrayDimension +constexpr uint16_t MultiArrayDimension::_capnpPrivate::dataWordSize; +constexpr uint16_t MultiArrayDimension::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind MultiArrayDimension::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* MultiArrayDimension::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// MultiArrayLayout +constexpr uint16_t MultiArrayLayout::_capnpPrivate::dataWordSize; +constexpr uint16_t MultiArrayLayout::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind MultiArrayLayout::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* MultiArrayLayout::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// String +constexpr uint16_t String::_capnpPrivate::dataWordSize; +constexpr uint16_t String::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind String::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* String::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// Time +constexpr uint16_t Time::_capnpPrivate::dataWordSize; +constexpr uint16_t Time::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Time::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Time::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// UInt16MultiArray +constexpr uint16_t UInt16MultiArray::_capnpPrivate::dataWordSize; +constexpr uint16_t UInt16MultiArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind UInt16MultiArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UInt16MultiArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// UInt32MultiArray +constexpr uint16_t UInt32MultiArray::_capnpPrivate::dataWordSize; +constexpr uint16_t UInt32MultiArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind UInt32MultiArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UInt32MultiArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// UInt64MultiArray +constexpr uint16_t UInt64MultiArray::_capnpPrivate::dataWordSize; +constexpr uint16_t UInt64MultiArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind UInt64MultiArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UInt64MultiArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// UInt8MultiArray +constexpr uint16_t UInt8MultiArray::_capnpPrivate::dataWordSize; +constexpr uint16_t UInt8MultiArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind UInt8MultiArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UInt8MultiArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + + +} // namespace +} // namespace + diff --git a/msg/src/fairomsg/cpp/std_msgs.capnp.h b/msg/src/fairomsg/cpp/std_msgs.capnp.h new file mode 100644 index 0000000000..2ea57bc8db --- /dev/null +++ b/msg/src/fairomsg/cpp/std_msgs.capnp.h @@ -0,0 +1,3427 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: std_msgs.capnp + +#pragma once + +#include +#include + +#if CAPNP_VERSION != 9001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + + +CAPNP_BEGIN_HEADER + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(aae043d52a4e8c60); +CAPNP_DECLARE_SCHEMA(b67e2ec602362112); +CAPNP_DECLARE_SCHEMA(98a0a20f340bb6c8); +CAPNP_DECLARE_SCHEMA(fcddd22e31ab4f70); +CAPNP_DECLARE_SCHEMA(8fba5bceec2d81ff); +CAPNP_DECLARE_SCHEMA(91883f029b2592f8); +CAPNP_DECLARE_SCHEMA(a1ada55891f92fbc); +CAPNP_DECLARE_SCHEMA(f26e720fc35cd246); +CAPNP_DECLARE_SCHEMA(cf9a8bcf03922937); +CAPNP_DECLARE_SCHEMA(cce4456a438dfada); +CAPNP_DECLARE_SCHEMA(97220a0c9cee8e22); +CAPNP_DECLARE_SCHEMA(895053609043e89a); +CAPNP_DECLARE_SCHEMA(8454977525614501); +CAPNP_DECLARE_SCHEMA(da16d19a39e3c483); +CAPNP_DECLARE_SCHEMA(f28620b89bed09ac); +CAPNP_DECLARE_SCHEMA(da572a7d156dda3a); +CAPNP_DECLARE_SCHEMA(ebbe5c04cf550c4f); +CAPNP_DECLARE_SCHEMA(a505ca401d1e8578); +CAPNP_DECLARE_SCHEMA(e1bd799bdfa95af3); +CAPNP_DECLARE_SCHEMA(a3fc446486ff277b); +CAPNP_DECLARE_SCHEMA(a590f4103f797b9b); + +} // namespace schemas +} // namespace capnp + +namespace mrp { +namespace std { + +struct Byte { + Byte() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(aae043d52a4e8c60, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct ByteMultiArray { + ByteMultiArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b67e2ec602362112, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Char { + Char() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(98a0a20f340bb6c8, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct ColorRGBA { + ColorRGBA() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(fcddd22e31ab4f70, 2, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Duration { + Duration() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8fba5bceec2d81ff, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Empty { + Empty() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(91883f029b2592f8, 0, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Float32MultiArray { + Float32MultiArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a1ada55891f92fbc, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Float64MultiArray { + Float64MultiArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f26e720fc35cd246, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Header { + Header() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(cf9a8bcf03922937, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Int16MultiArray { + Int16MultiArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(cce4456a438dfada, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Int32MultiArray { + Int32MultiArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(97220a0c9cee8e22, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Int64MultiArray { + Int64MultiArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(895053609043e89a, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Int8MultiArray { + Int8MultiArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8454977525614501, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct MultiArrayDimension { + MultiArrayDimension() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(da16d19a39e3c483, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct MultiArrayLayout { + MultiArrayLayout() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f28620b89bed09ac, 1, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct String { + String() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(da572a7d156dda3a, 0, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Time { + Time() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(ebbe5c04cf550c4f, 1, 0) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct UInt16MultiArray { + UInt16MultiArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a505ca401d1e8578, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct UInt32MultiArray { + UInt32MultiArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e1bd799bdfa95af3, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct UInt64MultiArray { + UInt64MultiArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a3fc446486ff277b, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct UInt8MultiArray { + UInt8MultiArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(a590f4103f797b9b, 0, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class Byte::Reader { +public: + typedef Byte Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint8_t getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Byte::Builder { +public: + typedef Byte Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint8_t getData(); + inline void setData( ::uint8_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Byte::Pipeline { +public: + typedef Byte Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ByteMultiArray::Reader { +public: + typedef ByteMultiArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLayout() const; + inline ::mrp::std::MultiArrayLayout::Reader getLayout() const; + + inline bool hasData() const; + inline ::capnp::Data::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ByteMultiArray::Builder { +public: + typedef ByteMultiArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLayout(); + inline ::mrp::std::MultiArrayLayout::Builder getLayout(); + inline void setLayout( ::mrp::std::MultiArrayLayout::Reader value); + inline ::mrp::std::MultiArrayLayout::Builder initLayout(); + inline void adoptLayout(::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value); + inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> disownLayout(); + + inline bool hasData(); + inline ::capnp::Data::Builder getData(); + inline void setData( ::capnp::Data::Reader value); + inline ::capnp::Data::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::Data>&& value); + inline ::capnp::Orphan< ::capnp::Data> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ByteMultiArray::Pipeline { +public: + typedef ByteMultiArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::MultiArrayLayout::Pipeline getLayout(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Char::Reader { +public: + typedef Char Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::int8_t getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Char::Builder { +public: + typedef Char Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::int8_t getData(); + inline void setData( ::int8_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Char::Pipeline { +public: + typedef Char Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class ColorRGBA::Reader { +public: + typedef ColorRGBA Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline float getR() const; + + inline float getG() const; + + inline float getB() const; + + inline float getA() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ColorRGBA::Builder { +public: + typedef ColorRGBA Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline float getR(); + inline void setR(float value); + + inline float getG(); + inline void setG(float value); + + inline float getB(); + inline void setB(float value); + + inline float getA(); + inline void setA(float value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ColorRGBA::Pipeline { +public: + typedef ColorRGBA Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Duration::Reader { +public: + typedef Duration Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::int32_t getSec() const; + + inline ::int32_t getNsec() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Duration::Builder { +public: + typedef Duration Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::int32_t getSec(); + inline void setSec( ::int32_t value); + + inline ::int32_t getNsec(); + inline void setNsec( ::int32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Duration::Pipeline { +public: + typedef Duration Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Empty::Reader { +public: + typedef Empty Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Empty::Builder { +public: + typedef Empty Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Empty::Pipeline { +public: + typedef Empty Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Float32MultiArray::Reader { +public: + typedef Float32MultiArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLayout() const; + inline ::mrp::std::MultiArrayLayout::Reader getLayout() const; + + inline bool hasData() const; + inline ::capnp::List::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Float32MultiArray::Builder { +public: + typedef Float32MultiArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLayout(); + inline ::mrp::std::MultiArrayLayout::Builder getLayout(); + inline void setLayout( ::mrp::std::MultiArrayLayout::Reader value); + inline ::mrp::std::MultiArrayLayout::Builder initLayout(); + inline void adoptLayout(::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value); + inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> disownLayout(); + + inline bool hasData(); + inline ::capnp::List::Builder getData(); + inline void setData( ::capnp::List::Reader value); + inline void setData(::kj::ArrayPtr value); + inline ::capnp::List::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Float32MultiArray::Pipeline { +public: + typedef Float32MultiArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::MultiArrayLayout::Pipeline getLayout(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Float64MultiArray::Reader { +public: + typedef Float64MultiArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLayout() const; + inline ::mrp::std::MultiArrayLayout::Reader getLayout() const; + + inline bool hasData() const; + inline ::capnp::List::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Float64MultiArray::Builder { +public: + typedef Float64MultiArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLayout(); + inline ::mrp::std::MultiArrayLayout::Builder getLayout(); + inline void setLayout( ::mrp::std::MultiArrayLayout::Reader value); + inline ::mrp::std::MultiArrayLayout::Builder initLayout(); + inline void adoptLayout(::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value); + inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> disownLayout(); + + inline bool hasData(); + inline ::capnp::List::Builder getData(); + inline void setData( ::capnp::List::Reader value); + inline void setData(::kj::ArrayPtr value); + inline ::capnp::List::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Float64MultiArray::Pipeline { +public: + typedef Float64MultiArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::MultiArrayLayout::Pipeline getLayout(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Header::Reader { +public: + typedef Header Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getSeq() const; + + inline bool hasStamp() const; + inline ::mrp::std::Time::Reader getStamp() const; + + inline bool hasFrameId() const; + inline ::capnp::Text::Reader getFrameId() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Header::Builder { +public: + typedef Header Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getSeq(); + inline void setSeq( ::uint32_t value); + + inline bool hasStamp(); + inline ::mrp::std::Time::Builder getStamp(); + inline void setStamp( ::mrp::std::Time::Reader value); + inline ::mrp::std::Time::Builder initStamp(); + inline void adoptStamp(::capnp::Orphan< ::mrp::std::Time>&& value); + inline ::capnp::Orphan< ::mrp::std::Time> disownStamp(); + + inline bool hasFrameId(); + inline ::capnp::Text::Builder getFrameId(); + inline void setFrameId( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initFrameId(unsigned int size); + inline void adoptFrameId(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownFrameId(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Header::Pipeline { +public: + typedef Header Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Time::Pipeline getStamp(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Int16MultiArray::Reader { +public: + typedef Int16MultiArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLayout() const; + inline ::mrp::std::MultiArrayLayout::Reader getLayout() const; + + inline bool hasData() const; + inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Int16MultiArray::Builder { +public: + typedef Int16MultiArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLayout(); + inline ::mrp::std::MultiArrayLayout::Builder getLayout(); + inline void setLayout( ::mrp::std::MultiArrayLayout::Reader value); + inline ::mrp::std::MultiArrayLayout::Builder initLayout(); + inline void adoptLayout(::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value); + inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> disownLayout(); + + inline bool hasData(); + inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Builder getData(); + inline void setData( ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Reader value); + inline void setData(::kj::ArrayPtr value); + inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Int16MultiArray::Pipeline { +public: + typedef Int16MultiArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::MultiArrayLayout::Pipeline getLayout(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Int32MultiArray::Reader { +public: + typedef Int32MultiArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLayout() const; + inline ::mrp::std::MultiArrayLayout::Reader getLayout() const; + + inline bool hasData() const; + inline ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Int32MultiArray::Builder { +public: + typedef Int32MultiArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLayout(); + inline ::mrp::std::MultiArrayLayout::Builder getLayout(); + inline void setLayout( ::mrp::std::MultiArrayLayout::Reader value); + inline ::mrp::std::MultiArrayLayout::Builder initLayout(); + inline void adoptLayout(::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value); + inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> disownLayout(); + + inline bool hasData(); + inline ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Builder getData(); + inline void setData( ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Reader value); + inline void setData(::kj::ArrayPtr value); + inline ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Int32MultiArray::Pipeline { +public: + typedef Int32MultiArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::MultiArrayLayout::Pipeline getLayout(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Int64MultiArray::Reader { +public: + typedef Int64MultiArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLayout() const; + inline ::mrp::std::MultiArrayLayout::Reader getLayout() const; + + inline bool hasData() const; + inline ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Int64MultiArray::Builder { +public: + typedef Int64MultiArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLayout(); + inline ::mrp::std::MultiArrayLayout::Builder getLayout(); + inline void setLayout( ::mrp::std::MultiArrayLayout::Reader value); + inline ::mrp::std::MultiArrayLayout::Builder initLayout(); + inline void adoptLayout(::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value); + inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> disownLayout(); + + inline bool hasData(); + inline ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>::Builder getData(); + inline void setData( ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>::Reader value); + inline void setData(::kj::ArrayPtr value); + inline ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Int64MultiArray::Pipeline { +public: + typedef Int64MultiArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::MultiArrayLayout::Pipeline getLayout(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Int8MultiArray::Reader { +public: + typedef Int8MultiArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLayout() const; + inline ::mrp::std::MultiArrayLayout::Reader getLayout() const; + + inline bool hasData() const; + inline ::capnp::Data::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Int8MultiArray::Builder { +public: + typedef Int8MultiArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLayout(); + inline ::mrp::std::MultiArrayLayout::Builder getLayout(); + inline void setLayout( ::mrp::std::MultiArrayLayout::Reader value); + inline ::mrp::std::MultiArrayLayout::Builder initLayout(); + inline void adoptLayout(::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value); + inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> disownLayout(); + + inline bool hasData(); + inline ::capnp::Data::Builder getData(); + inline void setData( ::capnp::Data::Reader value); + inline ::capnp::Data::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::Data>&& value); + inline ::capnp::Orphan< ::capnp::Data> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Int8MultiArray::Pipeline { +public: + typedef Int8MultiArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::MultiArrayLayout::Pipeline getLayout(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class MultiArrayDimension::Reader { +public: + typedef MultiArrayDimension Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLabel() const; + inline ::capnp::Text::Reader getLabel() const; + + inline ::uint32_t getSize() const; + + inline ::uint32_t getStride() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class MultiArrayDimension::Builder { +public: + typedef MultiArrayDimension Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLabel(); + inline ::capnp::Text::Builder getLabel(); + inline void setLabel( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initLabel(unsigned int size); + inline void adoptLabel(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownLabel(); + + inline ::uint32_t getSize(); + inline void setSize( ::uint32_t value); + + inline ::uint32_t getStride(); + inline void setStride( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class MultiArrayDimension::Pipeline { +public: + typedef MultiArrayDimension Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class MultiArrayLayout::Reader { +public: + typedef MultiArrayLayout Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasDim() const; + inline ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>::Reader getDim() const; + + inline ::uint32_t getDataOffset() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class MultiArrayLayout::Builder { +public: + typedef MultiArrayLayout Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasDim(); + inline ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>::Builder getDim(); + inline void setDim( ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>::Builder initDim(unsigned int size); + inline void adoptDim(::capnp::Orphan< ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>> disownDim(); + + inline ::uint32_t getDataOffset(); + inline void setDataOffset( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class MultiArrayLayout::Pipeline { +public: + typedef MultiArrayLayout Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class String::Reader { +public: + typedef String Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasData() const; + inline ::capnp::Text::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class String::Builder { +public: + typedef String Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasData(); + inline ::capnp::Text::Builder getData(); + inline void setData( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class String::Pipeline { +public: + typedef String Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Time::Reader { +public: + typedef Time Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getSec() const; + + inline ::uint32_t getNsec() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Time::Builder { +public: + typedef Time Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getSec(); + inline void setSec( ::uint32_t value); + + inline ::uint32_t getNsec(); + inline void setNsec( ::uint32_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Time::Pipeline { +public: + typedef Time Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class UInt16MultiArray::Reader { +public: + typedef UInt16MultiArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLayout() const; + inline ::mrp::std::MultiArrayLayout::Reader getLayout() const; + + inline bool hasData() const; + inline ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class UInt16MultiArray::Builder { +public: + typedef UInt16MultiArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLayout(); + inline ::mrp::std::MultiArrayLayout::Builder getLayout(); + inline void setLayout( ::mrp::std::MultiArrayLayout::Reader value); + inline ::mrp::std::MultiArrayLayout::Builder initLayout(); + inline void adoptLayout(::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value); + inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> disownLayout(); + + inline bool hasData(); + inline ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>::Builder getData(); + inline void setData( ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>::Reader value); + inline void setData(::kj::ArrayPtr value); + inline ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class UInt16MultiArray::Pipeline { +public: + typedef UInt16MultiArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::MultiArrayLayout::Pipeline getLayout(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class UInt32MultiArray::Reader { +public: + typedef UInt32MultiArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLayout() const; + inline ::mrp::std::MultiArrayLayout::Reader getLayout() const; + + inline bool hasData() const; + inline ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class UInt32MultiArray::Builder { +public: + typedef UInt32MultiArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLayout(); + inline ::mrp::std::MultiArrayLayout::Builder getLayout(); + inline void setLayout( ::mrp::std::MultiArrayLayout::Reader value); + inline ::mrp::std::MultiArrayLayout::Builder initLayout(); + inline void adoptLayout(::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value); + inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> disownLayout(); + + inline bool hasData(); + inline ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Builder getData(); + inline void setData( ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Reader value); + inline void setData(::kj::ArrayPtr value); + inline ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class UInt32MultiArray::Pipeline { +public: + typedef UInt32MultiArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::MultiArrayLayout::Pipeline getLayout(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class UInt64MultiArray::Reader { +public: + typedef UInt64MultiArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLayout() const; + inline ::mrp::std::MultiArrayLayout::Reader getLayout() const; + + inline bool hasData() const; + inline ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class UInt64MultiArray::Builder { +public: + typedef UInt64MultiArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLayout(); + inline ::mrp::std::MultiArrayLayout::Builder getLayout(); + inline void setLayout( ::mrp::std::MultiArrayLayout::Reader value); + inline ::mrp::std::MultiArrayLayout::Builder initLayout(); + inline void adoptLayout(::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value); + inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> disownLayout(); + + inline bool hasData(); + inline ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>::Builder getData(); + inline void setData( ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>::Reader value); + inline void setData(::kj::ArrayPtr value); + inline ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class UInt64MultiArray::Pipeline { +public: + typedef UInt64MultiArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::MultiArrayLayout::Pipeline getLayout(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class UInt8MultiArray::Reader { +public: + typedef UInt8MultiArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasLayout() const; + inline ::mrp::std::MultiArrayLayout::Reader getLayout() const; + + inline bool hasData() const; + inline ::capnp::Data::Reader getData() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class UInt8MultiArray::Builder { +public: + typedef UInt8MultiArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasLayout(); + inline ::mrp::std::MultiArrayLayout::Builder getLayout(); + inline void setLayout( ::mrp::std::MultiArrayLayout::Reader value); + inline ::mrp::std::MultiArrayLayout::Builder initLayout(); + inline void adoptLayout(::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value); + inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> disownLayout(); + + inline bool hasData(); + inline ::capnp::Data::Builder getData(); + inline void setData( ::capnp::Data::Reader value); + inline ::capnp::Data::Builder initData(unsigned int size); + inline void adoptData(::capnp::Orphan< ::capnp::Data>&& value); + inline ::capnp::Orphan< ::capnp::Data> disownData(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class UInt8MultiArray::Pipeline { +public: + typedef UInt8MultiArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::MultiArrayLayout::Pipeline getLayout(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline ::uint8_t Byte::Reader::getData() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t Byte::Builder::getData() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Byte::Builder::setData( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool ByteMultiArray::Reader::hasLayout() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool ByteMultiArray::Builder::hasLayout() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::MultiArrayLayout::Reader ByteMultiArray::Reader::getLayout() const { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::MultiArrayLayout::Builder ByteMultiArray::Builder::getLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::MultiArrayLayout::Pipeline ByteMultiArray::Pipeline::getLayout() { + return ::mrp::std::MultiArrayLayout::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void ByteMultiArray::Builder::setLayout( ::mrp::std::MultiArrayLayout::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::MultiArrayLayout::Builder ByteMultiArray::Builder::initLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void ByteMultiArray::Builder::adoptLayout( + ::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> ByteMultiArray::Builder::disownLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool ByteMultiArray::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool ByteMultiArray::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Data::Reader ByteMultiArray::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Data::Builder ByteMultiArray::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void ByteMultiArray::Builder::setData( ::capnp::Data::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Data::Builder ByteMultiArray::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Data>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void ByteMultiArray::Builder::adoptData( + ::capnp::Orphan< ::capnp::Data>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Data> ByteMultiArray::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::int8_t Char::Reader::getData() const { + return _reader.getDataField< ::int8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::int8_t Char::Builder::getData() { + return _builder.getDataField< ::int8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Char::Builder::setData( ::int8_t value) { + _builder.setDataField< ::int8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline float ColorRGBA::Reader::getR() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline float ColorRGBA::Builder::getR() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void ColorRGBA::Builder::setR(float value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline float ColorRGBA::Reader::getG() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline float ColorRGBA::Builder::getG() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void ColorRGBA::Builder::setG(float value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline float ColorRGBA::Reader::getB() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline float ColorRGBA::Builder::getB() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void ColorRGBA::Builder::setB(float value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline float ColorRGBA::Reader::getA() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline float ColorRGBA::Builder::getA() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void ColorRGBA::Builder::setA(float value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline ::int32_t Duration::Reader::getSec() const { + return _reader.getDataField< ::int32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::int32_t Duration::Builder::getSec() { + return _builder.getDataField< ::int32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Duration::Builder::setSec( ::int32_t value) { + _builder.setDataField< ::int32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::int32_t Duration::Reader::getNsec() const { + return _reader.getDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::int32_t Duration::Builder::getNsec() { + return _builder.getDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Duration::Builder::setNsec( ::int32_t value) { + _builder.setDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool Float32MultiArray::Reader::hasLayout() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Float32MultiArray::Builder::hasLayout() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::MultiArrayLayout::Reader Float32MultiArray::Reader::getLayout() const { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::MultiArrayLayout::Builder Float32MultiArray::Builder::getLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::MultiArrayLayout::Pipeline Float32MultiArray::Pipeline::getLayout() { + return ::mrp::std::MultiArrayLayout::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Float32MultiArray::Builder::setLayout( ::mrp::std::MultiArrayLayout::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::MultiArrayLayout::Builder Float32MultiArray::Builder::initLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Float32MultiArray::Builder::adoptLayout( + ::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> Float32MultiArray::Builder::disownLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Float32MultiArray::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Float32MultiArray::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader Float32MultiArray::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder Float32MultiArray::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Float32MultiArray::Builder::setData( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void Float32MultiArray::Builder::setData(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder Float32MultiArray::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Float32MultiArray::Builder::adoptData( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> Float32MultiArray::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Float64MultiArray::Reader::hasLayout() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Float64MultiArray::Builder::hasLayout() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::MultiArrayLayout::Reader Float64MultiArray::Reader::getLayout() const { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::MultiArrayLayout::Builder Float64MultiArray::Builder::getLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::MultiArrayLayout::Pipeline Float64MultiArray::Pipeline::getLayout() { + return ::mrp::std::MultiArrayLayout::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Float64MultiArray::Builder::setLayout( ::mrp::std::MultiArrayLayout::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::MultiArrayLayout::Builder Float64MultiArray::Builder::initLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Float64MultiArray::Builder::adoptLayout( + ::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> Float64MultiArray::Builder::disownLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Float64MultiArray::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Float64MultiArray::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader Float64MultiArray::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder Float64MultiArray::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Float64MultiArray::Builder::setData( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void Float64MultiArray::Builder::setData(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder Float64MultiArray::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Float64MultiArray::Builder::adoptData( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> Float64MultiArray::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::uint32_t Header::Reader::getSeq() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Header::Builder::getSeq() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Header::Builder::setSeq( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool Header::Reader::hasStamp() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Header::Builder::hasStamp() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Time::Reader Header::Reader::getStamp() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Time::Builder Header::Builder::getStamp() { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Time::Pipeline Header::Pipeline::getStamp() { + return ::mrp::std::Time::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Header::Builder::setStamp( ::mrp::std::Time::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Time>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Time::Builder Header::Builder::initStamp() { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Header::Builder::adoptStamp( + ::capnp::Orphan< ::mrp::std::Time>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Time>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Time> Header::Builder::disownStamp() { + return ::capnp::_::PointerHelpers< ::mrp::std::Time>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Header::Reader::hasFrameId() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Header::Builder::hasFrameId() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Header::Reader::getFrameId() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Header::Builder::getFrameId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Header::Builder::setFrameId( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Header::Builder::initFrameId(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Header::Builder::adoptFrameId( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Header::Builder::disownFrameId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Int16MultiArray::Reader::hasLayout() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Int16MultiArray::Builder::hasLayout() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::MultiArrayLayout::Reader Int16MultiArray::Reader::getLayout() const { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::MultiArrayLayout::Builder Int16MultiArray::Builder::getLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::MultiArrayLayout::Pipeline Int16MultiArray::Pipeline::getLayout() { + return ::mrp::std::MultiArrayLayout::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Int16MultiArray::Builder::setLayout( ::mrp::std::MultiArrayLayout::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::MultiArrayLayout::Builder Int16MultiArray::Builder::initLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Int16MultiArray::Builder::adoptLayout( + ::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> Int16MultiArray::Builder::disownLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Int16MultiArray::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Int16MultiArray::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Reader Int16MultiArray::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Builder Int16MultiArray::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Int16MultiArray::Builder::setData( ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void Int16MultiArray::Builder::setData(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>::Builder Int16MultiArray::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Int16MultiArray::Builder::adoptData( + ::capnp::Orphan< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>> Int16MultiArray::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int16_t, ::capnp::Kind::PRIMITIVE>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Int32MultiArray::Reader::hasLayout() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Int32MultiArray::Builder::hasLayout() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::MultiArrayLayout::Reader Int32MultiArray::Reader::getLayout() const { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::MultiArrayLayout::Builder Int32MultiArray::Builder::getLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::MultiArrayLayout::Pipeline Int32MultiArray::Pipeline::getLayout() { + return ::mrp::std::MultiArrayLayout::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Int32MultiArray::Builder::setLayout( ::mrp::std::MultiArrayLayout::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::MultiArrayLayout::Builder Int32MultiArray::Builder::initLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Int32MultiArray::Builder::adoptLayout( + ::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> Int32MultiArray::Builder::disownLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Int32MultiArray::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Int32MultiArray::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Reader Int32MultiArray::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Builder Int32MultiArray::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Int32MultiArray::Builder::setData( ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void Int32MultiArray::Builder::setData(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>::Builder Int32MultiArray::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Int32MultiArray::Builder::adoptData( + ::capnp::Orphan< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>> Int32MultiArray::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int32_t, ::capnp::Kind::PRIMITIVE>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Int64MultiArray::Reader::hasLayout() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Int64MultiArray::Builder::hasLayout() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::MultiArrayLayout::Reader Int64MultiArray::Reader::getLayout() const { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::MultiArrayLayout::Builder Int64MultiArray::Builder::getLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::MultiArrayLayout::Pipeline Int64MultiArray::Pipeline::getLayout() { + return ::mrp::std::MultiArrayLayout::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Int64MultiArray::Builder::setLayout( ::mrp::std::MultiArrayLayout::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::MultiArrayLayout::Builder Int64MultiArray::Builder::initLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Int64MultiArray::Builder::adoptLayout( + ::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> Int64MultiArray::Builder::disownLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Int64MultiArray::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Int64MultiArray::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>::Reader Int64MultiArray::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>::Builder Int64MultiArray::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Int64MultiArray::Builder::setData( ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void Int64MultiArray::Builder::setData(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>::Builder Int64MultiArray::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Int64MultiArray::Builder::adoptData( + ::capnp::Orphan< ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>> Int64MultiArray::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::int64_t, ::capnp::Kind::PRIMITIVE>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool Int8MultiArray::Reader::hasLayout() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Int8MultiArray::Builder::hasLayout() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::MultiArrayLayout::Reader Int8MultiArray::Reader::getLayout() const { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::MultiArrayLayout::Builder Int8MultiArray::Builder::getLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::MultiArrayLayout::Pipeline Int8MultiArray::Pipeline::getLayout() { + return ::mrp::std::MultiArrayLayout::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Int8MultiArray::Builder::setLayout( ::mrp::std::MultiArrayLayout::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::MultiArrayLayout::Builder Int8MultiArray::Builder::initLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Int8MultiArray::Builder::adoptLayout( + ::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> Int8MultiArray::Builder::disownLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Int8MultiArray::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Int8MultiArray::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Data::Reader Int8MultiArray::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Data::Builder Int8MultiArray::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Int8MultiArray::Builder::setData( ::capnp::Data::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Data::Builder Int8MultiArray::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Data>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Int8MultiArray::Builder::adoptData( + ::capnp::Orphan< ::capnp::Data>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Data> Int8MultiArray::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool MultiArrayDimension::Reader::hasLabel() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiArrayDimension::Builder::hasLabel() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader MultiArrayDimension::Reader::getLabel() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder MultiArrayDimension::Builder::getLabel() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MultiArrayDimension::Builder::setLabel( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder MultiArrayDimension::Builder::initLabel(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void MultiArrayDimension::Builder::adoptLabel( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> MultiArrayDimension::Builder::disownLabel() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t MultiArrayDimension::Reader::getSize() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t MultiArrayDimension::Builder::getSize() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void MultiArrayDimension::Builder::setSize( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t MultiArrayDimension::Reader::getStride() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t MultiArrayDimension::Builder::getStride() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void MultiArrayDimension::Builder::setStride( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool MultiArrayLayout::Reader::hasDim() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiArrayLayout::Builder::hasDim() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>::Reader MultiArrayLayout::Reader::getDim() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>::Builder MultiArrayLayout::Builder::getDim() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MultiArrayLayout::Builder::setDim( ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>::Builder MultiArrayLayout::Builder::initDim(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void MultiArrayLayout::Builder::adoptDim( + ::capnp::Orphan< ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>> MultiArrayLayout::Builder::disownDim() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::MultiArrayDimension, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t MultiArrayLayout::Reader::getDataOffset() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t MultiArrayLayout::Builder::getDataOffset() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void MultiArrayLayout::Builder::setDataOffset( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool String::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool String::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader String::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder String::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void String::Builder::setData( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder String::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void String::Builder::adoptData( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> String::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t Time::Reader::getSec() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Time::Builder::getSec() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Time::Builder::setSec( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t Time::Reader::getNsec() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t Time::Builder::getNsec() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Time::Builder::setNsec( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool UInt16MultiArray::Reader::hasLayout() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool UInt16MultiArray::Builder::hasLayout() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::MultiArrayLayout::Reader UInt16MultiArray::Reader::getLayout() const { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::MultiArrayLayout::Builder UInt16MultiArray::Builder::getLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::MultiArrayLayout::Pipeline UInt16MultiArray::Pipeline::getLayout() { + return ::mrp::std::MultiArrayLayout::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void UInt16MultiArray::Builder::setLayout( ::mrp::std::MultiArrayLayout::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::MultiArrayLayout::Builder UInt16MultiArray::Builder::initLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void UInt16MultiArray::Builder::adoptLayout( + ::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> UInt16MultiArray::Builder::disownLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool UInt16MultiArray::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool UInt16MultiArray::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>::Reader UInt16MultiArray::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>::Builder UInt16MultiArray::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void UInt16MultiArray::Builder::setData( ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void UInt16MultiArray::Builder::setData(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>::Builder UInt16MultiArray::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void UInt16MultiArray::Builder::adoptData( + ::capnp::Orphan< ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>> UInt16MultiArray::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint16_t, ::capnp::Kind::PRIMITIVE>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool UInt32MultiArray::Reader::hasLayout() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool UInt32MultiArray::Builder::hasLayout() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::MultiArrayLayout::Reader UInt32MultiArray::Reader::getLayout() const { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::MultiArrayLayout::Builder UInt32MultiArray::Builder::getLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::MultiArrayLayout::Pipeline UInt32MultiArray::Pipeline::getLayout() { + return ::mrp::std::MultiArrayLayout::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void UInt32MultiArray::Builder::setLayout( ::mrp::std::MultiArrayLayout::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::MultiArrayLayout::Builder UInt32MultiArray::Builder::initLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void UInt32MultiArray::Builder::adoptLayout( + ::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> UInt32MultiArray::Builder::disownLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool UInt32MultiArray::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool UInt32MultiArray::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Reader UInt32MultiArray::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Builder UInt32MultiArray::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void UInt32MultiArray::Builder::setData( ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void UInt32MultiArray::Builder::setData(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>::Builder UInt32MultiArray::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void UInt32MultiArray::Builder::adoptData( + ::capnp::Orphan< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>> UInt32MultiArray::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint32_t, ::capnp::Kind::PRIMITIVE>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool UInt64MultiArray::Reader::hasLayout() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool UInt64MultiArray::Builder::hasLayout() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::MultiArrayLayout::Reader UInt64MultiArray::Reader::getLayout() const { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::MultiArrayLayout::Builder UInt64MultiArray::Builder::getLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::MultiArrayLayout::Pipeline UInt64MultiArray::Pipeline::getLayout() { + return ::mrp::std::MultiArrayLayout::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void UInt64MultiArray::Builder::setLayout( ::mrp::std::MultiArrayLayout::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::MultiArrayLayout::Builder UInt64MultiArray::Builder::initLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void UInt64MultiArray::Builder::adoptLayout( + ::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> UInt64MultiArray::Builder::disownLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool UInt64MultiArray::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool UInt64MultiArray::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>::Reader UInt64MultiArray::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>::Builder UInt64MultiArray::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void UInt64MultiArray::Builder::setData( ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void UInt64MultiArray::Builder::setData(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>::Builder UInt64MultiArray::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void UInt64MultiArray::Builder::adoptData( + ::capnp::Orphan< ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>> UInt64MultiArray::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::uint64_t, ::capnp::Kind::PRIMITIVE>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool UInt8MultiArray::Reader::hasLayout() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool UInt8MultiArray::Builder::hasLayout() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::MultiArrayLayout::Reader UInt8MultiArray::Reader::getLayout() const { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::MultiArrayLayout::Builder UInt8MultiArray::Builder::getLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::MultiArrayLayout::Pipeline UInt8MultiArray::Pipeline::getLayout() { + return ::mrp::std::MultiArrayLayout::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void UInt8MultiArray::Builder::setLayout( ::mrp::std::MultiArrayLayout::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::MultiArrayLayout::Builder UInt8MultiArray::Builder::initLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void UInt8MultiArray::Builder::adoptLayout( + ::capnp::Orphan< ::mrp::std::MultiArrayLayout>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::MultiArrayLayout> UInt8MultiArray::Builder::disownLayout() { + return ::capnp::_::PointerHelpers< ::mrp::std::MultiArrayLayout>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool UInt8MultiArray::Reader::hasData() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool UInt8MultiArray::Builder::hasData() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Data::Reader UInt8MultiArray::Reader::getData() const { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Data::Builder UInt8MultiArray::Builder::getData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void UInt8MultiArray::Builder::setData( ::capnp::Data::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Data::Builder UInt8MultiArray::Builder::initData(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Data>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void UInt8MultiArray::Builder::adoptData( + ::capnp::Orphan< ::capnp::Data>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Data>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Data> UInt8MultiArray::Builder::disownData() { + return ::capnp::_::PointerHelpers< ::capnp::Data>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +} // namespace +} // namespace + +CAPNP_END_HEADER + diff --git a/msg/src/fairomsg/cpp/stereo_msgs.capnp.c++ b/msg/src/fairomsg/cpp/stereo_msgs.capnp.c++ new file mode 100644 index 0000000000..8e4d2c478b --- /dev/null +++ b/msg/src/fairomsg/cpp/stereo_msgs.capnp.c++ @@ -0,0 +1,185 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: stereo_msgs.capnp + +#include "stereo_msgs.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<142> b_858a55eca55d6633 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 51, 102, 93, 165, 236, 85, 138, 133, + 22, 0, 0, 0, 1, 0, 3, 0, + 114, 225, 81, 76, 28, 160, 33, 132, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 115, 116, 101, 114, + 101, 111, 95, 109, 115, 103, 115, 46, + 99, 97, 112, 110, 112, 58, 68, 105, + 115, 112, 97, 114, 105, 116, 121, 73, + 109, 97, 103, 101, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 0, 0, 0, 3, 0, 1, 0, + 236, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 0, 0, 0, 3, 0, 1, 0, + 252, 0, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 0, 1, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 109, 97, 103, 101, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 11, 188, 143, 68, 13, 239, 42, 158, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 108, 105, 100, 87, 105, 110, + 100, 111, 119, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 74, 170, 172, 113, 191, 219, 200, 208, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 105, 110, 68, 105, 115, 112, 97, + 114, 105, 116, 121, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 120, 68, 105, 115, 112, 97, + 114, 105, 116, 121, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 108, 116, 97, 68, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_858a55eca55d6633 = b_858a55eca55d6633.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_858a55eca55d6633[] = { + &s_9e2aef0d448fbc0b, + &s_cf9a8bcf03922937, + &s_d0c8dbbf71acaa4a, +}; +static const uint16_t m_858a55eca55d6633[] = {7, 2, 0, 1, 6, 5, 3, 4}; +static const uint16_t i_858a55eca55d6633[] = {0, 1, 2, 3, 4, 5, 6, 7}; +const ::capnp::_::RawSchema s_858a55eca55d6633 = { + 0x858a55eca55d6633, b_858a55eca55d6633.words, 142, d_858a55eca55d6633, m_858a55eca55d6633, + 3, 8, i_858a55eca55d6633, nullptr, nullptr, { &s_858a55eca55d6633, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace mrp { +namespace stereo { + +// DisparityImage +constexpr uint16_t DisparityImage::_capnpPrivate::dataWordSize; +constexpr uint16_t DisparityImage::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind DisparityImage::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* DisparityImage::_capnpPrivate::schema; +#endif // !CAPNP_LITE + + +} // namespace +} // namespace + diff --git a/msg/src/fairomsg/cpp/stereo_msgs.capnp.h b/msg/src/fairomsg/cpp/stereo_msgs.capnp.h new file mode 100644 index 0000000000..1a9311c1d6 --- /dev/null +++ b/msg/src/fairomsg/cpp/stereo_msgs.capnp.h @@ -0,0 +1,368 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: stereo_msgs.capnp + +#pragma once + +#include +#include + +#if CAPNP_VERSION != 9001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + +#include "sensor_msgs.capnp.h" +#include "std_msgs.capnp.h" + +CAPNP_BEGIN_HEADER + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(858a55eca55d6633); + +} // namespace schemas +} // namespace capnp + +namespace mrp { +namespace stereo { + +struct DisparityImage { + DisparityImage() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(858a55eca55d6633, 3, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class DisparityImage::Reader { +public: + typedef DisparityImage Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasImage() const; + inline ::mrp::sensor::Image::Reader getImage() const; + + inline float getF() const; + + inline float getT() const; + + inline bool hasValidWindow() const; + inline ::mrp::sensor::RegionOfInterest::Reader getValidWindow() const; + + inline float getMinDisparity() const; + + inline float getMaxDisparity() const; + + inline float getDeltaD() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class DisparityImage::Builder { +public: + typedef DisparityImage Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasImage(); + inline ::mrp::sensor::Image::Builder getImage(); + inline void setImage( ::mrp::sensor::Image::Reader value); + inline ::mrp::sensor::Image::Builder initImage(); + inline void adoptImage(::capnp::Orphan< ::mrp::sensor::Image>&& value); + inline ::capnp::Orphan< ::mrp::sensor::Image> disownImage(); + + inline float getF(); + inline void setF(float value); + + inline float getT(); + inline void setT(float value); + + inline bool hasValidWindow(); + inline ::mrp::sensor::RegionOfInterest::Builder getValidWindow(); + inline void setValidWindow( ::mrp::sensor::RegionOfInterest::Reader value); + inline ::mrp::sensor::RegionOfInterest::Builder initValidWindow(); + inline void adoptValidWindow(::capnp::Orphan< ::mrp::sensor::RegionOfInterest>&& value); + inline ::capnp::Orphan< ::mrp::sensor::RegionOfInterest> disownValidWindow(); + + inline float getMinDisparity(); + inline void setMinDisparity(float value); + + inline float getMaxDisparity(); + inline void setMaxDisparity(float value); + + inline float getDeltaD(); + inline void setDeltaD(float value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class DisparityImage::Pipeline { +public: + typedef DisparityImage Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::sensor::Image::Pipeline getImage(); + inline ::mrp::sensor::RegionOfInterest::Pipeline getValidWindow(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline bool DisparityImage::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool DisparityImage::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader DisparityImage::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder DisparityImage::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline DisparityImage::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void DisparityImage::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder DisparityImage::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void DisparityImage::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> DisparityImage::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool DisparityImage::Reader::hasImage() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool DisparityImage::Builder::hasImage() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::sensor::Image::Reader DisparityImage::Reader::getImage() const { + return ::capnp::_::PointerHelpers< ::mrp::sensor::Image>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::sensor::Image::Builder DisparityImage::Builder::getImage() { + return ::capnp::_::PointerHelpers< ::mrp::sensor::Image>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::sensor::Image::Pipeline DisparityImage::Pipeline::getImage() { + return ::mrp::sensor::Image::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void DisparityImage::Builder::setImage( ::mrp::sensor::Image::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::sensor::Image>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::sensor::Image::Builder DisparityImage::Builder::initImage() { + return ::capnp::_::PointerHelpers< ::mrp::sensor::Image>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void DisparityImage::Builder::adoptImage( + ::capnp::Orphan< ::mrp::sensor::Image>&& value) { + ::capnp::_::PointerHelpers< ::mrp::sensor::Image>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::sensor::Image> DisparityImage::Builder::disownImage() { + return ::capnp::_::PointerHelpers< ::mrp::sensor::Image>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline float DisparityImage::Reader::getF() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline float DisparityImage::Builder::getF() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void DisparityImage::Builder::setF(float value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline float DisparityImage::Reader::getT() const { + return _reader.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline float DisparityImage::Builder::getT() { + return _builder.getDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void DisparityImage::Builder::setT(float value) { + _builder.setDataField( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool DisparityImage::Reader::hasValidWindow() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool DisparityImage::Builder::hasValidWindow() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::sensor::RegionOfInterest::Reader DisparityImage::Reader::getValidWindow() const { + return ::capnp::_::PointerHelpers< ::mrp::sensor::RegionOfInterest>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::mrp::sensor::RegionOfInterest::Builder DisparityImage::Builder::getValidWindow() { + return ::capnp::_::PointerHelpers< ::mrp::sensor::RegionOfInterest>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::sensor::RegionOfInterest::Pipeline DisparityImage::Pipeline::getValidWindow() { + return ::mrp::sensor::RegionOfInterest::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void DisparityImage::Builder::setValidWindow( ::mrp::sensor::RegionOfInterest::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::sensor::RegionOfInterest>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::mrp::sensor::RegionOfInterest::Builder DisparityImage::Builder::initValidWindow() { + return ::capnp::_::PointerHelpers< ::mrp::sensor::RegionOfInterest>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void DisparityImage::Builder::adoptValidWindow( + ::capnp::Orphan< ::mrp::sensor::RegionOfInterest>&& value) { + ::capnp::_::PointerHelpers< ::mrp::sensor::RegionOfInterest>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::sensor::RegionOfInterest> DisparityImage::Builder::disownValidWindow() { + return ::capnp::_::PointerHelpers< ::mrp::sensor::RegionOfInterest>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline float DisparityImage::Reader::getMinDisparity() const { + return _reader.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline float DisparityImage::Builder::getMinDisparity() { + return _builder.getDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void DisparityImage::Builder::setMinDisparity(float value) { + _builder.setDataField( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline float DisparityImage::Reader::getMaxDisparity() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline float DisparityImage::Builder::getMaxDisparity() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void DisparityImage::Builder::setMaxDisparity(float value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline float DisparityImage::Reader::getDeltaD() const { + return _reader.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} + +inline float DisparityImage::Builder::getDeltaD() { + return _builder.getDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS); +} +inline void DisparityImage::Builder::setDeltaD(float value) { + _builder.setDataField( + ::capnp::bounded<4>() * ::capnp::ELEMENTS, value); +} + +} // namespace +} // namespace + +CAPNP_END_HEADER + diff --git a/msg/src/fairomsg/cpp/trajectory_msgs.capnp.c++ b/msg/src/fairomsg/cpp/trajectory_msgs.capnp.c++ new file mode 100644 index 0000000000..985ef5394a --- /dev/null +++ b/msg/src/fairomsg/cpp/trajectory_msgs.capnp.c++ @@ -0,0 +1,472 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: trajectory_msgs.capnp + +#include "trajectory_msgs.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<74> b_85bc0f442bf3d0c7 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 199, 208, 243, 43, 68, 15, 188, 133, + 26, 0, 0, 0, 1, 0, 0, 0, + 255, 96, 167, 211, 100, 249, 203, 156, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 116, 114, 97, 106, + 101, 99, 116, 111, 114, 121, 95, 109, + 115, 103, 115, 46, 99, 97, 112, 110, + 112, 58, 74, 111, 105, 110, 116, 84, + 114, 97, 106, 101, 99, 116, 111, 114, + 121, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 100, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 106, 111, 105, 110, 116, 78, 97, 109, + 101, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 105, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 155, 220, 38, 218, 36, 163, 95, 201, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_85bc0f442bf3d0c7 = b_85bc0f442bf3d0c7.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_85bc0f442bf3d0c7[] = { + &s_c95fa324da26dc9b, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_85bc0f442bf3d0c7[] = {0, 1, 2}; +static const uint16_t i_85bc0f442bf3d0c7[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_85bc0f442bf3d0c7 = { + 0x85bc0f442bf3d0c7, b_85bc0f442bf3d0c7.words, 74, d_85bc0f442bf3d0c7, m_85bc0f442bf3d0c7, + 2, 3, i_85bc0f442bf3d0c7, nullptr, nullptr, { &s_85bc0f442bf3d0c7, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<115> b_c95fa324da26dc9b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 155, 220, 38, 218, 36, 163, 95, 201, + 26, 0, 0, 0, 1, 0, 0, 0, + 255, 96, 167, 211, 100, 249, 203, 156, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 122, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 116, 114, 97, 106, + 101, 99, 116, 111, 114, 121, 95, 109, + 115, 103, 115, 46, 99, 97, 112, 110, + 112, 58, 74, 111, 105, 110, 116, 84, + 114, 97, 106, 101, 99, 116, 111, 114, + 121, 80, 111, 105, 110, 116, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 152, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 176, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 115, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 108, 111, 99, 105, 116, 105, + 101, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 101, 114, 97, + 116, 105, 111, 110, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 102, 102, 111, 114, 116, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 70, 114, 111, 109, + 83, 116, 97, 114, 116, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 255, 129, 45, 236, 206, 91, 186, 143, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c95fa324da26dc9b = b_c95fa324da26dc9b.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c95fa324da26dc9b[] = { + &s_8fba5bceec2d81ff, +}; +static const uint16_t m_c95fa324da26dc9b[] = {2, 3, 0, 4, 1}; +static const uint16_t i_c95fa324da26dc9b[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_c95fa324da26dc9b = { + 0xc95fa324da26dc9b, b_c95fa324da26dc9b.words, 115, d_c95fa324da26dc9b, m_c95fa324da26dc9b, + 1, 5, i_c95fa324da26dc9b, nullptr, nullptr, { &s_c95fa324da26dc9b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<75> b_f89d6f946cf774de = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 222, 116, 247, 108, 148, 111, 157, 248, + 26, 0, 0, 0, 1, 0, 0, 0, + 255, 96, 167, 211, 100, 249, 203, 156, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 116, 114, 97, 106, + 101, 99, 116, 111, 114, 121, 95, 109, + 115, 103, 115, 46, 99, 97, 112, 110, + 112, 58, 77, 117, 108, 116, 105, 68, + 79, 70, 74, 111, 105, 110, 116, 84, + 114, 97, 106, 101, 99, 116, 111, 114, + 121, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 100, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 106, 111, 105, 110, 116, 78, 97, 109, + 101, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 105, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 213, 149, 65, 55, 85, 85, 242, 218, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f89d6f946cf774de = b_f89d6f946cf774de.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f89d6f946cf774de[] = { + &s_cf9a8bcf03922937, + &s_daf25555374195d5, +}; +static const uint16_t m_f89d6f946cf774de[] = {0, 1, 2}; +static const uint16_t i_f89d6f946cf774de[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_f89d6f946cf774de = { + 0xf89d6f946cf774de, b_f89d6f946cf774de.words, 75, d_f89d6f946cf774de, m_f89d6f946cf774de, + 2, 3, i_f89d6f946cf774de, nullptr, nullptr, { &s_f89d6f946cf774de, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<97> b_daf25555374195d5 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 213, 149, 65, 55, 85, 85, 242, 218, + 26, 0, 0, 0, 1, 0, 0, 0, + 255, 96, 167, 211, 100, 249, 203, 156, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 186, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 116, 114, 97, 106, + 101, 99, 116, 111, 114, 121, 95, 109, + 115, 103, 115, 46, 99, 97, 112, 110, + 112, 58, 77, 117, 108, 116, 105, 68, + 79, 70, 74, 111, 105, 110, 116, 84, + 114, 97, 106, 101, 99, 116, 111, 114, + 121, 80, 111, 105, 110, 116, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 116, 114, 97, 110, 115, 102, 111, 114, + 109, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 188, 173, 16, 182, 50, 63, 34, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 108, 111, 99, 105, 116, 105, + 101, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 197, 5, 214, 69, 57, 245, 239, 227, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 101, 114, 97, + 116, 105, 111, 110, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 197, 5, 214, 69, 57, 245, 239, 227, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 70, 114, 111, 109, + 83, 116, 97, 114, 116, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 255, 129, 45, 236, 206, 91, 186, 143, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_daf25555374195d5 = b_daf25555374195d5.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_daf25555374195d5[] = { + &s_8fba5bceec2d81ff, + &s_cf223f32b610adbc, + &s_e3eff53945d605c5, +}; +static const uint16_t m_daf25555374195d5[] = {2, 3, 0, 1}; +static const uint16_t i_daf25555374195d5[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_daf25555374195d5 = { + 0xdaf25555374195d5, b_daf25555374195d5.words, 97, d_daf25555374195d5, m_daf25555374195d5, + 3, 4, i_daf25555374195d5, nullptr, nullptr, { &s_daf25555374195d5, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace mrp { +namespace trajectory { + +// JointTrajectory +constexpr uint16_t JointTrajectory::_capnpPrivate::dataWordSize; +constexpr uint16_t JointTrajectory::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind JointTrajectory::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* JointTrajectory::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// JointTrajectoryPoint +constexpr uint16_t JointTrajectoryPoint::_capnpPrivate::dataWordSize; +constexpr uint16_t JointTrajectoryPoint::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind JointTrajectoryPoint::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* JointTrajectoryPoint::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// MultiDOFJointTrajectory +constexpr uint16_t MultiDOFJointTrajectory::_capnpPrivate::dataWordSize; +constexpr uint16_t MultiDOFJointTrajectory::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind MultiDOFJointTrajectory::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* MultiDOFJointTrajectory::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// MultiDOFJointTrajectoryPoint +constexpr uint16_t MultiDOFJointTrajectoryPoint::_capnpPrivate::dataWordSize; +constexpr uint16_t MultiDOFJointTrajectoryPoint::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind MultiDOFJointTrajectoryPoint::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* MultiDOFJointTrajectoryPoint::_capnpPrivate::schema; +#endif // !CAPNP_LITE + + +} // namespace +} // namespace + diff --git a/msg/src/fairomsg/cpp/trajectory_msgs.capnp.h b/msg/src/fairomsg/cpp/trajectory_msgs.capnp.h new file mode 100644 index 0000000000..a2f6ef03c0 --- /dev/null +++ b/msg/src/fairomsg/cpp/trajectory_msgs.capnp.h @@ -0,0 +1,1098 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: trajectory_msgs.capnp + +#pragma once + +#include +#include + +#if CAPNP_VERSION != 9001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + +#include "geometry_msgs.capnp.h" +#include "std_msgs.capnp.h" + +CAPNP_BEGIN_HEADER + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(85bc0f442bf3d0c7); +CAPNP_DECLARE_SCHEMA(c95fa324da26dc9b); +CAPNP_DECLARE_SCHEMA(f89d6f946cf774de); +CAPNP_DECLARE_SCHEMA(daf25555374195d5); + +} // namespace schemas +} // namespace capnp + +namespace mrp { +namespace trajectory { + +struct JointTrajectory { + JointTrajectory() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(85bc0f442bf3d0c7, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct JointTrajectoryPoint { + JointTrajectoryPoint() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c95fa324da26dc9b, 0, 5) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct MultiDOFJointTrajectory { + MultiDOFJointTrajectory() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(f89d6f946cf774de, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct MultiDOFJointTrajectoryPoint { + MultiDOFJointTrajectoryPoint() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(daf25555374195d5, 0, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class JointTrajectory::Reader { +public: + typedef JointTrajectory Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasJointNames() const; + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader getJointNames() const; + + inline bool hasPoints() const; + inline ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>::Reader getPoints() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JointTrajectory::Builder { +public: + typedef JointTrajectory Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasJointNames(); + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder getJointNames(); + inline void setJointNames( ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader value); + inline void setJointNames(::kj::ArrayPtr value); + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder initJointNames(unsigned int size); + inline void adoptJointNames(::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>> disownJointNames(); + + inline bool hasPoints(); + inline ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>::Builder getPoints(); + inline void setPoints( ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>::Builder initPoints(unsigned int size); + inline void adoptPoints(::capnp::Orphan< ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>> disownPoints(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JointTrajectory::Pipeline { +public: + typedef JointTrajectory Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class JointTrajectoryPoint::Reader { +public: + typedef JointTrajectoryPoint Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasPositions() const; + inline ::capnp::List::Reader getPositions() const; + + inline bool hasVelocities() const; + inline ::capnp::List::Reader getVelocities() const; + + inline bool hasAccelerations() const; + inline ::capnp::List::Reader getAccelerations() const; + + inline bool hasEffort() const; + inline ::capnp::List::Reader getEffort() const; + + inline bool hasTimeFromStart() const; + inline ::mrp::std::Duration::Reader getTimeFromStart() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class JointTrajectoryPoint::Builder { +public: + typedef JointTrajectoryPoint Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasPositions(); + inline ::capnp::List::Builder getPositions(); + inline void setPositions( ::capnp::List::Reader value); + inline void setPositions(::kj::ArrayPtr value); + inline ::capnp::List::Builder initPositions(unsigned int size); + inline void adoptPositions(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownPositions(); + + inline bool hasVelocities(); + inline ::capnp::List::Builder getVelocities(); + inline void setVelocities( ::capnp::List::Reader value); + inline void setVelocities(::kj::ArrayPtr value); + inline ::capnp::List::Builder initVelocities(unsigned int size); + inline void adoptVelocities(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownVelocities(); + + inline bool hasAccelerations(); + inline ::capnp::List::Builder getAccelerations(); + inline void setAccelerations( ::capnp::List::Reader value); + inline void setAccelerations(::kj::ArrayPtr value); + inline ::capnp::List::Builder initAccelerations(unsigned int size); + inline void adoptAccelerations(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownAccelerations(); + + inline bool hasEffort(); + inline ::capnp::List::Builder getEffort(); + inline void setEffort( ::capnp::List::Reader value); + inline void setEffort(::kj::ArrayPtr value); + inline ::capnp::List::Builder initEffort(unsigned int size); + inline void adoptEffort(::capnp::Orphan< ::capnp::List>&& value); + inline ::capnp::Orphan< ::capnp::List> disownEffort(); + + inline bool hasTimeFromStart(); + inline ::mrp::std::Duration::Builder getTimeFromStart(); + inline void setTimeFromStart( ::mrp::std::Duration::Reader value); + inline ::mrp::std::Duration::Builder initTimeFromStart(); + inline void adoptTimeFromStart(::capnp::Orphan< ::mrp::std::Duration>&& value); + inline ::capnp::Orphan< ::mrp::std::Duration> disownTimeFromStart(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class JointTrajectoryPoint::Pipeline { +public: + typedef JointTrajectoryPoint Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Duration::Pipeline getTimeFromStart(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class MultiDOFJointTrajectory::Reader { +public: + typedef MultiDOFJointTrajectory Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasJointNames() const; + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader getJointNames() const; + + inline bool hasPoints() const; + inline ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>::Reader getPoints() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class MultiDOFJointTrajectory::Builder { +public: + typedef MultiDOFJointTrajectory Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasJointNames(); + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder getJointNames(); + inline void setJointNames( ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader value); + inline void setJointNames(::kj::ArrayPtr value); + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder initJointNames(unsigned int size); + inline void adoptJointNames(::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>> disownJointNames(); + + inline bool hasPoints(); + inline ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>::Builder getPoints(); + inline void setPoints( ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>::Builder initPoints(unsigned int size); + inline void adoptPoints(::capnp::Orphan< ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>> disownPoints(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class MultiDOFJointTrajectory::Pipeline { +public: + typedef MultiDOFJointTrajectory Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class MultiDOFJointTrajectoryPoint::Reader { +public: + typedef MultiDOFJointTrajectoryPoint Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasTransforms() const; + inline ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Reader getTransforms() const; + + inline bool hasVelocities() const; + inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Reader getVelocities() const; + + inline bool hasAccelerations() const; + inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Reader getAccelerations() const; + + inline bool hasTimeFromStart() const; + inline ::mrp::std::Duration::Reader getTimeFromStart() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class MultiDOFJointTrajectoryPoint::Builder { +public: + typedef MultiDOFJointTrajectoryPoint Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasTransforms(); + inline ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Builder getTransforms(); + inline void setTransforms( ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Builder initTransforms(unsigned int size); + inline void adoptTransforms(::capnp::Orphan< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>> disownTransforms(); + + inline bool hasVelocities(); + inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Builder getVelocities(); + inline void setVelocities( ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Builder initVelocities(unsigned int size); + inline void adoptVelocities(::capnp::Orphan< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>> disownVelocities(); + + inline bool hasAccelerations(); + inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Builder getAccelerations(); + inline void setAccelerations( ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Builder initAccelerations(unsigned int size); + inline void adoptAccelerations(::capnp::Orphan< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>> disownAccelerations(); + + inline bool hasTimeFromStart(); + inline ::mrp::std::Duration::Builder getTimeFromStart(); + inline void setTimeFromStart( ::mrp::std::Duration::Reader value); + inline ::mrp::std::Duration::Builder initTimeFromStart(); + inline void adoptTimeFromStart(::capnp::Orphan< ::mrp::std::Duration>&& value); + inline ::capnp::Orphan< ::mrp::std::Duration> disownTimeFromStart(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class MultiDOFJointTrajectoryPoint::Pipeline { +public: + typedef MultiDOFJointTrajectoryPoint Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Duration::Pipeline getTimeFromStart(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline bool JointTrajectory::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JointTrajectory::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader JointTrajectory::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder JointTrajectory::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline JointTrajectory::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void JointTrajectory::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder JointTrajectory::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JointTrajectory::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> JointTrajectory::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JointTrajectory::Reader::hasJointNames() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool JointTrajectory::Builder::hasJointNames() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader JointTrajectory::Reader::getJointNames() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder JointTrajectory::Builder::getJointNames() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void JointTrajectory::Builder::setJointNames( ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void JointTrajectory::Builder::setJointNames(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder JointTrajectory::Builder::initJointNames(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void JointTrajectory::Builder::adoptJointNames( + ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>> JointTrajectory::Builder::disownJointNames() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool JointTrajectory::Reader::hasPoints() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool JointTrajectory::Builder::hasPoints() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>::Reader JointTrajectory::Reader::getPoints() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>::Builder JointTrajectory::Builder::getPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void JointTrajectory::Builder::setPoints( ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>::Builder JointTrajectory::Builder::initPoints(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void JointTrajectory::Builder::adoptPoints( + ::capnp::Orphan< ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>> JointTrajectory::Builder::disownPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::trajectory::JointTrajectoryPoint, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool JointTrajectoryPoint::Reader::hasPositions() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool JointTrajectoryPoint::Builder::hasPositions() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader JointTrajectoryPoint::Reader::getPositions() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder JointTrajectoryPoint::Builder::getPositions() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void JointTrajectoryPoint::Builder::setPositions( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline void JointTrajectoryPoint::Builder::setPositions(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder JointTrajectoryPoint::Builder::initPositions(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void JointTrajectoryPoint::Builder::adoptPositions( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> JointTrajectoryPoint::Builder::disownPositions() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool JointTrajectoryPoint::Reader::hasVelocities() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool JointTrajectoryPoint::Builder::hasVelocities() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader JointTrajectoryPoint::Reader::getVelocities() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder JointTrajectoryPoint::Builder::getVelocities() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void JointTrajectoryPoint::Builder::setVelocities( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void JointTrajectoryPoint::Builder::setVelocities(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder JointTrajectoryPoint::Builder::initVelocities(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void JointTrajectoryPoint::Builder::adoptVelocities( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> JointTrajectoryPoint::Builder::disownVelocities() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool JointTrajectoryPoint::Reader::hasAccelerations() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool JointTrajectoryPoint::Builder::hasAccelerations() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader JointTrajectoryPoint::Reader::getAccelerations() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder JointTrajectoryPoint::Builder::getAccelerations() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void JointTrajectoryPoint::Builder::setAccelerations( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline void JointTrajectoryPoint::Builder::setAccelerations(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder JointTrajectoryPoint::Builder::initAccelerations(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void JointTrajectoryPoint::Builder::adoptAccelerations( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> JointTrajectoryPoint::Builder::disownAccelerations() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool JointTrajectoryPoint::Reader::hasEffort() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool JointTrajectoryPoint::Builder::hasEffort() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List::Reader JointTrajectoryPoint::Reader::getEffort() const { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::List::Builder JointTrajectoryPoint::Builder::getEffort() { + return ::capnp::_::PointerHelpers< ::capnp::List>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void JointTrajectoryPoint::Builder::setEffort( ::capnp::List::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline void JointTrajectoryPoint::Builder::setEffort(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::List::Builder JointTrajectoryPoint::Builder::initEffort(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void JointTrajectoryPoint::Builder::adoptEffort( + ::capnp::Orphan< ::capnp::List>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List> JointTrajectoryPoint::Builder::disownEffort() { + return ::capnp::_::PointerHelpers< ::capnp::List>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool JointTrajectoryPoint::Reader::hasTimeFromStart() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool JointTrajectoryPoint::Builder::hasTimeFromStart() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Duration::Reader JointTrajectoryPoint::Reader::getTimeFromStart() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Duration::Builder JointTrajectoryPoint::Builder::getTimeFromStart() { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Duration::Pipeline JointTrajectoryPoint::Pipeline::getTimeFromStart() { + return ::mrp::std::Duration::Pipeline(_typeless.getPointerField(4)); +} +#endif // !CAPNP_LITE +inline void JointTrajectoryPoint::Builder::setTimeFromStart( ::mrp::std::Duration::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Duration>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Duration::Builder JointTrajectoryPoint::Builder::initTimeFromStart() { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void JointTrajectoryPoint::Builder::adoptTimeFromStart( + ::capnp::Orphan< ::mrp::std::Duration>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Duration>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Duration> JointTrajectoryPoint::Builder::disownTimeFromStart() { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline bool MultiDOFJointTrajectory::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiDOFJointTrajectory::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader MultiDOFJointTrajectory::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder MultiDOFJointTrajectory::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline MultiDOFJointTrajectory::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void MultiDOFJointTrajectory::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder MultiDOFJointTrajectory::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MultiDOFJointTrajectory::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> MultiDOFJointTrajectory::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool MultiDOFJointTrajectory::Reader::hasJointNames() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiDOFJointTrajectory::Builder::hasJointNames() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader MultiDOFJointTrajectory::Reader::getJointNames() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder MultiDOFJointTrajectory::Builder::getJointNames() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void MultiDOFJointTrajectory::Builder::setJointNames( ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline void MultiDOFJointTrajectory::Builder::setJointNames(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder MultiDOFJointTrajectory::Builder::initJointNames(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void MultiDOFJointTrajectory::Builder::adoptJointNames( + ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>> MultiDOFJointTrajectory::Builder::disownJointNames() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool MultiDOFJointTrajectory::Reader::hasPoints() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiDOFJointTrajectory::Builder::hasPoints() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>::Reader MultiDOFJointTrajectory::Reader::getPoints() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>::Builder MultiDOFJointTrajectory::Builder::getPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void MultiDOFJointTrajectory::Builder::setPoints( ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>::Builder MultiDOFJointTrajectory::Builder::initPoints(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void MultiDOFJointTrajectory::Builder::adoptPoints( + ::capnp::Orphan< ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>> MultiDOFJointTrajectory::Builder::disownPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::trajectory::MultiDOFJointTrajectoryPoint, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool MultiDOFJointTrajectoryPoint::Reader::hasTransforms() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiDOFJointTrajectoryPoint::Builder::hasTransforms() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Reader MultiDOFJointTrajectoryPoint::Reader::getTransforms() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Builder MultiDOFJointTrajectoryPoint::Builder::getTransforms() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MultiDOFJointTrajectoryPoint::Builder::setTransforms( ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>::Builder MultiDOFJointTrajectoryPoint::Builder::initTransforms(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void MultiDOFJointTrajectoryPoint::Builder::adoptTransforms( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>> MultiDOFJointTrajectoryPoint::Builder::disownTransforms() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Transform, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool MultiDOFJointTrajectoryPoint::Reader::hasVelocities() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiDOFJointTrajectoryPoint::Builder::hasVelocities() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Reader MultiDOFJointTrajectoryPoint::Reader::getVelocities() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Builder MultiDOFJointTrajectoryPoint::Builder::getVelocities() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void MultiDOFJointTrajectoryPoint::Builder::setVelocities( ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Builder MultiDOFJointTrajectoryPoint::Builder::initVelocities(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void MultiDOFJointTrajectoryPoint::Builder::adoptVelocities( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>> MultiDOFJointTrajectoryPoint::Builder::disownVelocities() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool MultiDOFJointTrajectoryPoint::Reader::hasAccelerations() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiDOFJointTrajectoryPoint::Builder::hasAccelerations() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Reader MultiDOFJointTrajectoryPoint::Reader::getAccelerations() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Builder MultiDOFJointTrajectoryPoint::Builder::getAccelerations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void MultiDOFJointTrajectoryPoint::Builder::setAccelerations( ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>::Builder MultiDOFJointTrajectoryPoint::Builder::initAccelerations(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void MultiDOFJointTrajectoryPoint::Builder::adoptAccelerations( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>> MultiDOFJointTrajectoryPoint::Builder::disownAccelerations() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Twist, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool MultiDOFJointTrajectoryPoint::Reader::hasTimeFromStart() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool MultiDOFJointTrajectoryPoint::Builder::hasTimeFromStart() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Duration::Reader MultiDOFJointTrajectoryPoint::Reader::getTimeFromStart() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Duration::Builder MultiDOFJointTrajectoryPoint::Builder::getTimeFromStart() { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Duration::Pipeline MultiDOFJointTrajectoryPoint::Pipeline::getTimeFromStart() { + return ::mrp::std::Duration::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void MultiDOFJointTrajectoryPoint::Builder::setTimeFromStart( ::mrp::std::Duration::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Duration>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Duration::Builder MultiDOFJointTrajectoryPoint::Builder::initTimeFromStart() { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void MultiDOFJointTrajectoryPoint::Builder::adoptTimeFromStart( + ::capnp::Orphan< ::mrp::std::Duration>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Duration>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Duration> MultiDOFJointTrajectoryPoint::Builder::disownTimeFromStart() { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +} // namespace +} // namespace + +CAPNP_END_HEADER + diff --git a/msg/src/fairomsg/cpp/visualization_msgs.capnp.c++ b/msg/src/fairomsg/cpp/visualization_msgs.capnp.c++ new file mode 100644 index 0000000000..d1f6ddb4c5 --- /dev/null +++ b/msg/src/fairomsg/cpp/visualization_msgs.capnp.c++ @@ -0,0 +1,3605 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: visualization_msgs.capnp + +#include "visualization_msgs.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<252> b_b340cf7c3d62a5e1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 225, 165, 98, 61, 124, 207, 64, 179, + 29, 0, 0, 0, 1, 0, 3, 0, + 139, 215, 25, 168, 123, 194, 57, 163, + 8, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 223, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 109, 97, + 103, 101, 77, 97, 114, 107, 101, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 0, 0, 0, 1, 0, 1, 0, + 75, 8, 125, 136, 217, 144, 109, 172, + 49, 0, 0, 0, 66, 0, 0, 0, + 186, 27, 122, 169, 17, 106, 68, 255, + 45, 0, 0, 0, 90, 0, 0, 0, + 118, 134, 255, 232, 53, 146, 212, 178, + 45, 0, 0, 0, 82, 0, 0, 0, + 87, 130, 176, 237, 175, 3, 113, 236, + 45, 0, 0, 0, 74, 0, 0, 0, + 102, 214, 174, 78, 191, 251, 88, 145, + 45, 0, 0, 0, 66, 0, 0, 0, + 103, 120, 110, 233, 207, 240, 133, 194, + 41, 0, 0, 0, 42, 0, 0, 0, + 90, 121, 132, 182, 59, 148, 102, 203, + 37, 0, 0, 0, 66, 0, 0, 0, + 107, 67, 105, 114, 99, 108, 101, 0, + 107, 76, 105, 110, 101, 83, 116, 114, + 105, 112, 0, 0, 0, 0, 0, 0, + 107, 76, 105, 110, 101, 76, 105, 115, + 116, 0, 0, 0, 0, 0, 0, 0, + 107, 80, 111, 108, 121, 103, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 80, 111, 105, 110, 116, 115, 0, + 107, 65, 100, 100, 0, 0, 0, 0, + 107, 82, 101, 109, 111, 118, 101, 0, + 52, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 1, 0, 0, 3, 0, 1, 0, + 100, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 1, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 1, 0, 0, 3, 0, 1, 0, + 104, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 1, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 1, 0, 0, 3, 0, 1, 0, + 108, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 1, 0, 0, 3, 0, 1, 0, + 112, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 1, 0, 0, 3, 0, 1, 0, + 116, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 1, 0, 0, 3, 0, 1, 0, + 124, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 1, 0, 0, 3, 0, 1, 0, + 128, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 1, 0, 0, 3, 0, 1, 0, + 136, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 1, 0, 0, 3, 0, 1, 0, + 140, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 1, 0, 0, 3, 0, 1, 0, + 148, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 1, 0, 0, 3, 0, 1, 0, + 156, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 1, 0, 0, 3, 0, 1, 0, + 176, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 1, 0, 0, 3, 0, 1, 0, + 200, 1, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 115, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 100, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 105, 111, 110, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 68, 59, 77, 248, 154, 89, 171, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 99, 97, 108, 101, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 117, 116, 108, 105, 110, 101, 67, + 111, 108, 111, 114, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 112, 79, 171, 49, 46, 210, 221, 252, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 108, 108, 101, 100, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 108, 108, 67, 111, 108, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 112, 79, 171, 49, 46, 210, 221, 252, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 102, 101, 116, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 255, 129, 45, 236, 206, 91, 186, 143, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 105, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 68, 59, 77, 248, 154, 89, 171, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 117, 116, 108, 105, 110, 101, 67, + 111, 108, 111, 114, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 112, 79, 171, 49, 46, 210, 221, 252, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b340cf7c3d62a5e1 = b_b340cf7c3d62a5e1.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_b340cf7c3d62a5e1[] = { + &s_8fba5bceec2d81ff, + &s_cf9a8bcf03922937, + &s_ebab599af84d3b44, + &s_fcddd22e31ab4f70, +}; +static const uint16_t m_b340cf7c3d62a5e1[] = {4, 9, 8, 0, 2, 10, 1, 7, 12, 11, 5, 6, 3}; +static const uint16_t i_b340cf7c3d62a5e1[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; +const ::capnp::_::RawSchema s_b340cf7c3d62a5e1 = { + 0xb340cf7c3d62a5e1, b_b340cf7c3d62a5e1.words, 252, d_b340cf7c3d62a5e1, m_b340cf7c3d62a5e1, + 4, 13, i_b340cf7c3d62a5e1, nullptr, nullptr, { &s_b340cf7c3d62a5e1, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_ac6d90d9887d084b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 75, 8, 125, 136, 217, 144, 109, 172, + 41, 0, 0, 0, 4, 0, 0, 0, + 225, 165, 98, 61, 124, 207, 64, 179, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 138, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 109, 97, + 103, 101, 77, 97, 114, 107, 101, 114, + 46, 107, 67, 105, 114, 99, 108, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ac6d90d9887d084b = b_ac6d90d9887d084b.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_ac6d90d9887d084b = { + 0xac6d90d9887d084b, b_ac6d90d9887d084b.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_ac6d90d9887d084b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_ff446a11a97a1bba = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 186, 27, 122, 169, 17, 106, 68, 255, + 41, 0, 0, 0, 4, 0, 0, 0, + 225, 165, 98, 61, 124, 207, 64, 179, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 109, 97, + 103, 101, 77, 97, 114, 107, 101, 114, + 46, 107, 76, 105, 110, 101, 83, 116, + 114, 105, 112, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ff446a11a97a1bba = b_ff446a11a97a1bba.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_ff446a11a97a1bba = { + 0xff446a11a97a1bba, b_ff446a11a97a1bba.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_ff446a11a97a1bba, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_b2d49235e8ff8676 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 118, 134, 255, 232, 53, 146, 212, 178, + 41, 0, 0, 0, 4, 0, 0, 0, + 225, 165, 98, 61, 124, 207, 64, 179, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 109, 97, + 103, 101, 77, 97, 114, 107, 101, 114, + 46, 107, 76, 105, 110, 101, 76, 105, + 115, 116, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b2d49235e8ff8676 = b_b2d49235e8ff8676.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_b2d49235e8ff8676 = { + 0xb2d49235e8ff8676, b_b2d49235e8ff8676.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_b2d49235e8ff8676, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_ec7103afedb08257 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 87, 130, 176, 237, 175, 3, 113, 236, + 41, 0, 0, 0, 4, 0, 0, 0, + 225, 165, 98, 61, 124, 207, 64, 179, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 109, 97, + 103, 101, 77, 97, 114, 107, 101, 114, + 46, 107, 80, 111, 108, 121, 103, 111, + 110, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ec7103afedb08257 = b_ec7103afedb08257.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_ec7103afedb08257 = { + 0xec7103afedb08257, b_ec7103afedb08257.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_ec7103afedb08257, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_9158fbbf4eaed666 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 102, 214, 174, 78, 191, 251, 88, 145, + 41, 0, 0, 0, 4, 0, 0, 0, + 225, 165, 98, 61, 124, 207, 64, 179, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 138, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 109, 97, + 103, 101, 77, 97, 114, 107, 101, 114, + 46, 107, 80, 111, 105, 110, 116, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 4, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9158fbbf4eaed666 = b_9158fbbf4eaed666.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_9158fbbf4eaed666 = { + 0x9158fbbf4eaed666, b_9158fbbf4eaed666.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_9158fbbf4eaed666, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_c285f0cfe96e7867 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 103, 120, 110, 233, 207, 240, 133, 194, + 41, 0, 0, 0, 4, 0, 0, 0, + 225, 165, 98, 61, 124, 207, 64, 179, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 114, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 109, 97, + 103, 101, 77, 97, 114, 107, 101, 114, + 46, 107, 65, 100, 100, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c285f0cfe96e7867 = b_c285f0cfe96e7867.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c285f0cfe96e7867 = { + 0xc285f0cfe96e7867, b_c285f0cfe96e7867.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c285f0cfe96e7867, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_cb66943bb684795a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 90, 121, 132, 182, 59, 148, 102, 203, + 41, 0, 0, 0, 4, 0, 0, 0, + 225, 165, 98, 61, 124, 207, 64, 179, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 138, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 109, 97, + 103, 101, 77, 97, 114, 107, 101, 114, + 46, 107, 82, 101, 109, 111, 118, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cb66943bb684795a = b_cb66943bb684795a.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_cb66943bb684795a = { + 0xcb66943bb684795a, b_cb66943bb684795a.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_cb66943bb684795a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<136> b_dab40ba8c922b4ba = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 186, 180, 34, 201, 168, 11, 180, 218, + 29, 0, 0, 0, 1, 0, 1, 0, + 139, 215, 25, 168, 123, 194, 57, 163, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 122, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 0, 0, 0, 3, 0, 1, 0, + 0, 1, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 168, 139, 201, 190, 163, 197, 246, 170, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 99, 114, 105, 112, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 99, 97, 108, 101, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 110, 117, 69, 110, 116, 114, + 105, 101, 115, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 218, 115, 190, 240, 233, 7, 25, 142, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 110, 116, 114, 111, 108, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_dab40ba8c922b4ba = b_dab40ba8c922b4ba.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_dab40ba8c922b4ba[] = { + &s_8e1907e9f0be73da, + &s_aaf6c5a3bec98ba8, + &s_b4ad12860007ca93, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_dab40ba8c922b4ba[] = {6, 3, 0, 5, 2, 1, 4}; +static const uint16_t i_dab40ba8c922b4ba[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_dab40ba8c922b4ba = { + 0xdab40ba8c922b4ba, b_dab40ba8c922b4ba.words, 136, d_dab40ba8c922b4ba, m_dab40ba8c922b4ba, + 4, 7, i_dab40ba8c922b4ba, nullptr, nullptr, { &s_dab40ba8c922b4ba, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<200> b_b4ad12860007ca93 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 29, 0, 0, 0, 1, 0, 1, 0, + 139, 215, 25, 168, 123, 194, 57, 163, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 1, 0, 0, + 45, 0, 0, 0, 215, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 0, 0, 0, + 52, 0, 0, 0, 1, 0, 1, 0, + 140, 49, 150, 212, 12, 141, 141, 187, + 97, 0, 0, 0, 74, 0, 0, 0, + 95, 136, 130, 98, 11, 105, 5, 252, + 97, 0, 0, 0, 58, 0, 0, 0, + 95, 209, 16, 172, 187, 18, 173, 183, + 93, 0, 0, 0, 98, 0, 0, 0, + 123, 128, 122, 23, 108, 27, 195, 251, + 93, 0, 0, 0, 50, 0, 0, 0, + 114, 73, 207, 126, 162, 53, 30, 247, + 89, 0, 0, 0, 50, 0, 0, 0, + 129, 232, 243, 6, 3, 90, 17, 187, + 85, 0, 0, 0, 66, 0, 0, 0, + 72, 56, 142, 57, 56, 242, 81, 251, + 81, 0, 0, 0, 82, 0, 0, 0, + 6, 27, 122, 168, 79, 202, 171, 187, + 81, 0, 0, 0, 90, 0, 0, 0, + 195, 76, 0, 159, 18, 10, 210, 195, + 81, 0, 0, 0, 98, 0, 0, 0, + 233, 30, 254, 24, 253, 221, 17, 233, + 81, 0, 0, 0, 98, 0, 0, 0, + 194, 116, 160, 162, 228, 171, 216, 233, + 81, 0, 0, 0, 66, 0, 0, 0, + 81, 252, 122, 69, 127, 169, 164, 232, + 77, 0, 0, 0, 82, 0, 0, 0, + 109, 88, 86, 129, 235, 60, 74, 183, + 77, 0, 0, 0, 114, 0, 0, 0, + 107, 73, 110, 104, 101, 114, 105, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 70, 105, 120, 101, 100, 0, 0, + 107, 86, 105, 101, 119, 70, 97, 99, + 105, 110, 103, 0, 0, 0, 0, 0, + 107, 78, 111, 110, 101, 0, 0, 0, + 107, 77, 101, 110, 117, 0, 0, 0, + 107, 66, 117, 116, 116, 111, 110, 0, + 107, 77, 111, 118, 101, 65, 120, 105, + 115, 0, 0, 0, 0, 0, 0, 0, + 107, 77, 111, 118, 101, 80, 108, 97, + 110, 101, 0, 0, 0, 0, 0, 0, + 107, 82, 111, 116, 97, 116, 101, 65, + 120, 105, 115, 0, 0, 0, 0, 0, + 107, 77, 111, 118, 101, 82, 111, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 107, 77, 111, 118, 101, 51, 68, 0, + 107, 82, 111, 116, 97, 116, 101, 51, + 68, 0, 0, 0, 0, 0, 0, 0, + 107, 77, 111, 118, 101, 82, 111, 116, + 97, 116, 101, 51, 68, 0, 0, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 0, 0, 0, 3, 0, 1, 0, + 240, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 0, 0, 0, 3, 0, 1, 0, + 12, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 1, 0, 0, 3, 0, 1, 0, + 36, 1, 0, 0, 2, 0, 1, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 101, 110, 116, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 100, 4, 183, 255, 76, 138, 17, 175, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 101, 110, 116, 97, 116, + 105, 111, 110, 77, 111, 100, 101, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 97, 99, 116, + 105, 111, 110, 77, 111, 100, 101, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 119, 97, 121, 115, 86, 105, + 115, 105, 98, 108, 101, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 114, 107, 101, 114, 115, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 100, 101, 112, 101, 110, 100, + 101, 110, 116, 77, 97, 114, 107, 101, + 114, 79, 114, 105, 101, 110, 116, 97, + 116, 105, 111, 110, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 99, 114, 105, 112, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b4ad12860007ca93 = b_b4ad12860007ca93.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_b4ad12860007ca93[] = { + &s_9ac063ef5a4f120f, + &s_af118a4cffb70464, +}; +static const uint16_t m_b4ad12860007ca93[] = {4, 7, 6, 3, 5, 0, 1, 2}; +static const uint16_t i_b4ad12860007ca93[] = {0, 1, 2, 3, 4, 5, 6, 7}; +const ::capnp::_::RawSchema s_b4ad12860007ca93 = { + 0xb4ad12860007ca93, b_b4ad12860007ca93.words, 200, d_b4ad12860007ca93, m_b4ad12860007ca93, + 2, 8, i_b4ad12860007ca93, nullptr, nullptr, { &s_b4ad12860007ca93, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_bb8d8d0cd496318c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 140, 49, 150, 212, 12, 141, 141, 187, + 54, 0, 0, 0, 4, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 46, 107, 73, + 110, 104, 101, 114, 105, 116, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bb8d8d0cd496318c = b_bb8d8d0cd496318c.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_bb8d8d0cd496318c = { + 0xbb8d8d0cd496318c, b_bb8d8d0cd496318c.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_bb8d8d0cd496318c, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_fc05690b6282885f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 95, 136, 130, 98, 11, 105, 5, 252, + 54, 0, 0, 0, 4, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 46, 107, 70, + 105, 120, 101, 100, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fc05690b6282885f = b_fc05690b6282885f.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_fc05690b6282885f = { + 0xfc05690b6282885f, b_fc05690b6282885f.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_fc05690b6282885f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_b7ad12bbac10d15f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 95, 209, 16, 172, 187, 18, 173, 183, + 54, 0, 0, 0, 4, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 46, 107, 86, + 105, 101, 119, 70, 97, 99, 105, 110, + 103, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b7ad12bbac10d15f = b_b7ad12bbac10d15f.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_b7ad12bbac10d15f = { + 0xb7ad12bbac10d15f, b_b7ad12bbac10d15f.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_b7ad12bbac10d15f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_fbc31b6c177a807b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 123, 128, 122, 23, 108, 27, 195, 251, + 54, 0, 0, 0, 4, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 226, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 46, 107, 78, + 111, 110, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fbc31b6c177a807b = b_fbc31b6c177a807b.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_fbc31b6c177a807b = { + 0xfbc31b6c177a807b, b_fbc31b6c177a807b.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_fbc31b6c177a807b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_f71e35a27ecf4972 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 114, 73, 207, 126, 162, 53, 30, 247, + 54, 0, 0, 0, 4, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 226, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 46, 107, 77, + 101, 110, 117, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f71e35a27ecf4972 = b_f71e35a27ecf4972.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_f71e35a27ecf4972 = { + 0xf71e35a27ecf4972, b_f71e35a27ecf4972.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_f71e35a27ecf4972, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_bb115a0306f3e881 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 129, 232, 243, 6, 3, 90, 17, 187, + 54, 0, 0, 0, 4, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 46, 107, 66, + 117, 116, 116, 111, 110, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bb115a0306f3e881 = b_bb115a0306f3e881.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_bb115a0306f3e881 = { + 0xbb115a0306f3e881, b_bb115a0306f3e881.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_bb115a0306f3e881, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_fb51f238398e3848 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 72, 56, 142, 57, 56, 242, 81, 251, + 54, 0, 0, 0, 4, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 2, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 46, 107, 77, + 111, 118, 101, 65, 120, 105, 115, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fb51f238398e3848 = b_fb51f238398e3848.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_fb51f238398e3848 = { + 0xfb51f238398e3848, b_fb51f238398e3848.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_fb51f238398e3848, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_bbabca4fa87a1b06 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 6, 27, 122, 168, 79, 202, 171, 187, + 54, 0, 0, 0, 4, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 46, 107, 77, + 111, 118, 101, 80, 108, 97, 110, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 4, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bbabca4fa87a1b06 = b_bbabca4fa87a1b06.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_bbabca4fa87a1b06 = { + 0xbbabca4fa87a1b06, b_bbabca4fa87a1b06.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_bbabca4fa87a1b06, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_c3d20a129f004cc3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 195, 76, 0, 159, 18, 10, 210, 195, + 54, 0, 0, 0, 4, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 46, 107, 82, + 111, 116, 97, 116, 101, 65, 120, 105, + 115, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 5, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c3d20a129f004cc3 = b_c3d20a129f004cc3.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c3d20a129f004cc3 = { + 0xc3d20a129f004cc3, b_c3d20a129f004cc3.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c3d20a129f004cc3, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_e911ddfd18fe1ee9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 233, 30, 254, 24, 253, 221, 17, 233, + 54, 0, 0, 0, 4, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 46, 107, 77, + 111, 118, 101, 82, 111, 116, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 6, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e911ddfd18fe1ee9 = b_e911ddfd18fe1ee9.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_e911ddfd18fe1ee9 = { + 0xe911ddfd18fe1ee9, b_e911ddfd18fe1ee9.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_e911ddfd18fe1ee9, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_e9d8abe4a2a074c2 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 194, 116, 160, 162, 228, 171, 216, 233, + 54, 0, 0, 0, 4, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 46, 107, 77, + 111, 118, 101, 51, 68, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e9d8abe4a2a074c2 = b_e9d8abe4a2a074c2.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_e9d8abe4a2a074c2 = { + 0xe9d8abe4a2a074c2, b_e9d8abe4a2a074c2.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_e9d8abe4a2a074c2, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_e8a4a97f457afc51 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 81, 252, 122, 69, 127, 169, 164, 232, + 54, 0, 0, 0, 4, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 2, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 46, 107, 82, + 111, 116, 97, 116, 101, 51, 68, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 8, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e8a4a97f457afc51 = b_e8a4a97f457afc51.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_e8a4a97f457afc51 = { + 0xe8a4a97f457afc51, b_e8a4a97f457afc51.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_e8a4a97f457afc51, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_b74a3ceb8156586d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 109, 88, 86, 129, 235, 60, 74, 183, + 54, 0, 0, 0, 4, 0, 0, 0, + 147, 202, 7, 0, 134, 18, 173, 180, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 67, 111, + 110, 116, 114, 111, 108, 46, 107, 77, + 111, 118, 101, 82, 111, 116, 97, 116, + 101, 51, 68, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 9, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b74a3ceb8156586d = b_b74a3ceb8156586d.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_b74a3ceb8156586d = { + 0xb74a3ceb8156586d, b_b74a3ceb8156586d.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_b74a3ceb8156586d, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<187> b_8717a25b15e06c03 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 3, 108, 224, 21, 91, 162, 23, 135, + 29, 0, 0, 0, 1, 0, 1, 0, + 139, 215, 25, 168, 123, 194, 57, 163, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 186, 1, 0, 0, + 45, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 255, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 70, 101, + 101, 100, 98, 97, 99, 107, 0, 0, + 24, 0, 0, 0, 1, 0, 1, 0, + 144, 122, 142, 118, 245, 39, 240, 172, + 41, 0, 0, 0, 90, 0, 0, 0, + 160, 176, 26, 114, 124, 231, 74, 197, + 41, 0, 0, 0, 98, 0, 0, 0, + 37, 252, 162, 3, 171, 36, 232, 164, + 41, 0, 0, 0, 98, 0, 0, 0, + 88, 134, 70, 54, 71, 15, 78, 149, + 41, 0, 0, 0, 106, 0, 0, 0, + 188, 93, 251, 104, 137, 250, 171, 187, + 41, 0, 0, 0, 90, 0, 0, 0, + 155, 52, 119, 99, 212, 159, 70, 223, + 41, 0, 0, 0, 74, 0, 0, 0, + 107, 75, 101, 101, 112, 65, 108, 105, + 118, 101, 0, 0, 0, 0, 0, 0, + 107, 80, 111, 115, 101, 85, 112, 100, + 97, 116, 101, 0, 0, 0, 0, 0, + 107, 77, 101, 110, 117, 83, 101, 108, + 101, 99, 116, 0, 0, 0, 0, 0, + 107, 66, 117, 116, 116, 111, 110, 67, + 108, 105, 99, 107, 0, 0, 0, 0, + 107, 77, 111, 117, 115, 101, 68, 111, + 119, 110, 0, 0, 0, 0, 0, 0, + 107, 77, 111, 117, 115, 101, 85, 112, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 0, 0, 0, 3, 0, 1, 0, + 252, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 0, 0, 0, 3, 0, 1, 0, + 4, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1, 0, 0, 3, 0, 1, 0, + 12, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 1, 0, 0, 3, 0, 1, 0, + 40, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 105, 101, 110, 116, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 114, 107, 101, 114, 78, 97, + 109, 101, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 110, 116, 114, 111, 108, 78, + 97, 109, 101, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 118, 101, 110, 116, 84, 121, 112, + 101, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 168, 139, 201, 190, 163, 197, 246, 170, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 110, 117, 69, 110, 116, 114, + 121, 73, 100, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 117, 115, 101, 80, 111, 105, + 110, 116, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 68, 59, 77, 248, 154, 89, 171, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 117, 115, 101, 80, 111, 105, + 110, 116, 86, 97, 108, 105, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8717a25b15e06c03 = b_8717a25b15e06c03.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_8717a25b15e06c03[] = { + &s_aaf6c5a3bec98ba8, + &s_cf9a8bcf03922937, + &s_ebab599af84d3b44, +}; +static const uint16_t m_8717a25b15e06c03[] = {1, 3, 4, 0, 2, 6, 7, 8, 5}; +static const uint16_t i_8717a25b15e06c03[] = {0, 1, 2, 3, 4, 5, 6, 7, 8}; +const ::capnp::_::RawSchema s_8717a25b15e06c03 = { + 0x8717a25b15e06c03, b_8717a25b15e06c03.words, 187, d_8717a25b15e06c03, m_8717a25b15e06c03, + 3, 9, i_8717a25b15e06c03, nullptr, nullptr, { &s_8717a25b15e06c03, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_acf027f5768e7a90 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 144, 122, 142, 118, 245, 39, 240, 172, + 55, 0, 0, 0, 4, 0, 0, 0, + 3, 108, 224, 21, 91, 162, 23, 135, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 70, 101, + 101, 100, 98, 97, 99, 107, 46, 107, + 75, 101, 101, 112, 65, 108, 105, 118, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_acf027f5768e7a90 = b_acf027f5768e7a90.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_acf027f5768e7a90 = { + 0xacf027f5768e7a90, b_acf027f5768e7a90.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_acf027f5768e7a90, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_c54ae77c721ab0a0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 160, 176, 26, 114, 124, 231, 74, 197, + 55, 0, 0, 0, 4, 0, 0, 0, + 3, 108, 224, 21, 91, 162, 23, 135, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 70, 101, + 101, 100, 98, 97, 99, 107, 46, 107, + 80, 111, 115, 101, 85, 112, 100, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c54ae77c721ab0a0 = b_c54ae77c721ab0a0.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c54ae77c721ab0a0 = { + 0xc54ae77c721ab0a0, b_c54ae77c721ab0a0.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c54ae77c721ab0a0, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_a4e824ab03a2fc25 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 37, 252, 162, 3, 171, 36, 232, 164, + 55, 0, 0, 0, 4, 0, 0, 0, + 3, 108, 224, 21, 91, 162, 23, 135, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 70, 101, + 101, 100, 98, 97, 99, 107, 46, 107, + 77, 101, 110, 117, 83, 101, 108, 101, + 99, 116, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a4e824ab03a2fc25 = b_a4e824ab03a2fc25.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_a4e824ab03a2fc25 = { + 0xa4e824ab03a2fc25, b_a4e824ab03a2fc25.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_a4e824ab03a2fc25, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_954e0f4736468658 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 88, 134, 70, 54, 71, 15, 78, 149, + 55, 0, 0, 0, 4, 0, 0, 0, + 3, 108, 224, 21, 91, 162, 23, 135, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 70, 101, + 101, 100, 98, 97, 99, 107, 46, 107, + 66, 117, 116, 116, 111, 110, 67, 108, + 105, 99, 107, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_954e0f4736468658 = b_954e0f4736468658.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_954e0f4736468658 = { + 0x954e0f4736468658, b_954e0f4736468658.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_954e0f4736468658, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<29> b_bbabfa8968fb5dbc = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 188, 93, 251, 104, 137, 250, 171, 187, + 55, 0, 0, 0, 4, 0, 0, 0, + 3, 108, 224, 21, 91, 162, 23, 135, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 70, 101, + 101, 100, 98, 97, 99, 107, 46, 107, + 77, 111, 117, 115, 101, 68, 111, 119, + 110, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 4, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bbabfa8968fb5dbc = b_bbabfa8968fb5dbc.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_bbabfa8968fb5dbc = { + 0xbbabfa8968fb5dbc, b_bbabfa8968fb5dbc.words, 29, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_bbabfa8968fb5dbc, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_df469fd46377349b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 155, 52, 119, 99, 212, 159, 70, 223, + 55, 0, 0, 0, 4, 0, 0, 0, + 3, 108, 224, 21, 91, 162, 23, 135, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 2, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 70, 101, + 101, 100, 98, 97, 99, 107, 46, 107, + 77, 111, 117, 115, 101, 85, 112, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 5, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_df469fd46377349b = b_df469fd46377349b.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_df469fd46377349b = { + 0xdf469fd46377349b, b_df469fd46377349b.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_df469fd46377349b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<71> b_dc53206ad56c678f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 143, 103, 108, 213, 106, 32, 83, 220, + 29, 0, 0, 0, 1, 0, 1, 0, + 139, 215, 25, 168, 123, 194, 57, 163, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 73, 110, + 105, 116, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 115, 101, 114, 118, 101, 114, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 113, 78, 117, 109, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 114, 107, 101, 114, 115, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 186, 180, 34, 201, 168, 11, 180, 218, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_dc53206ad56c678f = b_dc53206ad56c678f.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_dc53206ad56c678f[] = { + &s_dab40ba8c922b4ba, +}; +static const uint16_t m_dc53206ad56c678f[] = {2, 1, 0}; +static const uint16_t i_dc53206ad56c678f[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_dc53206ad56c678f = { + 0xdc53206ad56c678f, b_dc53206ad56c678f.words, 71, d_dc53206ad56c678f, m_dc53206ad56c678f, + 1, 3, i_dc53206ad56c678f, nullptr, nullptr, { &s_dc53206ad56c678f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<66> b_d56a6cd93315d05a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 90, 208, 21, 51, 217, 108, 106, 213, + 29, 0, 0, 0, 1, 0, 0, 0, + 139, 215, 25, 168, 123, 194, 57, 163, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 80, 111, + 115, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 168, 139, 201, 190, 163, 197, 246, 170, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d56a6cd93315d05a = b_d56a6cd93315d05a.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_d56a6cd93315d05a[] = { + &s_aaf6c5a3bec98ba8, + &s_cf9a8bcf03922937, +}; +static const uint16_t m_d56a6cd93315d05a[] = {0, 2, 1}; +static const uint16_t i_d56a6cd93315d05a[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_d56a6cd93315d05a = { + 0xd56a6cd93315d05a, b_d56a6cd93315d05a.words, 66, d_d56a6cd93315d05a, m_d56a6cd93315d05a, + 2, 3, i_d56a6cd93315d05a, nullptr, nullptr, { &s_d56a6cd93315d05a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<131> b_e98e44d10f26c1ad = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 173, 193, 38, 15, 209, 68, 142, 233, + 29, 0, 0, 0, 1, 0, 2, 0, + 139, 215, 25, 168, 123, 194, 57, 163, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 1, 0, 0, + 45, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 85, 112, + 100, 97, 116, 101, 0, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 41, 98, 114, 177, 157, 174, 250, 255, + 9, 0, 0, 0, 90, 0, 0, 0, + 233, 66, 36, 92, 8, 192, 166, 219, + 9, 0, 0, 0, 66, 0, 0, 0, + 107, 75, 101, 101, 112, 65, 108, 105, + 118, 101, 0, 0, 0, 0, 0, 0, + 107, 85, 112, 100, 97, 116, 101, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 0, 0, 0, 3, 0, 1, 0, + 168, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 115, 101, 114, 118, 101, 114, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 113, 78, 117, 109, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 114, 107, 101, 114, 115, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 186, 180, 34, 201, 168, 11, 180, 218, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 90, 208, 21, 51, 217, 108, 106, 213, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 114, 97, 115, 101, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e98e44d10f26c1ad = b_e98e44d10f26c1ad.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_e98e44d10f26c1ad[] = { + &s_d56a6cd93315d05a, + &s_dab40ba8c922b4ba, +}; +static const uint16_t m_e98e44d10f26c1ad[] = {5, 3, 4, 1, 0, 2}; +static const uint16_t i_e98e44d10f26c1ad[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_e98e44d10f26c1ad = { + 0xe98e44d10f26c1ad, b_e98e44d10f26c1ad.words, 131, d_e98e44d10f26c1ad, m_e98e44d10f26c1ad, + 2, 6, i_e98e44d10f26c1ad, nullptr, nullptr, { &s_e98e44d10f26c1ad, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_fffaae9db1726229 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 41, 98, 114, 177, 157, 174, 250, 255, + 53, 0, 0, 0, 4, 0, 0, 0, + 173, 193, 38, 15, 209, 68, 142, 233, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 2, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 85, 112, + 100, 97, 116, 101, 46, 107, 75, 101, + 101, 112, 65, 108, 105, 118, 101, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fffaae9db1726229 = b_fffaae9db1726229.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_fffaae9db1726229 = { + 0xfffaae9db1726229, b_fffaae9db1726229.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_fffaae9db1726229, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<28> b_dba6c0085c2442e9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 233, 66, 36, 92, 8, 192, 166, 219, + 53, 0, 0, 0, 4, 0, 0, 0, + 173, 193, 38, 15, 209, 68, 142, 233, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 1, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 73, 110, 116, + 101, 114, 97, 99, 116, 105, 118, 101, + 77, 97, 114, 107, 101, 114, 85, 112, + 100, 97, 116, 101, 46, 107, 85, 112, + 100, 97, 116, 101, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_dba6c0085c2442e9 = b_dba6c0085c2442e9.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_dba6c0085c2442e9 = { + 0xdba6c0085c2442e9, b_dba6c0085c2442e9.words, 28, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_dba6c0085c2442e9, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<315> b_9ac063ef5a4f120f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 29, 0, 0, 0, 1, 0, 2, 0, + 139, 215, 25, 168, 123, 194, 57, 163, + 10, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 1, 0, 0, 79, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 1, 0, 1, 0, + 63, 253, 139, 171, 95, 25, 217, 203, + 121, 0, 0, 0, 58, 0, 0, 0, + 250, 44, 132, 68, 200, 81, 31, 157, + 117, 0, 0, 0, 50, 0, 0, 0, + 196, 158, 119, 5, 88, 171, 249, 181, + 113, 0, 0, 0, 66, 0, 0, 0, + 218, 15, 62, 218, 98, 29, 52, 230, + 109, 0, 0, 0, 82, 0, 0, 0, + 215, 195, 204, 97, 134, 139, 244, 198, + 109, 0, 0, 0, 90, 0, 0, 0, + 153, 8, 152, 214, 219, 37, 244, 213, + 109, 0, 0, 0, 82, 0, 0, 0, + 138, 247, 217, 193, 24, 221, 134, 189, + 109, 0, 0, 0, 82, 0, 0, 0, + 157, 230, 9, 180, 172, 179, 230, 193, + 109, 0, 0, 0, 98, 0, 0, 0, + 107, 145, 128, 23, 150, 77, 165, 182, + 109, 0, 0, 0, 66, 0, 0, 0, + 100, 41, 66, 2, 128, 51, 249, 208, + 105, 0, 0, 0, 130, 0, 0, 0, + 203, 55, 2, 218, 237, 187, 14, 144, + 105, 0, 0, 0, 114, 0, 0, 0, + 53, 7, 151, 177, 120, 79, 236, 249, + 105, 0, 0, 0, 114, 0, 0, 0, + 190, 2, 1, 146, 82, 45, 95, 253, + 105, 0, 0, 0, 42, 0, 0, 0, + 209, 23, 62, 223, 125, 212, 120, 239, + 101, 0, 0, 0, 66, 0, 0, 0, + 59, 139, 28, 84, 89, 200, 98, 204, + 97, 0, 0, 0, 66, 0, 0, 0, + 130, 223, 223, 233, 106, 52, 15, 155, + 93, 0, 0, 0, 90, 0, 0, 0, + 107, 65, 114, 114, 111, 119, 0, 0, + 107, 67, 117, 98, 101, 0, 0, 0, + 107, 83, 112, 104, 101, 114, 101, 0, + 107, 67, 121, 108, 105, 110, 100, 101, + 114, 0, 0, 0, 0, 0, 0, 0, + 107, 76, 105, 110, 101, 83, 116, 114, + 105, 112, 0, 0, 0, 0, 0, 0, + 107, 76, 105, 110, 101, 76, 105, 115, + 116, 0, 0, 0, 0, 0, 0, 0, + 107, 67, 117, 98, 101, 76, 105, 115, + 116, 0, 0, 0, 0, 0, 0, 0, + 107, 83, 112, 104, 101, 114, 101, 76, + 105, 115, 116, 0, 0, 0, 0, 0, + 107, 80, 111, 105, 110, 116, 115, 0, + 107, 84, 101, 120, 116, 86, 105, 101, + 119, 70, 97, 99, 105, 110, 103, 0, + 107, 77, 101, 115, 104, 82, 101, 115, + 111, 117, 114, 99, 101, 0, 0, 0, + 107, 84, 114, 105, 97, 110, 103, 108, + 101, 76, 105, 115, 116, 0, 0, 0, + 107, 65, 100, 100, 0, 0, 0, 0, + 107, 77, 111, 100, 105, 102, 121, 0, + 107, 68, 101, 108, 101, 116, 101, 0, + 107, 68, 101, 108, 101, 116, 101, 97, + 108, 108, 0, 0, 0, 0, 0, 0, + 60, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 1, 0, 0, 3, 0, 1, 0, + 156, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 1, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 1, 0, 0, 3, 0, 1, 0, + 160, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 1, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 1, 0, 0, 3, 0, 1, 0, + 164, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 1, 0, 0, 3, 0, 1, 0, + 168, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 1, 0, 0, 3, 0, 1, 0, + 172, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 1, 0, 0, 3, 0, 1, 0, + 176, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 1, 0, 0, 3, 0, 1, 0, + 180, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 1, 0, 0, 3, 0, 1, 0, + 184, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 96, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 1, 0, 0, 3, 0, 1, 0, + 200, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 1, 0, 0, 3, 0, 1, 0, + 220, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 1, 0, 0, 3, 0, 1, 0, + 240, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 1, 0, 0, 3, 0, 1, 0, + 244, 1, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 1, 0, 0, 3, 0, 1, 0, + 252, 1, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 97, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 1, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 2, 0, 0, 3, 0, 1, 0, + 12, 2, 0, 0, 2, 0, 1, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 55, 41, 146, 3, 207, 139, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 115, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 100, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 105, 111, 110, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 168, 139, 201, 190, 163, 197, 246, 170, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 99, 97, 108, 101, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 154, 32, 240, 52, 187, 22, 215, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 108, 111, 114, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 112, 79, 171, 49, 46, 210, 221, 252, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 102, 101, 116, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 255, 129, 45, 236, 206, 91, 186, 143, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 76, 111, 99, + 107, 101, 100, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 105, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 68, 59, 77, 248, 154, 89, 171, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 108, 111, 114, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 112, 79, 171, 49, 46, 210, 221, 252, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 120, 116, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 115, 104, 82, 101, 115, 111, + 117, 114, 99, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 115, 104, 85, 115, 101, 69, + 109, 98, 101, 100, 100, 101, 100, 77, + 97, 116, 101, 114, 105, 97, 108, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9ac063ef5a4f120f = b_9ac063ef5a4f120f.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_9ac063ef5a4f120f[] = { + &s_89d716bb34f0209a, + &s_8fba5bceec2d81ff, + &s_aaf6c5a3bec98ba8, + &s_cf9a8bcf03922937, + &s_ebab599af84d3b44, + &s_fcddd22e31ab4f70, +}; +static const uint16_t m_9ac063ef5a4f120f[] = {4, 7, 11, 9, 0, 2, 8, 13, 14, 1, 10, 5, 6, 12, 3}; +static const uint16_t i_9ac063ef5a4f120f[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14}; +const ::capnp::_::RawSchema s_9ac063ef5a4f120f = { + 0x9ac063ef5a4f120f, b_9ac063ef5a4f120f.words, 315, d_9ac063ef5a4f120f, m_9ac063ef5a4f120f, + 6, 15, i_9ac063ef5a4f120f, nullptr, nullptr, { &s_9ac063ef5a4f120f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_cbd9195fab8bfd3f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 63, 253, 139, 171, 95, 25, 217, 203, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 65, 114, 114, + 111, 119, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cbd9195fab8bfd3f = b_cbd9195fab8bfd3f.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_cbd9195fab8bfd3f = { + 0xcbd9195fab8bfd3f, b_cbd9195fab8bfd3f.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_cbd9195fab8bfd3f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_9d1f51c844842cfa = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 250, 44, 132, 68, 200, 81, 31, 157, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 67, 117, 98, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9d1f51c844842cfa = b_9d1f51c844842cfa.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_9d1f51c844842cfa = { + 0x9d1f51c844842cfa, b_9d1f51c844842cfa.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_9d1f51c844842cfa, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_b5f9ab5805779ec4 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 196, 158, 119, 5, 88, 171, 249, 181, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 98, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 83, 112, 104, + 101, 114, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b5f9ab5805779ec4 = b_b5f9ab5805779ec4.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_b5f9ab5805779ec4 = { + 0xb5f9ab5805779ec4, b_b5f9ab5805779ec4.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_b5f9ab5805779ec4, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_e6341d62da3e0fda = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 218, 15, 62, 218, 98, 29, 52, 230, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 114, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 67, 121, 108, + 105, 110, 100, 101, 114, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e6341d62da3e0fda = b_e6341d62da3e0fda.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_e6341d62da3e0fda = { + 0xe6341d62da3e0fda, b_e6341d62da3e0fda.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_e6341d62da3e0fda, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_c6f48b8661ccc3d7 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 215, 195, 204, 97, 134, 139, 244, 198, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 122, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 76, 105, 110, + 101, 83, 116, 114, 105, 112, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 4, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c6f48b8661ccc3d7 = b_c6f48b8661ccc3d7.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c6f48b8661ccc3d7 = { + 0xc6f48b8661ccc3d7, b_c6f48b8661ccc3d7.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c6f48b8661ccc3d7, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_d5f425dbd6980899 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 153, 8, 152, 214, 219, 37, 244, 213, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 114, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 76, 105, 110, + 101, 76, 105, 115, 116, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 5, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d5f425dbd6980899 = b_d5f425dbd6980899.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_d5f425dbd6980899 = { + 0xd5f425dbd6980899, b_d5f425dbd6980899.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_d5f425dbd6980899, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_bd86dd18c1d9f78a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 138, 247, 217, 193, 24, 221, 134, 189, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 114, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 67, 117, 98, + 101, 76, 105, 115, 116, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 6, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bd86dd18c1d9f78a = b_bd86dd18c1d9f78a.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_bd86dd18c1d9f78a = { + 0xbd86dd18c1d9f78a, b_bd86dd18c1d9f78a.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_bd86dd18c1d9f78a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_c1e6b3acb409e69d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 157, 230, 9, 180, 172, 179, 230, 193, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 130, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 83, 112, 104, + 101, 114, 101, 76, 105, 115, 116, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c1e6b3acb409e69d = b_c1e6b3acb409e69d.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_c1e6b3acb409e69d = { + 0xc1e6b3acb409e69d, b_c1e6b3acb409e69d.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_c1e6b3acb409e69d, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_b6a54d961780916b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 107, 145, 128, 23, 150, 77, 165, 182, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 98, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 80, 111, 105, + 110, 116, 115, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 8, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b6a54d961780916b = b_b6a54d961780916b.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_b6a54d961780916b = { + 0xb6a54d961780916b, b_b6a54d961780916b.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_b6a54d961780916b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_d0f9338002422964 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 100, 41, 66, 2, 128, 51, 249, 208, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 84, 101, 120, + 116, 86, 105, 101, 119, 70, 97, 99, + 105, 110, 103, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 9, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d0f9338002422964 = b_d0f9338002422964.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_d0f9338002422964 = { + 0xd0f9338002422964, b_d0f9338002422964.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_d0f9338002422964, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_900ebbedda0237cb = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 203, 55, 2, 218, 237, 187, 14, 144, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 77, 101, 115, + 104, 82, 101, 115, 111, 117, 114, 99, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 10, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_900ebbedda0237cb = b_900ebbedda0237cb.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_900ebbedda0237cb = { + 0x900ebbedda0237cb, b_900ebbedda0237cb.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_900ebbedda0237cb, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_f9ec4f78b1970735 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 53, 7, 151, 177, 120, 79, 236, 249, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 84, 114, 105, + 97, 110, 103, 108, 101, 76, 105, 115, + 116, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 11, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f9ec4f78b1970735 = b_f9ec4f78b1970735.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_f9ec4f78b1970735 = { + 0xf9ec4f78b1970735, b_f9ec4f78b1970735.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_f9ec4f78b1970735, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_fd5f2d52920102be = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 190, 2, 1, 146, 82, 45, 95, 253, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 65, 100, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fd5f2d52920102be = b_fd5f2d52920102be.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_fd5f2d52920102be = { + 0xfd5f2d52920102be, b_fd5f2d52920102be.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_fd5f2d52920102be, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_ef78d47ddf3e17d1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 209, 23, 62, 223, 125, 212, 120, 239, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 98, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 77, 111, 100, + 105, 102, 121, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ef78d47ddf3e17d1 = b_ef78d47ddf3e17d1.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_ef78d47ddf3e17d1 = { + 0xef78d47ddf3e17d1, b_ef78d47ddf3e17d1.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_ef78d47ddf3e17d1, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_cc62c859541c8b3b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 59, 139, 28, 84, 89, 200, 98, 204, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 98, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 68, 101, 108, + 101, 116, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cc62c859541c8b3b = b_cc62c859541c8b3b.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_cc62c859541c8b3b = { + 0xcc62c859541c8b3b, b_cc62c859541c8b3b.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_cc62c859541c8b3b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_9b0f346ae9dfdf82 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 130, 223, 223, 233, 106, 52, 15, 155, + 36, 0, 0, 0, 4, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 122, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 46, 107, 68, 101, 108, + 101, 116, 101, 97, 108, 108, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 3, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9b0f346ae9dfdf82 = b_9b0f346ae9dfdf82.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_9b0f346ae9dfdf82 = { + 0x9b0f346ae9dfdf82, b_9b0f346ae9dfdf82.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_9b0f346ae9dfdf82, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<39> b_c4b1b8f64ffdf70f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 15, 247, 253, 79, 246, 184, 177, 196, + 29, 0, 0, 0, 1, 0, 0, 0, + 139, 215, 25, 168, 123, 194, 57, 163, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 97, 114, + 107, 101, 114, 65, 114, 114, 97, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 36, 0, 0, 0, 2, 0, 1, 0, + 109, 97, 114, 107, 101, 114, 115, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 15, 18, 79, 90, 239, 99, 192, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c4b1b8f64ffdf70f = b_c4b1b8f64ffdf70f.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c4b1b8f64ffdf70f[] = { + &s_9ac063ef5a4f120f, +}; +static const uint16_t m_c4b1b8f64ffdf70f[] = {0}; +static const uint16_t i_c4b1b8f64ffdf70f[] = {0}; +const ::capnp::_::RawSchema s_c4b1b8f64ffdf70f = { + 0xc4b1b8f64ffdf70f, b_c4b1b8f64ffdf70f.words, 39, d_c4b1b8f64ffdf70f, m_c4b1b8f64ffdf70f, + 1, 1, i_c4b1b8f64ffdf70f, nullptr, nullptr, { &s_c4b1b8f64ffdf70f, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<107> b_8e1907e9f0be73da = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 218, 115, 190, 240, 233, 7, 25, 142, + 29, 0, 0, 0, 1, 0, 2, 0, + 139, 215, 25, 168, 123, 194, 57, 163, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 101, 110, + 117, 69, 110, 116, 114, 121, 0, 0, + 12, 0, 0, 0, 1, 0, 1, 0, + 51, 251, 196, 85, 168, 86, 217, 165, + 17, 0, 0, 0, 82, 0, 0, 0, + 107, 100, 55, 183, 213, 2, 12, 147, + 17, 0, 0, 0, 66, 0, 0, 0, + 74, 63, 249, 209, 107, 239, 226, 178, + 13, 0, 0, 0, 90, 0, 0, 0, + 107, 70, 101, 101, 100, 98, 97, 99, + 107, 0, 0, 0, 0, 0, 0, 0, + 107, 82, 111, 115, 114, 117, 110, 0, + 107, 82, 111, 115, 108, 97, 117, 110, + 99, 104, 0, 0, 0, 0, 0, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 0, 0, 0, 3, 0, 1, 0, + 156, 0, 0, 0, 2, 0, 1, 0, + 105, 100, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 114, 101, 110, 116, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 116, 108, 101, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 109, 109, 97, 110, 100, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 109, 109, 97, 110, 100, 84, + 121, 112, 101, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8e1907e9f0be73da = b_8e1907e9f0be73da.words; +#if !CAPNP_LITE +static const uint16_t m_8e1907e9f0be73da[] = {3, 4, 0, 1, 2}; +static const uint16_t i_8e1907e9f0be73da[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_8e1907e9f0be73da = { + 0x8e1907e9f0be73da, b_8e1907e9f0be73da.words, 107, nullptr, m_8e1907e9f0be73da, + 0, 5, i_8e1907e9f0be73da, nullptr, nullptr, { &s_8e1907e9f0be73da, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_a5d956a855c4fb33 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 51, 251, 196, 85, 168, 86, 217, 165, + 39, 0, 0, 0, 4, 0, 0, 0, + 218, 115, 190, 240, 233, 7, 25, 142, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 138, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 101, 110, + 117, 69, 110, 116, 114, 121, 46, 107, + 70, 101, 101, 100, 98, 97, 99, 107, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a5d956a855c4fb33 = b_a5d956a855c4fb33.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_a5d956a855c4fb33 = { + 0xa5d956a855c4fb33, b_a5d956a855c4fb33.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_a5d956a855c4fb33, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<26> b_930c02d5b737646b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 107, 100, 55, 183, 213, 2, 12, 147, + 39, 0, 0, 0, 4, 0, 0, 0, + 218, 115, 190, 240, 233, 7, 25, 142, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 122, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 101, 110, + 117, 69, 110, 116, 114, 121, 46, 107, + 82, 111, 115, 114, 117, 110, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_930c02d5b737646b = b_930c02d5b737646b.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_930c02d5b737646b = { + 0x930c02d5b737646b, b_930c02d5b737646b.words, 26, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_930c02d5b737646b, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<27> b_b2e2ef6bd1f93f4a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 74, 63, 249, 209, 107, 239, 226, 178, + 39, 0, 0, 0, 4, 0, 0, 0, + 218, 115, 190, 240, 233, 7, 25, 142, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 102, 47, 118, 105, 115, 117, + 97, 108, 105, 122, 97, 116, 105, 111, + 110, 95, 109, 115, 103, 115, 46, 99, + 97, 112, 110, 112, 58, 77, 101, 110, + 117, 69, 110, 116, 114, 121, 46, 107, + 82, 111, 115, 108, 97, 117, 110, 99, + 104, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 2, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b2e2ef6bd1f93f4a = b_b2e2ef6bd1f93f4a.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_b2e2ef6bd1f93f4a = { + 0xb2e2ef6bd1f93f4a, b_b2e2ef6bd1f93f4a.words, 27, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_b2e2ef6bd1f93f4a, nullptr, nullptr, 0, 0, nullptr } +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace mrp { +namespace visualization { + +// ImageMarker +constexpr uint16_t ImageMarker::_capnpPrivate::dataWordSize; +constexpr uint16_t ImageMarker::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind ImageMarker::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ImageMarker::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t ImageMarker::K_CIRCLE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t ImageMarker::K_LINE_STRIP; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t ImageMarker::K_LINE_LIST; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t ImageMarker::K_POLYGON; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t ImageMarker::K_POINTS; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t ImageMarker::K_ADD; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t ImageMarker::K_REMOVE; +#endif +// InteractiveMarker +constexpr uint16_t InteractiveMarker::_capnpPrivate::dataWordSize; +constexpr uint16_t InteractiveMarker::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind InteractiveMarker::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InteractiveMarker::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// InteractiveMarkerControl +constexpr uint16_t InteractiveMarkerControl::_capnpPrivate::dataWordSize; +constexpr uint16_t InteractiveMarkerControl::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind InteractiveMarkerControl::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InteractiveMarkerControl::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerControl::K_INHERIT; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerControl::K_FIXED; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerControl::K_VIEW_FACING; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerControl::K_NONE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerControl::K_MENU; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerControl::K_BUTTON; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerControl::K_MOVE_AXIS; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerControl::K_MOVE_PLANE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerControl::K_ROTATE_AXIS; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerControl::K_MOVE_ROTATE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerControl::K_MOVE3_D; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerControl::K_ROTATE3_D; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerControl::K_MOVE_ROTATE3_D; +#endif +// InteractiveMarkerFeedback +constexpr uint16_t InteractiveMarkerFeedback::_capnpPrivate::dataWordSize; +constexpr uint16_t InteractiveMarkerFeedback::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind InteractiveMarkerFeedback::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InteractiveMarkerFeedback::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerFeedback::K_KEEP_ALIVE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerFeedback::K_POSE_UPDATE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerFeedback::K_MENU_SELECT; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerFeedback::K_BUTTON_CLICK; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerFeedback::K_MOUSE_DOWN; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerFeedback::K_MOUSE_UP; +#endif +// InteractiveMarkerInit +constexpr uint16_t InteractiveMarkerInit::_capnpPrivate::dataWordSize; +constexpr uint16_t InteractiveMarkerInit::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind InteractiveMarkerInit::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InteractiveMarkerInit::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// InteractiveMarkerPose +constexpr uint16_t InteractiveMarkerPose::_capnpPrivate::dataWordSize; +constexpr uint16_t InteractiveMarkerPose::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind InteractiveMarkerPose::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InteractiveMarkerPose::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// InteractiveMarkerUpdate +constexpr uint16_t InteractiveMarkerUpdate::_capnpPrivate::dataWordSize; +constexpr uint16_t InteractiveMarkerUpdate::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind InteractiveMarkerUpdate::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InteractiveMarkerUpdate::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerUpdate::K_KEEP_ALIVE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t InteractiveMarkerUpdate::K_UPDATE; +#endif +// Marker +constexpr uint16_t Marker::_capnpPrivate::dataWordSize; +constexpr uint16_t Marker::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind Marker::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Marker::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_ARROW; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_CUBE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_SPHERE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_CYLINDER; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_LINE_STRIP; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_LINE_LIST; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_CUBE_LIST; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_SPHERE_LIST; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_POINTS; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_TEXT_VIEW_FACING; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_MESH_RESOURCE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_TRIANGLE_LIST; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_ADD; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_MODIFY; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_DELETE; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t Marker::K_DELETEALL; +#endif +// MarkerArray +constexpr uint16_t MarkerArray::_capnpPrivate::dataWordSize; +constexpr uint16_t MarkerArray::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind MarkerArray::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* MarkerArray::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +// MenuEntry +constexpr uint16_t MenuEntry::_capnpPrivate::dataWordSize; +constexpr uint16_t MenuEntry::_capnpPrivate::pointerCount; +#if !CAPNP_LITE +constexpr ::capnp::Kind MenuEntry::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* MenuEntry::_capnpPrivate::schema; +#endif // !CAPNP_LITE + +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t MenuEntry::K_FEEDBACK; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t MenuEntry::K_ROSRUN; +#endif +#if !defined(_MSC_VER) || defined(__clang__) +constexpr ::uint8_t MenuEntry::K_ROSLAUNCH; +#endif + +} // namespace +} // namespace + diff --git a/msg/src/fairomsg/cpp/visualization_msgs.capnp.h b/msg/src/fairomsg/cpp/visualization_msgs.capnp.h new file mode 100644 index 0000000000..6fc3930f30 --- /dev/null +++ b/msg/src/fairomsg/cpp/visualization_msgs.capnp.h @@ -0,0 +1,3593 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: visualization_msgs.capnp + +#pragma once + +#include +#include + +#if CAPNP_VERSION != 9001 +#error "Version mismatch between generated code and library headers. You must use the same version of the Cap'n Proto compiler and library." +#endif + +#include "geometry_msgs.capnp.h" +#include "std_msgs.capnp.h" + +CAPNP_BEGIN_HEADER + +namespace capnp { +namespace schemas { + +CAPNP_DECLARE_SCHEMA(b340cf7c3d62a5e1); +CAPNP_DECLARE_SCHEMA(ac6d90d9887d084b); +CAPNP_DECLARE_SCHEMA(ff446a11a97a1bba); +CAPNP_DECLARE_SCHEMA(b2d49235e8ff8676); +CAPNP_DECLARE_SCHEMA(ec7103afedb08257); +CAPNP_DECLARE_SCHEMA(9158fbbf4eaed666); +CAPNP_DECLARE_SCHEMA(c285f0cfe96e7867); +CAPNP_DECLARE_SCHEMA(cb66943bb684795a); +CAPNP_DECLARE_SCHEMA(dab40ba8c922b4ba); +CAPNP_DECLARE_SCHEMA(b4ad12860007ca93); +CAPNP_DECLARE_SCHEMA(bb8d8d0cd496318c); +CAPNP_DECLARE_SCHEMA(fc05690b6282885f); +CAPNP_DECLARE_SCHEMA(b7ad12bbac10d15f); +CAPNP_DECLARE_SCHEMA(fbc31b6c177a807b); +CAPNP_DECLARE_SCHEMA(f71e35a27ecf4972); +CAPNP_DECLARE_SCHEMA(bb115a0306f3e881); +CAPNP_DECLARE_SCHEMA(fb51f238398e3848); +CAPNP_DECLARE_SCHEMA(bbabca4fa87a1b06); +CAPNP_DECLARE_SCHEMA(c3d20a129f004cc3); +CAPNP_DECLARE_SCHEMA(e911ddfd18fe1ee9); +CAPNP_DECLARE_SCHEMA(e9d8abe4a2a074c2); +CAPNP_DECLARE_SCHEMA(e8a4a97f457afc51); +CAPNP_DECLARE_SCHEMA(b74a3ceb8156586d); +CAPNP_DECLARE_SCHEMA(8717a25b15e06c03); +CAPNP_DECLARE_SCHEMA(acf027f5768e7a90); +CAPNP_DECLARE_SCHEMA(c54ae77c721ab0a0); +CAPNP_DECLARE_SCHEMA(a4e824ab03a2fc25); +CAPNP_DECLARE_SCHEMA(954e0f4736468658); +CAPNP_DECLARE_SCHEMA(bbabfa8968fb5dbc); +CAPNP_DECLARE_SCHEMA(df469fd46377349b); +CAPNP_DECLARE_SCHEMA(dc53206ad56c678f); +CAPNP_DECLARE_SCHEMA(d56a6cd93315d05a); +CAPNP_DECLARE_SCHEMA(e98e44d10f26c1ad); +CAPNP_DECLARE_SCHEMA(fffaae9db1726229); +CAPNP_DECLARE_SCHEMA(dba6c0085c2442e9); +CAPNP_DECLARE_SCHEMA(9ac063ef5a4f120f); +CAPNP_DECLARE_SCHEMA(cbd9195fab8bfd3f); +CAPNP_DECLARE_SCHEMA(9d1f51c844842cfa); +CAPNP_DECLARE_SCHEMA(b5f9ab5805779ec4); +CAPNP_DECLARE_SCHEMA(e6341d62da3e0fda); +CAPNP_DECLARE_SCHEMA(c6f48b8661ccc3d7); +CAPNP_DECLARE_SCHEMA(d5f425dbd6980899); +CAPNP_DECLARE_SCHEMA(bd86dd18c1d9f78a); +CAPNP_DECLARE_SCHEMA(c1e6b3acb409e69d); +CAPNP_DECLARE_SCHEMA(b6a54d961780916b); +CAPNP_DECLARE_SCHEMA(d0f9338002422964); +CAPNP_DECLARE_SCHEMA(900ebbedda0237cb); +CAPNP_DECLARE_SCHEMA(f9ec4f78b1970735); +CAPNP_DECLARE_SCHEMA(fd5f2d52920102be); +CAPNP_DECLARE_SCHEMA(ef78d47ddf3e17d1); +CAPNP_DECLARE_SCHEMA(cc62c859541c8b3b); +CAPNP_DECLARE_SCHEMA(9b0f346ae9dfdf82); +CAPNP_DECLARE_SCHEMA(c4b1b8f64ffdf70f); +CAPNP_DECLARE_SCHEMA(8e1907e9f0be73da); +CAPNP_DECLARE_SCHEMA(a5d956a855c4fb33); +CAPNP_DECLARE_SCHEMA(930c02d5b737646b); +CAPNP_DECLARE_SCHEMA(b2e2ef6bd1f93f4a); + +} // namespace schemas +} // namespace capnp + +namespace mrp { +namespace visualization { + +struct ImageMarker { + ImageMarker() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_CIRCLE = 0u; + static constexpr ::uint8_t K_LINE_STRIP = 1u; + static constexpr ::uint8_t K_LINE_LIST = 2u; + static constexpr ::uint8_t K_POLYGON = 3u; + static constexpr ::uint8_t K_POINTS = 4u; + static constexpr ::uint8_t K_ADD = 0u; + static constexpr ::uint8_t K_REMOVE = 1u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b340cf7c3d62a5e1, 3, 8) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct InteractiveMarker { + InteractiveMarker() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(dab40ba8c922b4ba, 1, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct InteractiveMarkerControl { + InteractiveMarkerControl() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_INHERIT = 0u; + static constexpr ::uint8_t K_FIXED = 1u; + static constexpr ::uint8_t K_VIEW_FACING = 2u; + static constexpr ::uint8_t K_NONE = 0u; + static constexpr ::uint8_t K_MENU = 1u; + static constexpr ::uint8_t K_BUTTON = 2u; + static constexpr ::uint8_t K_MOVE_AXIS = 3u; + static constexpr ::uint8_t K_MOVE_PLANE = 4u; + static constexpr ::uint8_t K_ROTATE_AXIS = 5u; + static constexpr ::uint8_t K_MOVE_ROTATE = 6u; + static constexpr ::uint8_t K_MOVE3_D = 7u; + static constexpr ::uint8_t K_ROTATE3_D = 8u; + static constexpr ::uint8_t K_MOVE_ROTATE3_D = 9u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(b4ad12860007ca93, 1, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct InteractiveMarkerFeedback { + InteractiveMarkerFeedback() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_KEEP_ALIVE = 0u; + static constexpr ::uint8_t K_POSE_UPDATE = 1u; + static constexpr ::uint8_t K_MENU_SELECT = 2u; + static constexpr ::uint8_t K_BUTTON_CLICK = 3u; + static constexpr ::uint8_t K_MOUSE_DOWN = 4u; + static constexpr ::uint8_t K_MOUSE_UP = 5u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8717a25b15e06c03, 1, 6) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct InteractiveMarkerInit { + InteractiveMarkerInit() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(dc53206ad56c678f, 1, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct InteractiveMarkerPose { + InteractiveMarkerPose() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(d56a6cd93315d05a, 0, 3) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct InteractiveMarkerUpdate { + InteractiveMarkerUpdate() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_KEEP_ALIVE = 0u; + static constexpr ::uint8_t K_UPDATE = 1u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(e98e44d10f26c1ad, 2, 4) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct Marker { + Marker() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_ARROW = 0u; + static constexpr ::uint8_t K_CUBE = 1u; + static constexpr ::uint8_t K_SPHERE = 2u; + static constexpr ::uint8_t K_CYLINDER = 3u; + static constexpr ::uint8_t K_LINE_STRIP = 4u; + static constexpr ::uint8_t K_LINE_LIST = 5u; + static constexpr ::uint8_t K_CUBE_LIST = 6u; + static constexpr ::uint8_t K_SPHERE_LIST = 7u; + static constexpr ::uint8_t K_POINTS = 8u; + static constexpr ::uint8_t K_TEXT_VIEW_FACING = 9u; + static constexpr ::uint8_t K_MESH_RESOURCE = 10u; + static constexpr ::uint8_t K_TRIANGLE_LIST = 11u; + static constexpr ::uint8_t K_ADD = 0u; + static constexpr ::uint8_t K_MODIFY = 0u; + static constexpr ::uint8_t K_DELETE = 2u; + static constexpr ::uint8_t K_DELETEALL = 3u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(9ac063ef5a4f120f, 2, 10) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct MarkerArray { + MarkerArray() = delete; + + class Reader; + class Builder; + class Pipeline; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(c4b1b8f64ffdf70f, 0, 1) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +struct MenuEntry { + MenuEntry() = delete; + + class Reader; + class Builder; + class Pipeline; + static constexpr ::uint8_t K_FEEDBACK = 0u; + static constexpr ::uint8_t K_ROSRUN = 1u; + static constexpr ::uint8_t K_ROSLAUNCH = 2u; + + struct _capnpPrivate { + CAPNP_DECLARE_STRUCT_HEADER(8e1907e9f0be73da, 2, 2) + #if !CAPNP_LITE + static constexpr ::capnp::_::RawBrandedSchema const* brand() { return &schema->defaultBrand; } + #endif // !CAPNP_LITE + }; +}; + +// ======================================================================================= + +class ImageMarker::Reader { +public: + typedef ImageMarker Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasNs() const; + inline ::capnp::Text::Reader getNs() const; + + inline ::int32_t getId() const; + + inline ::int32_t getType() const; + + inline ::int32_t getAction() const; + + inline bool hasPosition() const; + inline ::mrp::geometry::Point::Reader getPosition() const; + + inline float getScale() const; + + inline bool hasOutlineColor() const; + inline ::mrp::std::ColorRGBA::Reader getOutlineColor() const; + + inline ::uint8_t getFilled() const; + + inline bool hasFillColor() const; + inline ::mrp::std::ColorRGBA::Reader getFillColor() const; + + inline bool hasLifetime() const; + inline ::mrp::std::Duration::Reader getLifetime() const; + + inline bool hasPoints() const; + inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader getPoints() const; + + inline bool hasOutlineColors() const; + inline ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Reader getOutlineColors() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class ImageMarker::Builder { +public: + typedef ImageMarker Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasNs(); + inline ::capnp::Text::Builder getNs(); + inline void setNs( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initNs(unsigned int size); + inline void adoptNs(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownNs(); + + inline ::int32_t getId(); + inline void setId( ::int32_t value); + + inline ::int32_t getType(); + inline void setType( ::int32_t value); + + inline ::int32_t getAction(); + inline void setAction( ::int32_t value); + + inline bool hasPosition(); + inline ::mrp::geometry::Point::Builder getPosition(); + inline void setPosition( ::mrp::geometry::Point::Reader value); + inline ::mrp::geometry::Point::Builder initPosition(); + inline void adoptPosition(::capnp::Orphan< ::mrp::geometry::Point>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Point> disownPosition(); + + inline float getScale(); + inline void setScale(float value); + + inline bool hasOutlineColor(); + inline ::mrp::std::ColorRGBA::Builder getOutlineColor(); + inline void setOutlineColor( ::mrp::std::ColorRGBA::Reader value); + inline ::mrp::std::ColorRGBA::Builder initOutlineColor(); + inline void adoptOutlineColor(::capnp::Orphan< ::mrp::std::ColorRGBA>&& value); + inline ::capnp::Orphan< ::mrp::std::ColorRGBA> disownOutlineColor(); + + inline ::uint8_t getFilled(); + inline void setFilled( ::uint8_t value); + + inline bool hasFillColor(); + inline ::mrp::std::ColorRGBA::Builder getFillColor(); + inline void setFillColor( ::mrp::std::ColorRGBA::Reader value); + inline ::mrp::std::ColorRGBA::Builder initFillColor(); + inline void adoptFillColor(::capnp::Orphan< ::mrp::std::ColorRGBA>&& value); + inline ::capnp::Orphan< ::mrp::std::ColorRGBA> disownFillColor(); + + inline bool hasLifetime(); + inline ::mrp::std::Duration::Builder getLifetime(); + inline void setLifetime( ::mrp::std::Duration::Reader value); + inline ::mrp::std::Duration::Builder initLifetime(); + inline void adoptLifetime(::capnp::Orphan< ::mrp::std::Duration>&& value); + inline ::capnp::Orphan< ::mrp::std::Duration> disownLifetime(); + + inline bool hasPoints(); + inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder getPoints(); + inline void setPoints( ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder initPoints(unsigned int size); + inline void adoptPoints(::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>> disownPoints(); + + inline bool hasOutlineColors(); + inline ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Builder getOutlineColors(); + inline void setOutlineColors( ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Builder initOutlineColors(unsigned int size); + inline void adoptOutlineColors(::capnp::Orphan< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>> disownOutlineColors(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class ImageMarker::Pipeline { +public: + typedef ImageMarker Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Point::Pipeline getPosition(); + inline ::mrp::std::ColorRGBA::Pipeline getOutlineColor(); + inline ::mrp::std::ColorRGBA::Pipeline getFillColor(); + inline ::mrp::std::Duration::Pipeline getLifetime(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class InteractiveMarker::Reader { +public: + typedef InteractiveMarker Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasPose() const; + inline ::mrp::geometry::Pose::Reader getPose() const; + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline bool hasDescription() const; + inline ::capnp::Text::Reader getDescription() const; + + inline float getScale() const; + + inline bool hasMenuEntries() const; + inline ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>::Reader getMenuEntries() const; + + inline bool hasControls() const; + inline ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>::Reader getControls() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class InteractiveMarker::Builder { +public: + typedef InteractiveMarker Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasPose(); + inline ::mrp::geometry::Pose::Builder getPose(); + inline void setPose( ::mrp::geometry::Pose::Reader value); + inline ::mrp::geometry::Pose::Builder initPose(); + inline void adoptPose(::capnp::Orphan< ::mrp::geometry::Pose>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Pose> disownPose(); + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline bool hasDescription(); + inline ::capnp::Text::Builder getDescription(); + inline void setDescription( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initDescription(unsigned int size); + inline void adoptDescription(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownDescription(); + + inline float getScale(); + inline void setScale(float value); + + inline bool hasMenuEntries(); + inline ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>::Builder getMenuEntries(); + inline void setMenuEntries( ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>::Builder initMenuEntries(unsigned int size); + inline void adoptMenuEntries(::capnp::Orphan< ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>> disownMenuEntries(); + + inline bool hasControls(); + inline ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>::Builder getControls(); + inline void setControls( ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>::Builder initControls(unsigned int size); + inline void adoptControls(::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>> disownControls(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class InteractiveMarker::Pipeline { +public: + typedef InteractiveMarker Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Pose::Pipeline getPose(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class InteractiveMarkerControl::Reader { +public: + typedef InteractiveMarkerControl Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + + inline bool hasOrientation() const; + inline ::mrp::geometry::Quaternion::Reader getOrientation() const; + + inline ::uint8_t getOrientationMode() const; + + inline ::uint8_t getInteractionMode() const; + + inline bool getAlwaysVisible() const; + + inline bool hasMarkers() const; + inline ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Reader getMarkers() const; + + inline bool getIndependentMarkerOrientation() const; + + inline bool hasDescription() const; + inline ::capnp::Text::Reader getDescription() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class InteractiveMarkerControl::Builder { +public: + typedef InteractiveMarkerControl Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + + inline bool hasOrientation(); + inline ::mrp::geometry::Quaternion::Builder getOrientation(); + inline void setOrientation( ::mrp::geometry::Quaternion::Reader value); + inline ::mrp::geometry::Quaternion::Builder initOrientation(); + inline void adoptOrientation(::capnp::Orphan< ::mrp::geometry::Quaternion>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Quaternion> disownOrientation(); + + inline ::uint8_t getOrientationMode(); + inline void setOrientationMode( ::uint8_t value); + + inline ::uint8_t getInteractionMode(); + inline void setInteractionMode( ::uint8_t value); + + inline bool getAlwaysVisible(); + inline void setAlwaysVisible(bool value); + + inline bool hasMarkers(); + inline ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Builder getMarkers(); + inline void setMarkers( ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Builder initMarkers(unsigned int size); + inline void adoptMarkers(::capnp::Orphan< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>> disownMarkers(); + + inline bool getIndependentMarkerOrientation(); + inline void setIndependentMarkerOrientation(bool value); + + inline bool hasDescription(); + inline ::capnp::Text::Builder getDescription(); + inline void setDescription( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initDescription(unsigned int size); + inline void adoptDescription(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownDescription(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class InteractiveMarkerControl::Pipeline { +public: + typedef InteractiveMarkerControl Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::geometry::Quaternion::Pipeline getOrientation(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class InteractiveMarkerFeedback::Reader { +public: + typedef InteractiveMarkerFeedback Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasClientId() const; + inline ::capnp::Text::Reader getClientId() const; + + inline bool hasMarkerName() const; + inline ::capnp::Text::Reader getMarkerName() const; + + inline bool hasControlName() const; + inline ::capnp::Text::Reader getControlName() const; + + inline ::uint8_t getEventType() const; + + inline bool hasPose() const; + inline ::mrp::geometry::Pose::Reader getPose() const; + + inline ::uint32_t getMenuEntryId() const; + + inline bool hasMousePoint() const; + inline ::mrp::geometry::Point::Reader getMousePoint() const; + + inline bool getMousePointValid() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class InteractiveMarkerFeedback::Builder { +public: + typedef InteractiveMarkerFeedback Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasClientId(); + inline ::capnp::Text::Builder getClientId(); + inline void setClientId( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initClientId(unsigned int size); + inline void adoptClientId(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownClientId(); + + inline bool hasMarkerName(); + inline ::capnp::Text::Builder getMarkerName(); + inline void setMarkerName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initMarkerName(unsigned int size); + inline void adoptMarkerName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownMarkerName(); + + inline bool hasControlName(); + inline ::capnp::Text::Builder getControlName(); + inline void setControlName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initControlName(unsigned int size); + inline void adoptControlName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownControlName(); + + inline ::uint8_t getEventType(); + inline void setEventType( ::uint8_t value); + + inline bool hasPose(); + inline ::mrp::geometry::Pose::Builder getPose(); + inline void setPose( ::mrp::geometry::Pose::Reader value); + inline ::mrp::geometry::Pose::Builder initPose(); + inline void adoptPose(::capnp::Orphan< ::mrp::geometry::Pose>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Pose> disownPose(); + + inline ::uint32_t getMenuEntryId(); + inline void setMenuEntryId( ::uint32_t value); + + inline bool hasMousePoint(); + inline ::mrp::geometry::Point::Builder getMousePoint(); + inline void setMousePoint( ::mrp::geometry::Point::Reader value); + inline ::mrp::geometry::Point::Builder initMousePoint(); + inline void adoptMousePoint(::capnp::Orphan< ::mrp::geometry::Point>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Point> disownMousePoint(); + + inline bool getMousePointValid(); + inline void setMousePointValid(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class InteractiveMarkerFeedback::Pipeline { +public: + typedef InteractiveMarkerFeedback Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Pose::Pipeline getPose(); + inline ::mrp::geometry::Point::Pipeline getMousePoint(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class InteractiveMarkerInit::Reader { +public: + typedef InteractiveMarkerInit Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasServerId() const; + inline ::capnp::Text::Reader getServerId() const; + + inline ::uint64_t getSeqNum() const; + + inline bool hasMarkers() const; + inline ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Reader getMarkers() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class InteractiveMarkerInit::Builder { +public: + typedef InteractiveMarkerInit Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasServerId(); + inline ::capnp::Text::Builder getServerId(); + inline void setServerId( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initServerId(unsigned int size); + inline void adoptServerId(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownServerId(); + + inline ::uint64_t getSeqNum(); + inline void setSeqNum( ::uint64_t value); + + inline bool hasMarkers(); + inline ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Builder getMarkers(); + inline void setMarkers( ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Builder initMarkers(unsigned int size); + inline void adoptMarkers(::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>> disownMarkers(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class InteractiveMarkerInit::Pipeline { +public: + typedef InteractiveMarkerInit Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class InteractiveMarkerPose::Reader { +public: + typedef InteractiveMarkerPose Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasPose() const; + inline ::mrp::geometry::Pose::Reader getPose() const; + + inline bool hasName() const; + inline ::capnp::Text::Reader getName() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class InteractiveMarkerPose::Builder { +public: + typedef InteractiveMarkerPose Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasPose(); + inline ::mrp::geometry::Pose::Builder getPose(); + inline void setPose( ::mrp::geometry::Pose::Reader value); + inline ::mrp::geometry::Pose::Builder initPose(); + inline void adoptPose(::capnp::Orphan< ::mrp::geometry::Pose>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Pose> disownPose(); + + inline bool hasName(); + inline ::capnp::Text::Builder getName(); + inline void setName( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initName(unsigned int size); + inline void adoptName(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownName(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class InteractiveMarkerPose::Pipeline { +public: + typedef InteractiveMarkerPose Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Pose::Pipeline getPose(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class InteractiveMarkerUpdate::Reader { +public: + typedef InteractiveMarkerUpdate Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasServerId() const; + inline ::capnp::Text::Reader getServerId() const; + + inline ::uint64_t getSeqNum() const; + + inline ::uint8_t getType() const; + + inline bool hasMarkers() const; + inline ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Reader getMarkers() const; + + inline bool hasPoses() const; + inline ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>::Reader getPoses() const; + + inline bool hasErases() const; + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader getErases() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class InteractiveMarkerUpdate::Builder { +public: + typedef InteractiveMarkerUpdate Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasServerId(); + inline ::capnp::Text::Builder getServerId(); + inline void setServerId( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initServerId(unsigned int size); + inline void adoptServerId(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownServerId(); + + inline ::uint64_t getSeqNum(); + inline void setSeqNum( ::uint64_t value); + + inline ::uint8_t getType(); + inline void setType( ::uint8_t value); + + inline bool hasMarkers(); + inline ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Builder getMarkers(); + inline void setMarkers( ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Builder initMarkers(unsigned int size); + inline void adoptMarkers(::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>> disownMarkers(); + + inline bool hasPoses(); + inline ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>::Builder getPoses(); + inline void setPoses( ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>::Builder initPoses(unsigned int size); + inline void adoptPoses(::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>> disownPoses(); + + inline bool hasErases(); + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder getErases(); + inline void setErases( ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader value); + inline void setErases(::kj::ArrayPtr value); + inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder initErases(unsigned int size); + inline void adoptErases(::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>> disownErases(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class InteractiveMarkerUpdate::Pipeline { +public: + typedef InteractiveMarkerUpdate Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class Marker::Reader { +public: + typedef Marker Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasHeader() const; + inline ::mrp::std::Header::Reader getHeader() const; + + inline bool hasNs() const; + inline ::capnp::Text::Reader getNs() const; + + inline ::int32_t getId() const; + + inline ::int32_t getType() const; + + inline ::int32_t getAction() const; + + inline bool hasPose() const; + inline ::mrp::geometry::Pose::Reader getPose() const; + + inline bool hasScale() const; + inline ::mrp::geometry::Vector3::Reader getScale() const; + + inline bool hasColor() const; + inline ::mrp::std::ColorRGBA::Reader getColor() const; + + inline bool hasLifetime() const; + inline ::mrp::std::Duration::Reader getLifetime() const; + + inline bool getFrameLocked() const; + + inline bool hasPoints() const; + inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader getPoints() const; + + inline bool hasColors() const; + inline ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Reader getColors() const; + + inline bool hasText() const; + inline ::capnp::Text::Reader getText() const; + + inline bool hasMeshResource() const; + inline ::capnp::Text::Reader getMeshResource() const; + + inline bool getMeshUseEmbeddedMaterials() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class Marker::Builder { +public: + typedef Marker Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasHeader(); + inline ::mrp::std::Header::Builder getHeader(); + inline void setHeader( ::mrp::std::Header::Reader value); + inline ::mrp::std::Header::Builder initHeader(); + inline void adoptHeader(::capnp::Orphan< ::mrp::std::Header>&& value); + inline ::capnp::Orphan< ::mrp::std::Header> disownHeader(); + + inline bool hasNs(); + inline ::capnp::Text::Builder getNs(); + inline void setNs( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initNs(unsigned int size); + inline void adoptNs(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownNs(); + + inline ::int32_t getId(); + inline void setId( ::int32_t value); + + inline ::int32_t getType(); + inline void setType( ::int32_t value); + + inline ::int32_t getAction(); + inline void setAction( ::int32_t value); + + inline bool hasPose(); + inline ::mrp::geometry::Pose::Builder getPose(); + inline void setPose( ::mrp::geometry::Pose::Reader value); + inline ::mrp::geometry::Pose::Builder initPose(); + inline void adoptPose(::capnp::Orphan< ::mrp::geometry::Pose>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Pose> disownPose(); + + inline bool hasScale(); + inline ::mrp::geometry::Vector3::Builder getScale(); + inline void setScale( ::mrp::geometry::Vector3::Reader value); + inline ::mrp::geometry::Vector3::Builder initScale(); + inline void adoptScale(::capnp::Orphan< ::mrp::geometry::Vector3>&& value); + inline ::capnp::Orphan< ::mrp::geometry::Vector3> disownScale(); + + inline bool hasColor(); + inline ::mrp::std::ColorRGBA::Builder getColor(); + inline void setColor( ::mrp::std::ColorRGBA::Reader value); + inline ::mrp::std::ColorRGBA::Builder initColor(); + inline void adoptColor(::capnp::Orphan< ::mrp::std::ColorRGBA>&& value); + inline ::capnp::Orphan< ::mrp::std::ColorRGBA> disownColor(); + + inline bool hasLifetime(); + inline ::mrp::std::Duration::Builder getLifetime(); + inline void setLifetime( ::mrp::std::Duration::Reader value); + inline ::mrp::std::Duration::Builder initLifetime(); + inline void adoptLifetime(::capnp::Orphan< ::mrp::std::Duration>&& value); + inline ::capnp::Orphan< ::mrp::std::Duration> disownLifetime(); + + inline bool getFrameLocked(); + inline void setFrameLocked(bool value); + + inline bool hasPoints(); + inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder getPoints(); + inline void setPoints( ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder initPoints(unsigned int size); + inline void adoptPoints(::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>> disownPoints(); + + inline bool hasColors(); + inline ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Builder getColors(); + inline void setColors( ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Builder initColors(unsigned int size); + inline void adoptColors(::capnp::Orphan< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>> disownColors(); + + inline bool hasText(); + inline ::capnp::Text::Builder getText(); + inline void setText( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initText(unsigned int size); + inline void adoptText(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownText(); + + inline bool hasMeshResource(); + inline ::capnp::Text::Builder getMeshResource(); + inline void setMeshResource( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initMeshResource(unsigned int size); + inline void adoptMeshResource(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownMeshResource(); + + inline bool getMeshUseEmbeddedMaterials(); + inline void setMeshUseEmbeddedMaterials(bool value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class Marker::Pipeline { +public: + typedef Marker Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + + inline ::mrp::std::Header::Pipeline getHeader(); + inline ::mrp::geometry::Pose::Pipeline getPose(); + inline ::mrp::geometry::Vector3::Pipeline getScale(); + inline ::mrp::std::ColorRGBA::Pipeline getColor(); + inline ::mrp::std::Duration::Pipeline getLifetime(); +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class MarkerArray::Reader { +public: + typedef MarkerArray Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline bool hasMarkers() const; + inline ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Reader getMarkers() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class MarkerArray::Builder { +public: + typedef MarkerArray Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline bool hasMarkers(); + inline ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Builder getMarkers(); + inline void setMarkers( ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Reader value); + inline ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Builder initMarkers(unsigned int size); + inline void adoptMarkers(::capnp::Orphan< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>&& value); + inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>> disownMarkers(); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class MarkerArray::Pipeline { +public: + typedef MarkerArray Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +class MenuEntry::Reader { +public: + typedef MenuEntry Reads; + + Reader() = default; + inline explicit Reader(::capnp::_::StructReader base): _reader(base) {} + + inline ::capnp::MessageSize totalSize() const { + return _reader.totalSize().asPublic(); + } + +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { + return ::capnp::_::structString(_reader, *_capnpPrivate::brand()); + } +#endif // !CAPNP_LITE + + inline ::uint32_t getId() const; + + inline ::uint32_t getParentId() const; + + inline bool hasTitle() const; + inline ::capnp::Text::Reader getTitle() const; + + inline bool hasCommand() const; + inline ::capnp::Text::Reader getCommand() const; + + inline ::uint8_t getCommandType() const; + +private: + ::capnp::_::StructReader _reader; + template + friend struct ::capnp::ToDynamic_; + template + friend struct ::capnp::_::PointerHelpers; + template + friend struct ::capnp::List; + friend class ::capnp::MessageBuilder; + friend class ::capnp::Orphanage; +}; + +class MenuEntry::Builder { +public: + typedef MenuEntry Builds; + + Builder() = delete; // Deleted to discourage incorrect usage. + // You can explicitly initialize to nullptr instead. + inline Builder(decltype(nullptr)) {} + inline explicit Builder(::capnp::_::StructBuilder base): _builder(base) {} + inline operator Reader() const { return Reader(_builder.asReader()); } + inline Reader asReader() const { return *this; } + + inline ::capnp::MessageSize totalSize() const { return asReader().totalSize(); } +#if !CAPNP_LITE + inline ::kj::StringTree toString() const { return asReader().toString(); } +#endif // !CAPNP_LITE + + inline ::uint32_t getId(); + inline void setId( ::uint32_t value); + + inline ::uint32_t getParentId(); + inline void setParentId( ::uint32_t value); + + inline bool hasTitle(); + inline ::capnp::Text::Builder getTitle(); + inline void setTitle( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initTitle(unsigned int size); + inline void adoptTitle(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownTitle(); + + inline bool hasCommand(); + inline ::capnp::Text::Builder getCommand(); + inline void setCommand( ::capnp::Text::Reader value); + inline ::capnp::Text::Builder initCommand(unsigned int size); + inline void adoptCommand(::capnp::Orphan< ::capnp::Text>&& value); + inline ::capnp::Orphan< ::capnp::Text> disownCommand(); + + inline ::uint8_t getCommandType(); + inline void setCommandType( ::uint8_t value); + +private: + ::capnp::_::StructBuilder _builder; + template + friend struct ::capnp::ToDynamic_; + friend class ::capnp::Orphanage; + template + friend struct ::capnp::_::PointerHelpers; +}; + +#if !CAPNP_LITE +class MenuEntry::Pipeline { +public: + typedef MenuEntry Pipelines; + + inline Pipeline(decltype(nullptr)): _typeless(nullptr) {} + inline explicit Pipeline(::capnp::AnyPointer::Pipeline&& typeless) + : _typeless(kj::mv(typeless)) {} + +private: + ::capnp::AnyPointer::Pipeline _typeless; + friend class ::capnp::PipelineHook; + template + friend struct ::capnp::ToDynamic_; +}; +#endif // !CAPNP_LITE + +// ======================================================================================= + +inline bool ImageMarker::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool ImageMarker::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader ImageMarker::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder ImageMarker::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline ImageMarker::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void ImageMarker::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder ImageMarker::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void ImageMarker::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> ImageMarker::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool ImageMarker::Reader::hasNs() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool ImageMarker::Builder::hasNs() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader ImageMarker::Reader::getNs() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder ImageMarker::Builder::getNs() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void ImageMarker::Builder::setNs( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder ImageMarker::Builder::initNs(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void ImageMarker::Builder::adoptNs( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> ImageMarker::Builder::disownNs() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::int32_t ImageMarker::Reader::getId() const { + return _reader.getDataField< ::int32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::int32_t ImageMarker::Builder::getId() { + return _builder.getDataField< ::int32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void ImageMarker::Builder::setId( ::int32_t value) { + _builder.setDataField< ::int32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::int32_t ImageMarker::Reader::getType() const { + return _reader.getDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::int32_t ImageMarker::Builder::getType() { + return _builder.getDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void ImageMarker::Builder::setType( ::int32_t value) { + _builder.setDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline ::int32_t ImageMarker::Reader::getAction() const { + return _reader.getDataField< ::int32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::int32_t ImageMarker::Builder::getAction() { + return _builder.getDataField< ::int32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void ImageMarker::Builder::setAction( ::int32_t value) { + _builder.setDataField< ::int32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool ImageMarker::Reader::hasPosition() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool ImageMarker::Builder::hasPosition() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Point::Reader ImageMarker::Reader::getPosition() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Point::Builder ImageMarker::Builder::getPosition() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Point::Pipeline ImageMarker::Pipeline::getPosition() { + return ::mrp::geometry::Point::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void ImageMarker::Builder::setPosition( ::mrp::geometry::Point::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Point::Builder ImageMarker::Builder::initPosition() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void ImageMarker::Builder::adoptPosition( + ::capnp::Orphan< ::mrp::geometry::Point>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Point> ImageMarker::Builder::disownPosition() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline float ImageMarker::Reader::getScale() const { + return _reader.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} + +inline float ImageMarker::Builder::getScale() { + return _builder.getDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS); +} +inline void ImageMarker::Builder::setScale(float value) { + _builder.setDataField( + ::capnp::bounded<3>() * ::capnp::ELEMENTS, value); +} + +inline bool ImageMarker::Reader::hasOutlineColor() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool ImageMarker::Builder::hasOutlineColor() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::ColorRGBA::Reader ImageMarker::Reader::getOutlineColor() const { + return ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::mrp::std::ColorRGBA::Builder ImageMarker::Builder::getOutlineColor() { + return ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::ColorRGBA::Pipeline ImageMarker::Pipeline::getOutlineColor() { + return ::mrp::std::ColorRGBA::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void ImageMarker::Builder::setOutlineColor( ::mrp::std::ColorRGBA::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::ColorRGBA::Builder ImageMarker::Builder::initOutlineColor() { + return ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void ImageMarker::Builder::adoptOutlineColor( + ::capnp::Orphan< ::mrp::std::ColorRGBA>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::ColorRGBA> ImageMarker::Builder::disownOutlineColor() { + return ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline ::uint8_t ImageMarker::Reader::getFilled() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<16>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t ImageMarker::Builder::getFilled() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<16>() * ::capnp::ELEMENTS); +} +inline void ImageMarker::Builder::setFilled( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<16>() * ::capnp::ELEMENTS, value); +} + +inline bool ImageMarker::Reader::hasFillColor() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool ImageMarker::Builder::hasFillColor() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::ColorRGBA::Reader ImageMarker::Reader::getFillColor() const { + return ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::mrp::std::ColorRGBA::Builder ImageMarker::Builder::getFillColor() { + return ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::ColorRGBA::Pipeline ImageMarker::Pipeline::getFillColor() { + return ::mrp::std::ColorRGBA::Pipeline(_typeless.getPointerField(4)); +} +#endif // !CAPNP_LITE +inline void ImageMarker::Builder::setFillColor( ::mrp::std::ColorRGBA::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::ColorRGBA::Builder ImageMarker::Builder::initFillColor() { + return ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void ImageMarker::Builder::adoptFillColor( + ::capnp::Orphan< ::mrp::std::ColorRGBA>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::ColorRGBA> ImageMarker::Builder::disownFillColor() { + return ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline bool ImageMarker::Reader::hasLifetime() const { + return !_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline bool ImageMarker::Builder::hasLifetime() { + return !_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Duration::Reader ImageMarker::Reader::getLifetime() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::get(_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Duration::Builder ImageMarker::Builder::getLifetime() { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::get(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Duration::Pipeline ImageMarker::Pipeline::getLifetime() { + return ::mrp::std::Duration::Pipeline(_typeless.getPointerField(5)); +} +#endif // !CAPNP_LITE +inline void ImageMarker::Builder::setLifetime( ::mrp::std::Duration::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Duration>::set(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Duration::Builder ImageMarker::Builder::initLifetime() { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::init(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline void ImageMarker::Builder::adoptLifetime( + ::capnp::Orphan< ::mrp::std::Duration>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Duration>::adopt(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Duration> ImageMarker::Builder::disownLifetime() { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::disown(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} + +inline bool ImageMarker::Reader::hasPoints() const { + return !_reader.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS).isNull(); +} +inline bool ImageMarker::Builder::hasPoints() { + return !_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader ImageMarker::Reader::getPoints() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder ImageMarker::Builder::getPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS)); +} +inline void ImageMarker::Builder::setPoints( ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder ImageMarker::Builder::initPoints(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS), size); +} +inline void ImageMarker::Builder::adoptPoints( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>> ImageMarker::Builder::disownPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS)); +} + +inline bool ImageMarker::Reader::hasOutlineColors() const { + return !_reader.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS).isNull(); +} +inline bool ImageMarker::Builder::hasOutlineColors() { + return !_builder.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Reader ImageMarker::Reader::getOutlineColors() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Builder ImageMarker::Builder::getOutlineColors() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS)); +} +inline void ImageMarker::Builder::setOutlineColors( ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Builder ImageMarker::Builder::initOutlineColors(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS), size); +} +inline void ImageMarker::Builder::adoptOutlineColors( + ::capnp::Orphan< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>> ImageMarker::Builder::disownOutlineColors() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarker::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarker::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader InteractiveMarker::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder InteractiveMarker::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline InteractiveMarker::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void InteractiveMarker::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder InteractiveMarker::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void InteractiveMarker::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> InteractiveMarker::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarker::Reader::hasPose() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarker::Builder::hasPose() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Pose::Reader InteractiveMarker::Reader::getPose() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Pose::Builder InteractiveMarker::Builder::getPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Pose::Pipeline InteractiveMarker::Pipeline::getPose() { + return ::mrp::geometry::Pose::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void InteractiveMarker::Builder::setPose( ::mrp::geometry::Pose::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Pose::Builder InteractiveMarker::Builder::initPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void InteractiveMarker::Builder::adoptPose( + ::capnp::Orphan< ::mrp::geometry::Pose>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Pose> InteractiveMarker::Builder::disownPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarker::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarker::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InteractiveMarker::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InteractiveMarker::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void InteractiveMarker::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InteractiveMarker::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarker::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InteractiveMarker::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarker::Reader::hasDescription() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarker::Builder::hasDescription() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InteractiveMarker::Reader::getDescription() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InteractiveMarker::Builder::getDescription() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void InteractiveMarker::Builder::setDescription( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InteractiveMarker::Builder::initDescription(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarker::Builder::adoptDescription( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InteractiveMarker::Builder::disownDescription() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline float InteractiveMarker::Reader::getScale() const { + return _reader.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline float InteractiveMarker::Builder::getScale() { + return _builder.getDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void InteractiveMarker::Builder::setScale(float value) { + _builder.setDataField( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool InteractiveMarker::Reader::hasMenuEntries() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarker::Builder::hasMenuEntries() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>::Reader InteractiveMarker::Reader::getMenuEntries() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>::Builder InteractiveMarker::Builder::getMenuEntries() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void InteractiveMarker::Builder::setMenuEntries( ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>::Builder InteractiveMarker::Builder::initMenuEntries(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarker::Builder::adoptMenuEntries( + ::capnp::Orphan< ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>> InteractiveMarker::Builder::disownMenuEntries() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::MenuEntry, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarker::Reader::hasControls() const { + return !_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarker::Builder::hasControls() { + return !_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>::Reader InteractiveMarker::Reader::getControls() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>::Builder InteractiveMarker::Builder::getControls() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline void InteractiveMarker::Builder::setControls( ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>::Builder InteractiveMarker::Builder::initControls(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarker::Builder::adoptControls( + ::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>> InteractiveMarker::Builder::disownControls() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarkerControl, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerControl::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerControl::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InteractiveMarkerControl::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InteractiveMarkerControl::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerControl::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InteractiveMarkerControl::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarkerControl::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InteractiveMarkerControl::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerControl::Reader::hasOrientation() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerControl::Builder::hasOrientation() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Quaternion::Reader InteractiveMarkerControl::Reader::getOrientation() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Quaternion::Builder InteractiveMarkerControl::Builder::getOrientation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Quaternion::Pipeline InteractiveMarkerControl::Pipeline::getOrientation() { + return ::mrp::geometry::Quaternion::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void InteractiveMarkerControl::Builder::setOrientation( ::mrp::geometry::Quaternion::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Quaternion::Builder InteractiveMarkerControl::Builder::initOrientation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerControl::Builder::adoptOrientation( + ::capnp::Orphan< ::mrp::geometry::Quaternion>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Quaternion> InteractiveMarkerControl::Builder::disownOrientation() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Quaternion>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::uint8_t InteractiveMarkerControl::Reader::getOrientationMode() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t InteractiveMarkerControl::Builder::getOrientationMode() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void InteractiveMarkerControl::Builder::setOrientationMode( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t InteractiveMarkerControl::Reader::getInteractionMode() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t InteractiveMarkerControl::Builder::getInteractionMode() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void InteractiveMarkerControl::Builder::setInteractionMode( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool InteractiveMarkerControl::Reader::getAlwaysVisible() const { + return _reader.getDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS); +} + +inline bool InteractiveMarkerControl::Builder::getAlwaysVisible() { + return _builder.getDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS); +} +inline void InteractiveMarkerControl::Builder::setAlwaysVisible(bool value) { + _builder.setDataField( + ::capnp::bounded<16>() * ::capnp::ELEMENTS, value); +} + +inline bool InteractiveMarkerControl::Reader::hasMarkers() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerControl::Builder::hasMarkers() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Reader InteractiveMarkerControl::Reader::getMarkers() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Builder InteractiveMarkerControl::Builder::getMarkers() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerControl::Builder::setMarkers( ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Builder InteractiveMarkerControl::Builder::initMarkers(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarkerControl::Builder::adoptMarkers( + ::capnp::Orphan< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>> InteractiveMarkerControl::Builder::disownMarkers() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerControl::Reader::getIndependentMarkerOrientation() const { + return _reader.getDataField( + ::capnp::bounded<17>() * ::capnp::ELEMENTS); +} + +inline bool InteractiveMarkerControl::Builder::getIndependentMarkerOrientation() { + return _builder.getDataField( + ::capnp::bounded<17>() * ::capnp::ELEMENTS); +} +inline void InteractiveMarkerControl::Builder::setIndependentMarkerOrientation(bool value) { + _builder.setDataField( + ::capnp::bounded<17>() * ::capnp::ELEMENTS, value); +} + +inline bool InteractiveMarkerControl::Reader::hasDescription() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerControl::Builder::hasDescription() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InteractiveMarkerControl::Reader::getDescription() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InteractiveMarkerControl::Builder::getDescription() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerControl::Builder::setDescription( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InteractiveMarkerControl::Builder::initDescription(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarkerControl::Builder::adoptDescription( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InteractiveMarkerControl::Builder::disownDescription() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerFeedback::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerFeedback::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader InteractiveMarkerFeedback::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder InteractiveMarkerFeedback::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline InteractiveMarkerFeedback::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void InteractiveMarkerFeedback::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder InteractiveMarkerFeedback::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerFeedback::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> InteractiveMarkerFeedback::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerFeedback::Reader::hasClientId() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerFeedback::Builder::hasClientId() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InteractiveMarkerFeedback::Reader::getClientId() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InteractiveMarkerFeedback::Builder::getClientId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerFeedback::Builder::setClientId( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InteractiveMarkerFeedback::Builder::initClientId(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarkerFeedback::Builder::adoptClientId( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InteractiveMarkerFeedback::Builder::disownClientId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerFeedback::Reader::hasMarkerName() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerFeedback::Builder::hasMarkerName() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InteractiveMarkerFeedback::Reader::getMarkerName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InteractiveMarkerFeedback::Builder::getMarkerName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerFeedback::Builder::setMarkerName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InteractiveMarkerFeedback::Builder::initMarkerName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarkerFeedback::Builder::adoptMarkerName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InteractiveMarkerFeedback::Builder::disownMarkerName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerFeedback::Reader::hasControlName() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerFeedback::Builder::hasControlName() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InteractiveMarkerFeedback::Reader::getControlName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InteractiveMarkerFeedback::Builder::getControlName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerFeedback::Builder::setControlName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InteractiveMarkerFeedback::Builder::initControlName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarkerFeedback::Builder::adoptControlName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InteractiveMarkerFeedback::Builder::disownControlName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline ::uint8_t InteractiveMarkerFeedback::Reader::getEventType() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t InteractiveMarkerFeedback::Builder::getEventType() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void InteractiveMarkerFeedback::Builder::setEventType( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool InteractiveMarkerFeedback::Reader::hasPose() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerFeedback::Builder::hasPose() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Pose::Reader InteractiveMarkerFeedback::Reader::getPose() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Pose::Builder InteractiveMarkerFeedback::Builder::getPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Pose::Pipeline InteractiveMarkerFeedback::Pipeline::getPose() { + return ::mrp::geometry::Pose::Pipeline(_typeless.getPointerField(4)); +} +#endif // !CAPNP_LITE +inline void InteractiveMarkerFeedback::Builder::setPose( ::mrp::geometry::Pose::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Pose::Builder InteractiveMarkerFeedback::Builder::initPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerFeedback::Builder::adoptPose( + ::capnp::Orphan< ::mrp::geometry::Pose>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Pose> InteractiveMarkerFeedback::Builder::disownPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline ::uint32_t InteractiveMarkerFeedback::Reader::getMenuEntryId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t InteractiveMarkerFeedback::Builder::getMenuEntryId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void InteractiveMarkerFeedback::Builder::setMenuEntryId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool InteractiveMarkerFeedback::Reader::hasMousePoint() const { + return !_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerFeedback::Builder::hasMousePoint() { + return !_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Point::Reader InteractiveMarkerFeedback::Reader::getMousePoint() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::get(_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Point::Builder InteractiveMarkerFeedback::Builder::getMousePoint() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::get(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Point::Pipeline InteractiveMarkerFeedback::Pipeline::getMousePoint() { + return ::mrp::geometry::Point::Pipeline(_typeless.getPointerField(5)); +} +#endif // !CAPNP_LITE +inline void InteractiveMarkerFeedback::Builder::setMousePoint( ::mrp::geometry::Point::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::set(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Point::Builder InteractiveMarkerFeedback::Builder::initMousePoint() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::init(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerFeedback::Builder::adoptMousePoint( + ::capnp::Orphan< ::mrp::geometry::Point>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::adopt(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Point> InteractiveMarkerFeedback::Builder::disownMousePoint() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Point>::disown(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerFeedback::Reader::getMousePointValid() const { + return _reader.getDataField( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} + +inline bool InteractiveMarkerFeedback::Builder::getMousePointValid() { + return _builder.getDataField( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} +inline void InteractiveMarkerFeedback::Builder::setMousePointValid(bool value) { + _builder.setDataField( + ::capnp::bounded<8>() * ::capnp::ELEMENTS, value); +} + +inline bool InteractiveMarkerInit::Reader::hasServerId() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerInit::Builder::hasServerId() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InteractiveMarkerInit::Reader::getServerId() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InteractiveMarkerInit::Builder::getServerId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerInit::Builder::setServerId( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InteractiveMarkerInit::Builder::initServerId(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarkerInit::Builder::adoptServerId( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InteractiveMarkerInit::Builder::disownServerId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint64_t InteractiveMarkerInit::Reader::getSeqNum() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t InteractiveMarkerInit::Builder::getSeqNum() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void InteractiveMarkerInit::Builder::setSeqNum( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline bool InteractiveMarkerInit::Reader::hasMarkers() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerInit::Builder::hasMarkers() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Reader InteractiveMarkerInit::Reader::getMarkers() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Builder InteractiveMarkerInit::Builder::getMarkers() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerInit::Builder::setMarkers( ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Builder InteractiveMarkerInit::Builder::initMarkers(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarkerInit::Builder::adoptMarkers( + ::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>> InteractiveMarkerInit::Builder::disownMarkers() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerPose::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerPose::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader InteractiveMarkerPose::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder InteractiveMarkerPose::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline InteractiveMarkerPose::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void InteractiveMarkerPose::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder InteractiveMarkerPose::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerPose::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> InteractiveMarkerPose::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerPose::Reader::hasPose() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerPose::Builder::hasPose() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Pose::Reader InteractiveMarkerPose::Reader::getPose() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Pose::Builder InteractiveMarkerPose::Builder::getPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Pose::Pipeline InteractiveMarkerPose::Pipeline::getPose() { + return ::mrp::geometry::Pose::Pipeline(_typeless.getPointerField(1)); +} +#endif // !CAPNP_LITE +inline void InteractiveMarkerPose::Builder::setPose( ::mrp::geometry::Pose::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Pose::Builder InteractiveMarkerPose::Builder::initPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerPose::Builder::adoptPose( + ::capnp::Orphan< ::mrp::geometry::Pose>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Pose> InteractiveMarkerPose::Builder::disownPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerPose::Reader::hasName() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerPose::Builder::hasName() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InteractiveMarkerPose::Reader::getName() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InteractiveMarkerPose::Builder::getName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerPose::Builder::setName( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InteractiveMarkerPose::Builder::initName(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarkerPose::Builder::adoptName( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InteractiveMarkerPose::Builder::disownName() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerUpdate::Reader::hasServerId() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerUpdate::Builder::hasServerId() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader InteractiveMarkerUpdate::Reader::getServerId() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder InteractiveMarkerUpdate::Builder::getServerId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerUpdate::Builder::setServerId( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder InteractiveMarkerUpdate::Builder::initServerId(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarkerUpdate::Builder::adoptServerId( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> InteractiveMarkerUpdate::Builder::disownServerId() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint64_t InteractiveMarkerUpdate::Reader::getSeqNum() const { + return _reader.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint64_t InteractiveMarkerUpdate::Builder::getSeqNum() { + return _builder.getDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void InteractiveMarkerUpdate::Builder::setSeqNum( ::uint64_t value) { + _builder.setDataField< ::uint64_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint8_t InteractiveMarkerUpdate::Reader::getType() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t InteractiveMarkerUpdate::Builder::getType() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} +inline void InteractiveMarkerUpdate::Builder::setType( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS, value); +} + +inline bool InteractiveMarkerUpdate::Reader::hasMarkers() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerUpdate::Builder::hasMarkers() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Reader InteractiveMarkerUpdate::Reader::getMarkers() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Builder InteractiveMarkerUpdate::Builder::getMarkers() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerUpdate::Builder::setMarkers( ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>::Builder InteractiveMarkerUpdate::Builder::initMarkers(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarkerUpdate::Builder::adoptMarkers( + ::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>> InteractiveMarkerUpdate::Builder::disownMarkers() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarker, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerUpdate::Reader::hasPoses() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerUpdate::Builder::hasPoses() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>::Reader InteractiveMarkerUpdate::Reader::getPoses() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>::Builder InteractiveMarkerUpdate::Builder::getPoses() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerUpdate::Builder::setPoses( ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>::Builder InteractiveMarkerUpdate::Builder::initPoses(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarkerUpdate::Builder::adoptPoses( + ::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>> InteractiveMarkerUpdate::Builder::disownPoses() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::InteractiveMarkerPose, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool InteractiveMarkerUpdate::Reader::hasErases() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool InteractiveMarkerUpdate::Builder::hasErases() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader InteractiveMarkerUpdate::Reader::getErases() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder InteractiveMarkerUpdate::Builder::getErases() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void InteractiveMarkerUpdate::Builder::setErases( ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline void InteractiveMarkerUpdate::Builder::setErases(::kj::ArrayPtr value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>::Builder InteractiveMarkerUpdate::Builder::initErases(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), size); +} +inline void InteractiveMarkerUpdate::Builder::adoptErases( + ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>> InteractiveMarkerUpdate::Builder::disownErases() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::capnp::Text, ::capnp::Kind::BLOB>>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Marker::Reader::hasHeader() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool Marker::Builder::hasHeader() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Header::Reader Marker::Reader::getHeader() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Header::Builder Marker::Builder::getHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Header::Pipeline Marker::Pipeline::getHeader() { + return ::mrp::std::Header::Pipeline(_typeless.getPointerField(0)); +} +#endif // !CAPNP_LITE +inline void Marker::Builder::setHeader( ::mrp::std::Header::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Header::Builder Marker::Builder::initHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void Marker::Builder::adoptHeader( + ::capnp::Orphan< ::mrp::std::Header>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Header>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Header> Marker::Builder::disownHeader() { + return ::capnp::_::PointerHelpers< ::mrp::std::Header>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool Marker::Reader::hasNs() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool Marker::Builder::hasNs() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Marker::Reader::getNs() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Marker::Builder::getNs() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void Marker::Builder::setNs( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Marker::Builder::initNs(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void Marker::Builder::adoptNs( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Marker::Builder::disownNs() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::int32_t Marker::Reader::getId() const { + return _reader.getDataField< ::int32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::int32_t Marker::Builder::getId() { + return _builder.getDataField< ::int32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void Marker::Builder::setId( ::int32_t value) { + _builder.setDataField< ::int32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::int32_t Marker::Reader::getType() const { + return _reader.getDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::int32_t Marker::Builder::getType() { + return _builder.getDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void Marker::Builder::setType( ::int32_t value) { + _builder.setDataField< ::int32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline ::int32_t Marker::Reader::getAction() const { + return _reader.getDataField< ::int32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} + +inline ::int32_t Marker::Builder::getAction() { + return _builder.getDataField< ::int32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS); +} +inline void Marker::Builder::setAction( ::int32_t value) { + _builder.setDataField< ::int32_t>( + ::capnp::bounded<2>() * ::capnp::ELEMENTS, value); +} + +inline bool Marker::Reader::hasPose() const { + return !_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline bool Marker::Builder::hasPose() { + return !_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Pose::Reader Marker::Reader::getPose() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_reader.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Pose::Builder Marker::Builder::getPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::get(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Pose::Pipeline Marker::Pipeline::getPose() { + return ::mrp::geometry::Pose::Pipeline(_typeless.getPointerField(2)); +} +#endif // !CAPNP_LITE +inline void Marker::Builder::setPose( ::mrp::geometry::Pose::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::set(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Pose::Builder Marker::Builder::initPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::init(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} +inline void Marker::Builder::adoptPose( + ::capnp::Orphan< ::mrp::geometry::Pose>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::adopt(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Pose> Marker::Builder::disownPose() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Pose>::disown(_builder.getPointerField( + ::capnp::bounded<2>() * ::capnp::POINTERS)); +} + +inline bool Marker::Reader::hasScale() const { + return !_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline bool Marker::Builder::hasScale() { + return !_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::geometry::Vector3::Reader Marker::Reader::getScale() const { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_reader.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline ::mrp::geometry::Vector3::Builder Marker::Builder::getScale() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::get(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::geometry::Vector3::Pipeline Marker::Pipeline::getScale() { + return ::mrp::geometry::Vector3::Pipeline(_typeless.getPointerField(3)); +} +#endif // !CAPNP_LITE +inline void Marker::Builder::setScale( ::mrp::geometry::Vector3::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::set(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), value); +} +inline ::mrp::geometry::Vector3::Builder Marker::Builder::initScale() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::init(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} +inline void Marker::Builder::adoptScale( + ::capnp::Orphan< ::mrp::geometry::Vector3>&& value) { + ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::adopt(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::geometry::Vector3> Marker::Builder::disownScale() { + return ::capnp::_::PointerHelpers< ::mrp::geometry::Vector3>::disown(_builder.getPointerField( + ::capnp::bounded<3>() * ::capnp::POINTERS)); +} + +inline bool Marker::Reader::hasColor() const { + return !_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline bool Marker::Builder::hasColor() { + return !_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::ColorRGBA::Reader Marker::Reader::getColor() const { + return ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::get(_reader.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline ::mrp::std::ColorRGBA::Builder Marker::Builder::getColor() { + return ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::get(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::ColorRGBA::Pipeline Marker::Pipeline::getColor() { + return ::mrp::std::ColorRGBA::Pipeline(_typeless.getPointerField(4)); +} +#endif // !CAPNP_LITE +inline void Marker::Builder::setColor( ::mrp::std::ColorRGBA::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::set(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::ColorRGBA::Builder Marker::Builder::initColor() { + return ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::init(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} +inline void Marker::Builder::adoptColor( + ::capnp::Orphan< ::mrp::std::ColorRGBA>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::adopt(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::ColorRGBA> Marker::Builder::disownColor() { + return ::capnp::_::PointerHelpers< ::mrp::std::ColorRGBA>::disown(_builder.getPointerField( + ::capnp::bounded<4>() * ::capnp::POINTERS)); +} + +inline bool Marker::Reader::hasLifetime() const { + return !_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline bool Marker::Builder::hasLifetime() { + return !_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS).isNull(); +} +inline ::mrp::std::Duration::Reader Marker::Reader::getLifetime() const { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::get(_reader.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline ::mrp::std::Duration::Builder Marker::Builder::getLifetime() { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::get(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +#if !CAPNP_LITE +inline ::mrp::std::Duration::Pipeline Marker::Pipeline::getLifetime() { + return ::mrp::std::Duration::Pipeline(_typeless.getPointerField(5)); +} +#endif // !CAPNP_LITE +inline void Marker::Builder::setLifetime( ::mrp::std::Duration::Reader value) { + ::capnp::_::PointerHelpers< ::mrp::std::Duration>::set(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), value); +} +inline ::mrp::std::Duration::Builder Marker::Builder::initLifetime() { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::init(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} +inline void Marker::Builder::adoptLifetime( + ::capnp::Orphan< ::mrp::std::Duration>&& value) { + ::capnp::_::PointerHelpers< ::mrp::std::Duration>::adopt(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::mrp::std::Duration> Marker::Builder::disownLifetime() { + return ::capnp::_::PointerHelpers< ::mrp::std::Duration>::disown(_builder.getPointerField( + ::capnp::bounded<5>() * ::capnp::POINTERS)); +} + +inline bool Marker::Reader::getFrameLocked() const { + return _reader.getDataField( + ::capnp::bounded<96>() * ::capnp::ELEMENTS); +} + +inline bool Marker::Builder::getFrameLocked() { + return _builder.getDataField( + ::capnp::bounded<96>() * ::capnp::ELEMENTS); +} +inline void Marker::Builder::setFrameLocked(bool value) { + _builder.setDataField( + ::capnp::bounded<96>() * ::capnp::ELEMENTS, value); +} + +inline bool Marker::Reader::hasPoints() const { + return !_reader.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS).isNull(); +} +inline bool Marker::Builder::hasPoints() { + return !_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader Marker::Reader::getPoints() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder Marker::Builder::getPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS)); +} +inline void Marker::Builder::setPoints( ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>::Builder Marker::Builder::initPoints(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS), size); +} +inline void Marker::Builder::adoptPoints( + ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>> Marker::Builder::disownPoints() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::geometry::Point, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<6>() * ::capnp::POINTERS)); +} + +inline bool Marker::Reader::hasColors() const { + return !_reader.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS).isNull(); +} +inline bool Marker::Builder::hasColors() { + return !_builder.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Reader Marker::Reader::getColors() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Builder Marker::Builder::getColors() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS)); +} +inline void Marker::Builder::setColors( ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>::Builder Marker::Builder::initColors(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS), size); +} +inline void Marker::Builder::adoptColors( + ::capnp::Orphan< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>> Marker::Builder::disownColors() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::std::ColorRGBA, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<7>() * ::capnp::POINTERS)); +} + +inline bool Marker::Reader::hasText() const { + return !_reader.getPointerField( + ::capnp::bounded<8>() * ::capnp::POINTERS).isNull(); +} +inline bool Marker::Builder::hasText() { + return !_builder.getPointerField( + ::capnp::bounded<8>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Marker::Reader::getText() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<8>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Marker::Builder::getText() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<8>() * ::capnp::POINTERS)); +} +inline void Marker::Builder::setText( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<8>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Marker::Builder::initText(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<8>() * ::capnp::POINTERS), size); +} +inline void Marker::Builder::adoptText( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<8>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Marker::Builder::disownText() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<8>() * ::capnp::POINTERS)); +} + +inline bool Marker::Reader::hasMeshResource() const { + return !_reader.getPointerField( + ::capnp::bounded<9>() * ::capnp::POINTERS).isNull(); +} +inline bool Marker::Builder::hasMeshResource() { + return !_builder.getPointerField( + ::capnp::bounded<9>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader Marker::Reader::getMeshResource() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<9>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder Marker::Builder::getMeshResource() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<9>() * ::capnp::POINTERS)); +} +inline void Marker::Builder::setMeshResource( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<9>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder Marker::Builder::initMeshResource(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<9>() * ::capnp::POINTERS), size); +} +inline void Marker::Builder::adoptMeshResource( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<9>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> Marker::Builder::disownMeshResource() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<9>() * ::capnp::POINTERS)); +} + +inline bool Marker::Reader::getMeshUseEmbeddedMaterials() const { + return _reader.getDataField( + ::capnp::bounded<97>() * ::capnp::ELEMENTS); +} + +inline bool Marker::Builder::getMeshUseEmbeddedMaterials() { + return _builder.getDataField( + ::capnp::bounded<97>() * ::capnp::ELEMENTS); +} +inline void Marker::Builder::setMeshUseEmbeddedMaterials(bool value) { + _builder.setDataField( + ::capnp::bounded<97>() * ::capnp::ELEMENTS, value); +} + +inline bool MarkerArray::Reader::hasMarkers() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool MarkerArray::Builder::hasMarkers() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Reader MarkerArray::Reader::getMarkers() const { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Builder MarkerArray::Builder::getMarkers() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MarkerArray::Builder::setMarkers( ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>::Builder MarkerArray::Builder::initMarkers(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void MarkerArray::Builder::adoptMarkers( + ::capnp::Orphan< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>&& value) { + ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>> MarkerArray::Builder::disownMarkers() { + return ::capnp::_::PointerHelpers< ::capnp::List< ::mrp::visualization::Marker, ::capnp::Kind::STRUCT>>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline ::uint32_t MenuEntry::Reader::getId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t MenuEntry::Builder::getId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS); +} +inline void MenuEntry::Builder::setId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<0>() * ::capnp::ELEMENTS, value); +} + +inline ::uint32_t MenuEntry::Reader::getParentId() const { + return _reader.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} + +inline ::uint32_t MenuEntry::Builder::getParentId() { + return _builder.getDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS); +} +inline void MenuEntry::Builder::setParentId( ::uint32_t value) { + _builder.setDataField< ::uint32_t>( + ::capnp::bounded<1>() * ::capnp::ELEMENTS, value); +} + +inline bool MenuEntry::Reader::hasTitle() const { + return !_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline bool MenuEntry::Builder::hasTitle() { + return !_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader MenuEntry::Reader::getTitle() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder MenuEntry::Builder::getTitle() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} +inline void MenuEntry::Builder::setTitle( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder MenuEntry::Builder::initTitle(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), size); +} +inline void MenuEntry::Builder::adoptTitle( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> MenuEntry::Builder::disownTitle() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<0>() * ::capnp::POINTERS)); +} + +inline bool MenuEntry::Reader::hasCommand() const { + return !_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline bool MenuEntry::Builder::hasCommand() { + return !_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS).isNull(); +} +inline ::capnp::Text::Reader MenuEntry::Reader::getCommand() const { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_reader.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline ::capnp::Text::Builder MenuEntry::Builder::getCommand() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::get(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} +inline void MenuEntry::Builder::setCommand( ::capnp::Text::Reader value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::set(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), value); +} +inline ::capnp::Text::Builder MenuEntry::Builder::initCommand(unsigned int size) { + return ::capnp::_::PointerHelpers< ::capnp::Text>::init(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), size); +} +inline void MenuEntry::Builder::adoptCommand( + ::capnp::Orphan< ::capnp::Text>&& value) { + ::capnp::_::PointerHelpers< ::capnp::Text>::adopt(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS), kj::mv(value)); +} +inline ::capnp::Orphan< ::capnp::Text> MenuEntry::Builder::disownCommand() { + return ::capnp::_::PointerHelpers< ::capnp::Text>::disown(_builder.getPointerField( + ::capnp::bounded<1>() * ::capnp::POINTERS)); +} + +inline ::uint8_t MenuEntry::Reader::getCommandType() const { + return _reader.getDataField< ::uint8_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} + +inline ::uint8_t MenuEntry::Builder::getCommandType() { + return _builder.getDataField< ::uint8_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS); +} +inline void MenuEntry::Builder::setCommandType( ::uint8_t value) { + _builder.setDataField< ::uint8_t>( + ::capnp::bounded<8>() * ::capnp::ELEMENTS, value); +} + +} // namespace +} // namespace + +CAPNP_END_HEADER + diff --git a/msg/src/fairomsg/def/actionlib_msgs.capnp b/msg/src/fairomsg/def/actionlib_msgs.capnp new file mode 100644 index 0000000000..0f707ebeac --- /dev/null +++ b/msg/src/fairomsg/def/actionlib_msgs.capnp @@ -0,0 +1,28 @@ +@0xc7ead4e7826cfc1a; +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("mrp::actionlib"); +using Header = import "std_msgs.capnp".Header; +using Time = import "std_msgs.capnp".Time; +struct GoalID { + stamp @0 :Time; + id @1 :Text; +} +struct GoalStatus { + goalId @0 :GoalID; + status @1 :UInt8; + const kPending :UInt8 = 0; + const kActive :UInt8 = 1; + const kPreempted :UInt8 = 2; + const kSucceeded :UInt8 = 3; + const kAborted :UInt8 = 4; + const kRejected :UInt8 = 5; + const kPreempting :UInt8 = 6; + const kRecalling :UInt8 = 7; + const kRecalled :UInt8 = 8; + const kLost :UInt8 = 9; + text @2 :Text; +} +struct GoalStatusArray { + header @0 :Header; + statusList @1 :List(GoalStatus); +} diff --git a/msg/src/fairomsg/def/diagnostic_msgs.capnp b/msg/src/fairomsg/def/diagnostic_msgs.capnp new file mode 100644 index 0000000000..9808e51580 --- /dev/null +++ b/msg/src/fairomsg/def/diagnostic_msgs.capnp @@ -0,0 +1,23 @@ +@0xf072c9baec2e3f22; +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("mrp::diagnostic"); +using Header = import "std_msgs.capnp".Header; +struct DiagnosticStatus { + const kOk :UInt8 = 0; + const kWarn :UInt8 = 1; + const kError :UInt8 = 2; + const kStale :UInt8 = 3; + level @0 :UInt8; + name @1 :Text; + message @2 :Text; + hardwareId @3 :Text; + values @4 :List(KeyValue); +} +struct DiagnosticArray { + header @0 :Header; + status @1 :List(DiagnosticStatus); +} +struct KeyValue { + key @0 :Text; + value @1 :Text; +} diff --git a/msg/src/fairomsg/def/geometry_msgs.capnp b/msg/src/fairomsg/def/geometry_msgs.capnp new file mode 100644 index 0000000000..b738090d59 --- /dev/null +++ b/msg/src/fairomsg/def/geometry_msgs.capnp @@ -0,0 +1,132 @@ +@0xd639476cdeb42f7a; +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("mrp::geometry"); +using Header = import "std_msgs.capnp".Header; +struct PoseStamped { + header @0 :Header; + pose @1 :Pose; +} +struct InertiaStamped { + header @0 :Header; + inertia @1 :Inertia; +} +struct Twist { + linear @0 :Vector3; + angular @1 :Vector3; +} +struct Vector3Stamped { + header @0 :Header; + vector @1 :Vector3; +} +struct Vector3 { + x @0 :Float64; + y @1 :Float64; + z @2 :Float64; +} +struct PoseWithCovarianceStamped { + header @0 :Header; + pose @1 :PoseWithCovariance; +} +struct Inertia { + m @0 :Float64; + com @1 :Vector3; + ixx @2 :Float64; + ixy @3 :Float64; + ixz @4 :Float64; + iyy @5 :Float64; + iyz @6 :Float64; + izz @7 :Float64; +} +struct Polygon { + points @0 :List(Point32); +} +struct Pose2D { + x @0 :Float64; + y @1 :Float64; + theta @2 :Float64; +} +struct Point32 { + x @0 :Float32; + y @1 :Float32; + z @2 :Float32; +} +struct PolygonStamped { + header @0 :Header; + polygon @1 :Polygon; +} +struct QuaternionStamped { + header @0 :Header; + quaternion @1 :Quaternion; +} +struct AccelWithCovariance { + accel @0 :Accel; + covariance @1 :List(Float64); +} +struct TwistStamped { + header @0 :Header; + twist @1 :Twist; +} +struct Quaternion { + x @0 :Float64; + y @1 :Float64; + z @2 :Float64; + w @3 :Float64; +} +struct PoseWithCovariance { + pose @0 :Pose; + covariance @1 :List(Float64); +} +struct PointStamped { + header @0 :Header; + point @1 :Point; +} +struct TwistWithCovariance { + twist @0 :Twist; + covariance @1 :List(Float64); +} +struct Accel { + linear @0 :Vector3; + angular @1 :Vector3; +} +struct TwistWithCovarianceStamped { + header @0 :Header; + twist @1 :TwistWithCovariance; +} +struct Transform { + translation @0 :Vector3; + rotation @1 :Quaternion; +} +struct AccelStamped { + header @0 :Header; + accel @1 :Accel; +} +struct Wrench { + force @0 :Vector3; + torque @1 :Vector3; +} +struct AccelWithCovarianceStamped { + header @0 :Header; + accel @1 :AccelWithCovariance; +} +struct TransformStamped { + header @0 :Header; + childFrameId @1 :Text; + transform @2 :Transform; +} +struct PoseArray { + header @0 :Header; + poses @1 :List(Pose); +} +struct Point { + x @0 :Float64; + y @1 :Float64; + z @2 :Float64; +} +struct WrenchStamped { + header @0 :Header; + wrench @1 :Wrench; +} +struct Pose { + position @0 :Point; + orientation @1 :Quaternion; +} diff --git a/msg/src/fairomsg/def/nav_msgs.capnp b/msg/src/fairomsg/def/nav_msgs.capnp new file mode 100644 index 0000000000..865d20b0c8 --- /dev/null +++ b/msg/src/fairomsg/def/nav_msgs.capnp @@ -0,0 +1,67 @@ +@0x8e1824e69341e9dd; +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("mrp::nav"); +using GoalID = import "actionlib_msgs.capnp".GoalID; +using GoalStatus = import "actionlib_msgs.capnp".GoalStatus; +using Header = import "std_msgs.capnp".Header; +using Point = import "geometry_msgs.capnp".Point; +using Pose = import "geometry_msgs.capnp".Pose; +using PoseStamped = import "geometry_msgs.capnp".PoseStamped; +using PoseWithCovariance = import "geometry_msgs.capnp".PoseWithCovariance; +using Time = import "std_msgs.capnp".Time; +using TwistWithCovariance = import "geometry_msgs.capnp".TwistWithCovariance; +struct Path { + header @0 :Header; + poses @1 :List(PoseStamped); +} +struct OccupancyGrid { + header @0 :Header; + info @1 :MapMetaData; + data @2 :Data; +} +struct GetMapGoal { +} +struct GetMapActionResult { + header @0 :Header; + status @1 :GoalStatus; + result @2 :GetMapResult; +} +struct GetMapFeedback { +} +struct GridCells { + header @0 :Header; + cellWidth @1 :Float32; + cellHeight @2 :Float32; + cells @3 :List(Point); +} +struct GetMapResult { + map @0 :OccupancyGrid; +} +struct MapMetaData { + mapLoadTime @0 :Time; + resolution @1 :Float32; + width @2 :UInt32; + height @3 :UInt32; + origin @4 :Pose; +} +struct Odometry { + header @0 :Header; + childFrameId @1 :Text; + pose @2 :PoseWithCovariance; + twist @3 :TwistWithCovariance; +} +struct GetMapActionGoal { + header @0 :Header; + goalId @1 :GoalID; + goal @2 :GetMapGoal; +} +struct GetMapActionFeedback { + header @0 :Header; + status @1 :GoalStatus; + feedback @2 :GetMapFeedback; +} +struct GetMapAction { + actionGoal @0 :GetMapActionGoal; + actionResult @1 :GetMapActionResult; + actionFeedback @2 :GetMapActionFeedback; +} diff --git a/msg/src/fairomsg/def/sensor_msgs.capnp b/msg/src/fairomsg/def/sensor_msgs.capnp new file mode 100644 index 0000000000..96692a96ea --- /dev/null +++ b/msg/src/fairomsg/def/sensor_msgs.capnp @@ -0,0 +1,249 @@ +@0xb42d13c7a02429e5; +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("mrp::sensor"); +using Header = import "std_msgs.capnp".Header; +using Point32 = import "geometry_msgs.capnp".Point32; +using Quaternion = import "geometry_msgs.capnp".Quaternion; +using Time = import "std_msgs.capnp".Time; +using Transform = import "geometry_msgs.capnp".Transform; +using Twist = import "geometry_msgs.capnp".Twist; +using Vector3 = import "geometry_msgs.capnp".Vector3; +using Wrench = import "geometry_msgs.capnp".Wrench; +struct Imu { + header @0 :Header; + orientation @1 :Quaternion; + orientationCovariance @2 :List(Float64); + angularVelocity @3 :Vector3; + angularVelocityCovariance @4 :List(Float64); + linearAcceleration @5 :Vector3; + linearAccelerationCovariance @6 :List(Float64); +} +struct CompressedImage { + header @0 :Header; + format @1 :Text; + data @2 :Data; +} +struct Image { + header @0 :Header; + height @1 :UInt32; + width @2 :UInt32; + encoding @3 :Text; + isBigendian @4 :UInt8; + step @5 :UInt32; + data @6 :Data; +} +struct TimeReference { + header @0 :Header; + timeRef @1 :Time; + source @2 :Text; +} +struct MultiDOFJointState { + header @0 :Header; + jointNames @1 :List(Text); + transforms @2 :List(Transform); + twist @3 :List(Twist); + wrench @4 :List(Wrench); +} +struct Range { + header @0 :Header; + const kUltrasound :UInt8 = 0; + const kInfrared :UInt8 = 1; + radiationType @1 :UInt8; + fieldOfView @2 :Float32; + minRange @3 :Float32; + maxRange @4 :Float32; + range @5 :Float32; +} +struct PointCloud2 { + header @0 :Header; + height @1 :UInt32; + width @2 :UInt32; + fields @3 :List(PointField); + isBigendian @4 :Bool; + pointStep @5 :UInt32; + rowStep @6 :UInt32; + data @7 :Data; + isDense @8 :Bool; +} +struct JoyFeedbackArray { + array @0 :List(JoyFeedback); +} +struct Illuminance { + header @0 :Header; + illuminance @1 :Float64; + variance @2 :Float64; +} +struct NavSatFix { + header @0 :Header; + status @1 :NavSatStatus; + latitude @2 :Float64; + longitude @3 :Float64; + altitude @4 :Float64; + positionCovariance @5 :List(Float64); + const kCovarianceTypeUnknown :UInt8 = 0; + const kCovarianceTypeApproximated :UInt8 = 1; + const kCovarianceTypeDiagonalKnown :UInt8 = 2; + const kCovarianceTypeKnown :UInt8 = 3; + positionCovarianceType @6 :UInt8; +} +struct CameraInfo { + header @0 :Header; + height @1 :UInt32; + width @2 :UInt32; + distortionModel @3 :Text; + d @4 :List(Float64); + k @5 :List(Float64); + r @6 :List(Float64); + p @7 :List(Float64); + binningX @8 :UInt32; + binningY @9 :UInt32; + roi @10 :RegionOfInterest; +} +struct PointField { + const kInt8 :UInt8 = 1; + const kUint8 :UInt8 = 2; + const kInt16 :UInt8 = 3; + const kUint16 :UInt8 = 4; + const kInt32 :UInt8 = 5; + const kUint32 :UInt8 = 6; + const kFloat32 :UInt8 = 7; + const kFloat64 :UInt8 = 8; + name @0 :Text; + offset @1 :UInt32; + datatype @2 :UInt8; + count @3 :UInt32; +} +struct MultiEchoLaserScan { + header @0 :Header; + angleMin @1 :Float32; + angleMax @2 :Float32; + angleIncrement @3 :Float32; + timeIncrement @4 :Float32; + scanTime @5 :Float32; + rangeMin @6 :Float32; + rangeMax @7 :Float32; + ranges @8 :List(LaserEcho); + intensities @9 :List(LaserEcho); +} +struct Temperature { + header @0 :Header; + temperature @1 :Float64; + variance @2 :Float64; +} +struct Joy { + header @0 :Header; + axes @1 :List(Float32); + buttons @2 :List(Int32); +} +struct JoyFeedback { + const kTypeLed :UInt8 = 0; + const kTypeRumble :UInt8 = 1; + const kTypeBuzzer :UInt8 = 2; + type @0 :UInt8; + id @1 :UInt8; + intensity @2 :Float32; +} +struct PointCloud { + header @0 :Header; + points @1 :List(Point32); + channels @2 :List(ChannelFloat32); +} +struct JointState { + header @0 :Header; + name @1 :List(Text); + position @2 :List(Float64); + velocity @3 :List(Float64); + effort @4 :List(Float64); +} +struct LaserScan { + header @0 :Header; + angleMin @1 :Float32; + angleMax @2 :Float32; + angleIncrement @3 :Float32; + timeIncrement @4 :Float32; + scanTime @5 :Float32; + rangeMin @6 :Float32; + rangeMax @7 :Float32; + ranges @8 :List(Float32); + intensities @9 :List(Float32); +} +struct MagneticField { + header @0 :Header; + magneticField @1 :Vector3; + magneticFieldCovariance @2 :List(Float64); +} +struct LaserEcho { + echoes @0 :List(Float32); +} +struct RegionOfInterest { + xOffset @0 :UInt32; + yOffset @1 :UInt32; + height @2 :UInt32; + width @3 :UInt32; + doRectify @4 :Bool; +} +struct BatteryState { + const kPowerSupplyStatusUnknown :UInt8 = 0; + const kPowerSupplyStatusCharging :UInt8 = 1; + const kPowerSupplyStatusDischarging :UInt8 = 2; + const kPowerSupplyStatusNotCharging :UInt8 = 3; + const kPowerSupplyStatusFull :UInt8 = 4; + const kPowerSupplyHealthUnknown :UInt8 = 0; + const kPowerSupplyHealthGood :UInt8 = 1; + const kPowerSupplyHealthOverheat :UInt8 = 2; + const kPowerSupplyHealthDead :UInt8 = 3; + const kPowerSupplyHealthOvervoltage :UInt8 = 4; + const kPowerSupplyHealthUnspecFailure :UInt8 = 5; + const kPowerSupplyHealthCold :UInt8 = 6; + const kPowerSupplyHealthWatchdogTimerExpire :UInt8 = 7; + const kPowerSupplyHealthSafetyTimerExpire :UInt8 = 8; + const kPowerSupplyTechnologyUnknown :UInt8 = 0; + const kPowerSupplyTechnologyNimh :UInt8 = 1; + const kPowerSupplyTechnologyLion :UInt8 = 2; + const kPowerSupplyTechnologyLipo :UInt8 = 3; + const kPowerSupplyTechnologyLife :UInt8 = 4; + const kPowerSupplyTechnologyNicd :UInt8 = 5; + const kPowerSupplyTechnologyLimn :UInt8 = 6; + header @0 :Header; + voltage @1 :Float32; + temperature @2 :Float32; + current @3 :Float32; + charge @4 :Float32; + capacity @5 :Float32; + designCapacity @6 :Float32; + percentage @7 :Float32; + powerSupplyStatus @8 :UInt8; + powerSupplyHealth @9 :UInt8; + powerSupplyTechnology @10 :UInt8; + present @11 :Bool; + cellVoltage @12 :List(Float32); + cellTemperature @13 :List(Float32); + location @14 :Text; + serialNumber @15 :Text; +} +struct NavSatStatus { + const kStatusNoFix :Int8 = 1; + const kStatusFix :Int8 = 0; + const kStatusSbasFix :Int8 = 1; + const kStatusGbasFix :Int8 = 2; + status @0 :Int8; + const kServiceGps :UInt16 = 1; + const kServiceGlonass :UInt16 = 2; + const kServiceCompass :UInt16 = 4; + const kServiceGalileo :UInt16 = 8; + service @1 :UInt16; +} +struct FluidPressure { + header @0 :Header; + fluidPressure @1 :Float64; + variance @2 :Float64; +} +struct RelativeHumidity { + header @0 :Header; + relativeHumidity @1 :Float64; + variance @2 :Float64; +} +struct ChannelFloat32 { + name @0 :Text; + values @1 :List(Float32); +} diff --git a/msg/src/fairomsg/def/shape_msgs.capnp b/msg/src/fairomsg/def/shape_msgs.capnp new file mode 100644 index 0000000000..a98281892f --- /dev/null +++ b/msg/src/fairomsg/def/shape_msgs.capnp @@ -0,0 +1,30 @@ +@0xd95d03f2b0af9bb0; +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("mrp::shape"); +using Point = import "geometry_msgs.capnp".Point; +struct SolidPrimitive { + const kBox :UInt8 = 1; + const kSphere :UInt8 = 2; + const kCylinder :UInt8 = 3; + const kCone :UInt8 = 4; + type @0 :UInt8; + dimensions @1 :List(Float64); + const kBoxX :UInt8 = 0; + const kBoxY :UInt8 = 1; + const kBoxZ :UInt8 = 2; + const kSphereRadius :UInt8 = 0; + const kCylinderHeight :UInt8 = 0; + const kCylinderRadius :UInt8 = 1; + const kConeHeight :UInt8 = 0; + const kConeRadius :UInt8 = 1; +} +struct Plane { + coef @0 :List(Float64); +} +struct MeshTriangle { + vertexIndices @0 :List(UInt32); +} +struct Mesh { + triangles @0 :List(MeshTriangle); + vertices @1 :List(Point); +} diff --git a/msg/src/fairomsg/def/std_msgs.capnp b/msg/src/fairomsg/def/std_msgs.capnp new file mode 100644 index 0000000000..ed95276a8c --- /dev/null +++ b/msg/src/fairomsg/def/std_msgs.capnp @@ -0,0 +1,86 @@ +@0xfcdd69141cab2608; +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("mrp::std"); +struct Int16MultiArray { + layout @0 :MultiArrayLayout; + data @1 :List(Int16); +} +struct Time { + sec @0 :UInt32; + nsec @1 :UInt32; +} +struct MultiArrayDimension { + label @0 :Text; + size @1 :UInt32; + stride @2 :UInt32; +} +struct Float32MultiArray { + layout @0 :MultiArrayLayout; + data @1 :List(Float32); +} +struct UInt32MultiArray { + layout @0 :MultiArrayLayout; + data @1 :List(UInt32); +} +struct ColorRGBA { + r @0 :Float32; + g @1 :Float32; + b @2 :Float32; + a @3 :Float32; +} +struct Int32MultiArray { + layout @0 :MultiArrayLayout; + data @1 :List(Int32); +} +struct String { + data @0 :Text; +} +struct UInt16MultiArray { + layout @0 :MultiArrayLayout; + data @1 :List(UInt16); +} +struct UInt8MultiArray { + layout @0 :MultiArrayLayout; + data @1 :Data; +} +struct Byte { + data @0 :UInt8; +} +struct Header { + seq @0 :UInt32; + stamp @1 :Time; + frameId @2 :Text; +} +struct Float64MultiArray { + layout @0 :MultiArrayLayout; + data @1 :List(Float64); +} +struct Char { + data @0 :Int8; +} +struct UInt64MultiArray { + layout @0 :MultiArrayLayout; + data @1 :List(UInt64); +} +struct Duration { + sec @0 :Int32; + nsec @1 :Int32; +} +struct MultiArrayLayout { + dim @0 :List(MultiArrayDimension); + dataOffset @1 :UInt32; +} +struct Int8MultiArray { + layout @0 :MultiArrayLayout; + data @1 :Data; +} +struct Int64MultiArray { + layout @0 :MultiArrayLayout; + data @1 :List(Int64); +} +struct ByteMultiArray { + layout @0 :MultiArrayLayout; + data @1 :Data; +} +struct Empty { +} diff --git a/msg/src/fairomsg/def/stereo_msgs.capnp b/msg/src/fairomsg/def/stereo_msgs.capnp new file mode 100644 index 0000000000..303636248d --- /dev/null +++ b/msg/src/fairomsg/def/stereo_msgs.capnp @@ -0,0 +1,16 @@ +@0xa9f896a24e23368e; +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("mrp::stereo"); +using Header = import "std_msgs.capnp".Header; +using Image = import "sensor_msgs.capnp".Image; +using RegionOfInterest = import "sensor_msgs.capnp".RegionOfInterest; +struct DisparityImage { + header @0 :Header; + image @1 :Image; + f @2 :Float32; + t @3 :Float32; + validWindow @4 :RegionOfInterest; + minDisparity @5 :Float32; + maxDisparity @6 :Float32; + deltaD @7 :Float32; +} diff --git a/msg/src/fairomsg/def/trajectory_msgs.capnp b/msg/src/fairomsg/def/trajectory_msgs.capnp new file mode 100644 index 0000000000..6d8475b302 --- /dev/null +++ b/msg/src/fairomsg/def/trajectory_msgs.capnp @@ -0,0 +1,30 @@ +@0xe52fc95e987ddfdd; +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("mrp::trajectory"); +using Duration = import "std_msgs.capnp".Duration; +using Header = import "std_msgs.capnp".Header; +using Transform = import "geometry_msgs.capnp".Transform; +using Twist = import "geometry_msgs.capnp".Twist; +struct JointTrajectory { + header @0 :Header; + jointNames @1 :List(Text); + points @2 :List(JointTrajectoryPoint); +} +struct MultiDOFJointTrajectoryPoint { + transforms @0 :List(Transform); + velocities @1 :List(Twist); + accelerations @2 :List(Twist); + timeFromStart @3 :Duration; +} +struct MultiDOFJointTrajectory { + header @0 :Header; + jointNames @1 :List(Text); + points @2 :List(MultiDOFJointTrajectoryPoint); +} +struct JointTrajectoryPoint { + positions @0 :List(Float64); + velocities @1 :List(Float64); + accelerations @2 :List(Float64); + effort @3 :List(Float64); + timeFromStart @4 :Duration; +} diff --git a/msg/src/fairomsg/def/visualization_msgs.capnp b/msg/src/fairomsg/def/visualization_msgs.capnp new file mode 100644 index 0000000000..e90318ab57 --- /dev/null +++ b/msg/src/fairomsg/def/visualization_msgs.capnp @@ -0,0 +1,147 @@ +@0xc6ab06e10596c625; +using Cxx = import "/capnp/c++.capnp"; +$Cxx.namespace("mrp::visualization"); +using ColorRGBA = import "std_msgs.capnp".ColorRGBA; +using Duration = import "std_msgs.capnp".Duration; +using Header = import "std_msgs.capnp".Header; +using Point = import "geometry_msgs.capnp".Point; +using Pose = import "geometry_msgs.capnp".Pose; +using Quaternion = import "geometry_msgs.capnp".Quaternion; +using Vector3 = import "geometry_msgs.capnp".Vector3; +struct InteractiveMarkerUpdate { + serverId @0 :Text; + seqNum @1 :UInt64; + const kKeepAlive :UInt8 = 0; + const kUpdate :UInt8 = 1; + type @2 :UInt8; + markers @3 :List(InteractiveMarker); + poses @4 :List(InteractiveMarkerPose); + erases @5 :List(Text); +} +struct ImageMarker { + const kCircle :UInt8 = 0; + const kLineStrip :UInt8 = 1; + const kLineList :UInt8 = 2; + const kPolygon :UInt8 = 3; + const kPoints :UInt8 = 4; + const kAdd :UInt8 = 0; + const kRemove :UInt8 = 1; + header @0 :Header; + ns @1 :Text; + id @2 :Int32; + type @3 :Int32; + action @4 :Int32; + position @5 :Point; + scale @6 :Float32; + outlineColor @7 :ColorRGBA; + filled @8 :UInt8; + fillColor @9 :ColorRGBA; + lifetime @10 :Duration; + points @11 :List(Point); + outlineColors @12 :List(ColorRGBA); +} +struct InteractiveMarkerControl { + name @0 :Text; + orientation @1 :Quaternion; + const kInherit :UInt8 = 0; + const kFixed :UInt8 = 1; + const kViewFacing :UInt8 = 2; + orientationMode @2 :UInt8; + const kNone :UInt8 = 0; + const kMenu :UInt8 = 1; + const kButton :UInt8 = 2; + const kMoveAxis :UInt8 = 3; + const kMovePlane :UInt8 = 4; + const kRotateAxis :UInt8 = 5; + const kMoveRotate :UInt8 = 6; + const kMove3D :UInt8 = 7; + const kRotate3D :UInt8 = 8; + const kMoveRotate3D :UInt8 = 9; + interactionMode @3 :UInt8; + alwaysVisible @4 :Bool; + markers @5 :List(Marker); + independentMarkerOrientation @6 :Bool; + description @7 :Text; +} +struct InteractiveMarkerInit { + serverId @0 :Text; + seqNum @1 :UInt64; + markers @2 :List(InteractiveMarker); +} +struct MarkerArray { + markers @0 :List(Marker); +} +struct InteractiveMarkerFeedback { + header @0 :Header; + clientId @1 :Text; + markerName @2 :Text; + controlName @3 :Text; + const kKeepAlive :UInt8 = 0; + const kPoseUpdate :UInt8 = 1; + const kMenuSelect :UInt8 = 2; + const kButtonClick :UInt8 = 3; + const kMouseDown :UInt8 = 4; + const kMouseUp :UInt8 = 5; + eventType @4 :UInt8; + pose @5 :Pose; + menuEntryId @6 :UInt32; + mousePoint @7 :Point; + mousePointValid @8 :Bool; +} +struct Marker { + const kArrow :UInt8 = 0; + const kCube :UInt8 = 1; + const kSphere :UInt8 = 2; + const kCylinder :UInt8 = 3; + const kLineStrip :UInt8 = 4; + const kLineList :UInt8 = 5; + const kCubeList :UInt8 = 6; + const kSphereList :UInt8 = 7; + const kPoints :UInt8 = 8; + const kTextViewFacing :UInt8 = 9; + const kMeshResource :UInt8 = 10; + const kTriangleList :UInt8 = 11; + const kAdd :UInt8 = 0; + const kModify :UInt8 = 0; + const kDelete :UInt8 = 2; + const kDeleteall :UInt8 = 3; + header @0 :Header; + ns @1 :Text; + id @2 :Int32; + type @3 :Int32; + action @4 :Int32; + pose @5 :Pose; + scale @6 :Vector3; + color @7 :ColorRGBA; + lifetime @8 :Duration; + frameLocked @9 :Bool; + points @10 :List(Point); + colors @11 :List(ColorRGBA); + text @12 :Text; + meshResource @13 :Text; + meshUseEmbeddedMaterials @14 :Bool; +} +struct InteractiveMarker { + header @0 :Header; + pose @1 :Pose; + name @2 :Text; + description @3 :Text; + scale @4 :Float32; + menuEntries @5 :List(MenuEntry); + controls @6 :List(InteractiveMarkerControl); +} +struct MenuEntry { + id @0 :UInt32; + parentId @1 :UInt32; + title @2 :Text; + command @3 :Text; + const kFeedback :UInt8 = 0; + const kRosrun :UInt8 = 1; + const kRoslaunch :UInt8 = 2; + commandType @4 :UInt8; +} +struct InteractiveMarkerPose { + header @0 :Header; + pose @1 :Pose; + name @2 :Text; +} diff --git a/msg/src/fairomsg/serdes.py b/msg/src/fairomsg/serdes.py new file mode 100644 index 0000000000..ec4d779aa6 --- /dev/null +++ b/msg/src/fairomsg/serdes.py @@ -0,0 +1,28 @@ +import os +import site +import threading +import glob + +import capnp + +_schema_parser = capnp.SchemaParser() +capnp_cache = {} +lock = threading.Lock() + +def _get_full_filepath(msgpkg): + filedir = os.path.dirname(os.path.abspath(__file__)) + return os.path.join(filedir, f"def/{msgpkg}.capnp") + + +def get_msgs(msgpkg): + with lock: + if msgpkg not in capnp_cache: + print(f"capnp loading {msgpkg}") + capnp_cache[msgpkg] = _schema_parser.load(_get_full_filepath(msgpkg), imports=site.getsitepackages() + ) + return capnp_cache[msgpkg] + +def get_pkgs(): + filedir = os.path.dirname(os.path.abspath(__file__)) + filenames = glob.glob(f"{filedir}/def/*.capnp") + return [os.path.splitext(os.path.basename(filename))[0] for filename in filenames] diff --git a/msg/tests/test_fairomsg.py b/msg/tests/test_fairomsg.py new file mode 100644 index 0000000000..11a35bfab6 --- /dev/null +++ b/msg/tests/test_fairomsg.py @@ -0,0 +1,13 @@ +import pytest +from fairomsg import get_msgs, get_pkgs + +@pytest.fixture +def pkg_names(): + return get_pkgs() + +def test_get_pkgs(pkg_names): + assert len(pkg_names) > 0 + +def test_get_msgs(pkg_names): + for pkg_name in pkg_names: + get_msgs(pkg_name) \ No newline at end of file From d73a1c6c35ab6323832dc01a1c57907262b02daf Mon Sep 17 00:00:00 2001 From: 1heart Date: Wed, 13 Apr 2022 14:57:24 -0700 Subject: [PATCH 09/69] Bump README --- msg/README.md | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/msg/README.md b/msg/README.md index 5399ee1d5d..f202175786 100644 --- a/msg/README.md +++ b/msg/README.md @@ -8,6 +8,18 @@ Cap'n Proto message definitions, auto-generated from rosmsg. pip install git+https://github.com/facebookresearch/fairo.git@main#subdirectory=msg ``` +## Usage + +```python +import fairomsg + +pkg_names = fairomsg.get_pkgs() +assert 'sensor_msgs' in pkg_names + +sensor_msgs = fairomsg.get_msgs('sensor_msgs') +img_builder = sensor_msgs.Image() +``` + ## Build Add ROS msg packages to the Conda environment as necessary in [msetup.py](msetup.py) by appending to `ros_msg_packages`. Then, From 04296e05d5eb6641a6390e17f8c70f64991de4f8 Mon Sep 17 00:00:00 2001 From: Yixin Lin <1heart@users.noreply.github.com> Date: Wed, 13 Apr 2022 18:06:41 -0400 Subject: [PATCH 10/69] Update config.yml --- .circleci/config.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.circleci/config.yml b/.circleci/config.yml index 8e3cba83fe..0b1ba4a60f 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -458,6 +458,7 @@ workflows: - formatting - mrp - fairotag + - fairomsg - eyehandcal - update-docs: requires: From 2098c1f7e95bbeb467d17b9e3a423043e2ea3872 Mon Sep 17 00:00:00 2001 From: 1heart Date: Thu, 14 Apr 2022 19:09:06 -0700 Subject: [PATCH 11/69] Minor fixes --- .circleci/config.yml | 4 ++-- msg/setup.py | 1 - perception/sandbox/eyehandcal/.envrc | 1 - 3 files changed, 2 insertions(+), 4 deletions(-) delete mode 100644 perception/sandbox/eyehandcal/.envrc diff --git a/.circleci/config.yml b/.circleci/config.yml index 0b1ba4a60f..2e0ce17d16 100644 --- a/.circleci/config.yml +++ b/.circleci/config.yml @@ -364,8 +364,8 @@ jobs: - image: cimg/python:3.8 steps: - checkout - - run: pip install ./fairomsg - - run: pip install pytest && pytest fairomsg/tests + - run: pip install ./msg + - run: pip install pytest && pytest ./msg/tests update-docs: docker: - image: cimg/node:current diff --git a/msg/setup.py b/msg/setup.py index 5f0b973ac6..90a9ee6492 100644 --- a/msg/setup.py +++ b/msg/setup.py @@ -7,7 +7,6 @@ install_requires = [ "pycapnp", - "mrp", ] diff --git a/perception/sandbox/eyehandcal/.envrc b/perception/sandbox/eyehandcal/.envrc deleted file mode 100644 index ea148ff778..0000000000 --- a/perception/sandbox/eyehandcal/.envrc +++ /dev/null @@ -1 +0,0 @@ -layout_miniconda eyehandcal From b70664f2847bc1288c1a47409599cc4e697c6263 Mon Sep 17 00:00:00 2001 From: 1heart Date: Fri, 15 Apr 2022 07:31:37 -0700 Subject: [PATCH 12/69] Readd envrc --- perception/sandbox/eyehandcal/.envrc | 1 + 1 file changed, 1 insertion(+) create mode 100644 perception/sandbox/eyehandcal/.envrc diff --git a/perception/sandbox/eyehandcal/.envrc b/perception/sandbox/eyehandcal/.envrc new file mode 100644 index 0000000000..ea148ff778 --- /dev/null +++ b/perception/sandbox/eyehandcal/.envrc @@ -0,0 +1 @@ +layout_miniconda eyehandcal From eff5582acc9cd71bdd11ff299de4696292ec5b5a Mon Sep 17 00:00:00 2001 From: 1heart Date: Fri, 15 Apr 2022 09:17:30 -0700 Subject: [PATCH 13/69] Reproduced o3d pointcloud creation --- .../sandbox/polygrasp/scripts/run_grasp.py | 8 +-- perception/sandbox/polygrasp/setup.py | 2 + .../polygrasp/src/polygrasp/pointcloud_rpc.py | 52 ++++++++++++++++--- 3 files changed, 53 insertions(+), 9 deletions(-) diff --git a/perception/sandbox/polygrasp/scripts/run_grasp.py b/perception/sandbox/polygrasp/scripts/run_grasp.py index e938182682..0ea6798785 100644 --- a/perception/sandbox/polygrasp/scripts/run_grasp.py +++ b/perception/sandbox/polygrasp/scripts/run_grasp.py @@ -24,18 +24,20 @@ def main(cfg): # Initialize cameras cameras = RealsenseAPI() camera_intrinsics = cameras.get_intrinsics() - camera_extrinsics = json.load(hydra.utils.to_absolute_path(cfg.camera_extrinsics_path)) + with open(hydra.utils.to_absolute_path(cfg.camera_extrinsics_path), "r") as f: + camera_extrinsics = json.load(f) # Connect to grasp candidate selection and pointcloud processor - import pdb; pdb.set_trace() pcd_client = PointCloudClient(camera_intrinsics, camera_extrinsics) - grasp_suggester = GraspClient() + # grasp_suggester = GraspClient() num_iters = 1 for i in range(num_iters): + print(f"Grasp {i + 1} / num_iters") # Get RGBD & pointcloud rgbd = cameras.get_rgbd() scene_pcd = pcd_client.get_pcd(rgbd) + import pdb; pdb.set_trace() # Get grasps per object obj_to_pcd = pcd_client.segment_pcd(scene_pcd) diff --git a/perception/sandbox/polygrasp/setup.py b/perception/sandbox/polygrasp/setup.py index 5dd457f262..ac52a21a96 100644 --- a/perception/sandbox/polygrasp/setup.py +++ b/perception/sandbox/polygrasp/setup.py @@ -11,6 +11,8 @@ install_requires = [ "grpcio-tools", "realsense_wrapper", + "mrp", + "fairomsg", ] diff --git a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py index 7f027b7552..85239e61dd 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py @@ -1,13 +1,15 @@ -from typing import Iterator +from typing import Iterator, List import logging from concurrent import futures +import functools import numpy as np -import open3d +import open3d as o3d import grpc from polygrasp import polygrasp_pb2 from polygrasp import polygrasp_pb2_grpc +import pyrealsense2 log = logging.getLogger(__name__) @@ -21,11 +23,49 @@ def SegmentPointcloud(self, request_iterator: Iterator[polygrasp_pb2.PointCloud] raise NotImplementedError class PointCloudClient: - def __init__(self, camera_intrinsics: np.ndarray, camera_extrinsics: np.ndarray): - pass + def __init__(self, camera_intrinsics: List[pyrealsense2.pyrealsense2.intrinsics], camera_extrinsics: np.ndarray): + assert len(camera_intrinsics) == len(camera_extrinsics) + self.n_cams = len(camera_intrinsics) - def get_pcd(self) -> open3d.geometry.PointCloud: - raise NotImplementedError + # Convert to open3d intrinsics + self.o3_intrinsics = [ + o3d.camera.PinholeCameraIntrinsic( + width=intrinsic.width, + height=intrinsic.height, + fx=intrinsic.fx, + fy=intrinsic.fy, + cx=intrinsic.ppx, + cy=intrinsic.ppy, + ) + for intrinsic in camera_intrinsics + ] + + # Convert to numpy homogeneous transforms + self.extrinsic_transforms = np.empty([self.n_cams, 4, 4]) + for i, calibration in enumerate(camera_extrinsics): + self.extrinsic_transforms[i] = np.eye(4) + self.extrinsic_transforms[i, :3, :3] = calibration["camera_base_ori"] + self.extrinsic_transforms[i, :3, 3] = calibration["camera_base_pos"] + + def get_pcd(self, rgbds: np.ndarray) -> o3d.geometry.PointCloud: + scene_pcd = o3d.geometry.PointCloud() + for rgbd, intrinsic, transform in zip(rgbds, self.o3_intrinsics, self.extrinsic_transforms): + # The specific casting here seems to be very important, even though + # rgbd should already be in np.uint16 type... + img = rgbd[:, :, :3].astype(np.uint8) + depth = rgbd[:, :, 3].astype(np.uint16) + + o3d_img = o3d.cuda.pybind.geometry.Image(img) + o3d_depth = o3d.cuda.pybind.geometry.Image(depth) + + rgbd_image = o3d.geometry.RGBDImage.create_from_color_and_depth(o3d_img,o3d_depth,convert_rgb_to_intensity=False,) + + pcd = o3d.geometry.PointCloud.create_from_rgbd_image(rgbd_image, intrinsic) + pcd.transform(transform) + scene_pcd += pcd + + o3d.visualization.draw_geometries([scene_pcd]) + return scene_pcd def segment_pcd(self): raise NotImplementedError From cb518899969c2ad22a32ab0ca324ea228dee5074 Mon Sep 17 00:00:00 2001 From: 1heart Date: Mon, 18 Apr 2022 14:00:57 -0700 Subject: [PATCH 14/69] WIP: working grasp, pcd servers --- .../sandbox/polygrasp/conf/o3d_view.json | 41 ++++++ .../sandbox/polygrasp/conf/run_grasp.yaml | 3 +- perception/sandbox/polygrasp/msetup.py | 17 +++ .../sandbox/polygrasp/scripts/run_grasp.py | 39 ++--- perception/sandbox/polygrasp/setup.py | 1 - .../polygrasp/src/polygrasp/grasp_rpc.py | 139 +++++++++++++++--- .../polygrasp/src/polygrasp/pointcloud_rpc.py | 2 +- .../sandbox/polygrasp/src/polygrasp/serdes.py | 85 +++++++++++ 8 files changed, 282 insertions(+), 45 deletions(-) create mode 100644 perception/sandbox/polygrasp/conf/o3d_view.json create mode 100644 perception/sandbox/polygrasp/msetup.py create mode 100644 perception/sandbox/polygrasp/src/polygrasp/serdes.py diff --git a/perception/sandbox/polygrasp/conf/o3d_view.json b/perception/sandbox/polygrasp/conf/o3d_view.json new file mode 100644 index 0000000000..a95848bbdd --- /dev/null +++ b/perception/sandbox/polygrasp/conf/o3d_view.json @@ -0,0 +1,41 @@ +{ + "class_name" : "PinholeCameraParameters", + "extrinsic" : + [ + -0.17934232072035228, + 0.62824398015079619, + -0.75706395595281406, + 0.0, + -0.93071141841725624, + -0.3576959813755009, + -0.076353392429913805, + 0.0, + -0.31876729384674551, + 0.69091467368417026, + 0.64886387329047623, + 0.0, + -0.32553207564722353, + -0.45523096210618585, + 2.6578988267350927, + 1.0 + ], + "intrinsic" : + { + "height" : 1080, + "intrinsic_matrix" : + [ + 935.30743608719376, + 0.0, + 0.0, + 0.0, + 935.30743608719376, + 0.0, + 959.5, + 539.5, + 1.0 + ], + "width" : 1920 + }, + "version_major" : 1, + "version_minor" : 0 +} \ No newline at end of file diff --git a/perception/sandbox/polygrasp/conf/run_grasp.yaml b/perception/sandbox/polygrasp/conf/run_grasp.yaml index 31149923e2..a85af004a2 100644 --- a/perception/sandbox/polygrasp/conf/run_grasp.yaml +++ b/perception/sandbox/polygrasp/conf/run_grasp.yaml @@ -5,4 +5,5 @@ robot: gripper: _target_: polymetis.GripperInterface -camera_extrinsics_path: ../eyehandcal/calibration.json \ No newline at end of file +camera_extrinsics_path: ../eyehandcal/calibration.json +view_json_path: conf/o3d_view.json \ No newline at end of file diff --git a/perception/sandbox/polygrasp/msetup.py b/perception/sandbox/polygrasp/msetup.py new file mode 100644 index 0000000000..9ee570c467 --- /dev/null +++ b/perception/sandbox/polygrasp/msetup.py @@ -0,0 +1,17 @@ +import mrp + +mrp.process( + name="grasp_server", + runtime=mrp.Host( + run_command=["python", "src/polygrasp/grasp_rpc.py"], + ), +) + +mrp.process( + name="pointcloud_server", + runtime=mrp.Host( + run_command=["python", "src/polygrasp/pointcloud_rpc.py"], + ), +) + +mrp.main() diff --git a/perception/sandbox/polygrasp/scripts/run_grasp.py b/perception/sandbox/polygrasp/scripts/run_grasp.py index 0ea6798785..6108cc4160 100644 --- a/perception/sandbox/polygrasp/scripts/run_grasp.py +++ b/perception/sandbox/polygrasp/scripts/run_grasp.py @@ -29,7 +29,7 @@ def main(cfg): # Connect to grasp candidate selection and pointcloud processor pcd_client = PointCloudClient(camera_intrinsics, camera_extrinsics) - # grasp_suggester = GraspClient() + grasp_client = GraspClient(view_json_path=hydra.utils.to_absolute_path(cfg.view_json_path)) num_iters = 1 for i in range(num_iters): @@ -37,29 +37,30 @@ def main(cfg): # Get RGBD & pointcloud rgbd = cameras.get_rgbd() scene_pcd = pcd_client.get_pcd(rgbd) - import pdb; pdb.set_trace() + grasp_group = grasp_client.get_grasps(scene_pcd) + grasp_client.visualize_grasp(scene_pcd, grasp_group, plot=True) - # Get grasps per object - obj_to_pcd = pcd_client.segment_pcd(scene_pcd) - obj_to_grasps = {obj: grasp_suggester.get_grasps(pcd) for obj, pcd in obj_to_pcd.items()} + # # Get grasps per object + # obj_to_pcd = pcd_client.segment_pcd(scene_pcd) + # obj_to_grasps = {obj: grasp_client.get_grasps(pcd) for obj, pcd in obj_to_pcd.items()} - # Pick a random object to grasp - curr_obj, curr_grasps = random.choice(list(obj_to_grasps.items())) - print(f"Picking object with ID {curr_obj}") + # # Pick a random object to grasp + # curr_obj, curr_grasps = random.choice(list(obj_to_grasps.items())) + # print(f"Picking object with ID {curr_obj}") - # Choose a grasp for this object - # TODO: scene-aware motion planning for grasps - des_ee_pos, des_ee_ori = robot.select_grasp(curr_grasps, scene_pcd) + # # Choose a grasp for this object + # # TODO: scene-aware motion planning for grasps + # des_ee_pos, des_ee_ori = robot.select_grasp(curr_grasps, scene_pcd) - # Execute grasp - traj, success = robot.grasp(ee_pos=des_ee_pos, ee_ori=des_ee_ori) - print(f"Grasp success: {success}") + # # Execute grasp + # traj, success = robot.grasp(ee_pos=des_ee_pos, ee_ori=des_ee_ori) + # print(f"Grasp success: {success}") - if success: - print(f"Moving end-effector up and down") - curr_pose, curr_ori = robot.get_ee_pose() - robot.move_to_ee_pose(torch.Tensor([0, 0, 0.1]), delta=True) - robot.move_to_ee_pose(torch.Tensor([0, 0, -0.1]), delta=True) + # if success: + # print(f"Moving end-effector up and down") + # curr_pose, curr_ori = robot.get_ee_pose() + # robot.move_to_ee_pose(torch.Tensor([0, 0, 0.1]), delta=True) + # robot.move_to_ee_pose(torch.Tensor([0, 0, -0.1]), delta=True) if __name__ == "__main__": main() diff --git a/perception/sandbox/polygrasp/setup.py b/perception/sandbox/polygrasp/setup.py index ac52a21a96..4477886ddf 100644 --- a/perception/sandbox/polygrasp/setup.py +++ b/perception/sandbox/polygrasp/setup.py @@ -10,7 +10,6 @@ install_requires = [ "grpcio-tools", - "realsense_wrapper", "mrp", "fairomsg", ] diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py index 28c8b65851..0ac4b5a622 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py @@ -1,39 +1,132 @@ -from typing import Iterator import logging -from concurrent import futures - import numpy as np -import open3d +import scipy +import open3d as o3d + +from matplotlib import pyplot as plt + +import a0 -import grpc -from polygrasp import polygrasp_pb2 -from polygrasp import polygrasp_pb2_grpc +import graspnetAPI +from polygrasp import serdes log = logging.getLogger(__name__) +topic_key = "grasp_server" -class GraspServer(polygrasp_pb2_grpc.GraspServer): - def _get_grasps(self, pcd: open3d.geometry.PointCloud) -> np.ndarray: +class GraspServer: + def _get_grasps(self, pcd: o3d.geometry.PointCloud) -> np.ndarray: raise NotImplementedError - def GetGrasps(self, request_iterator: Iterator[polygrasp_pb2.PointCloud], context) -> Iterator[polygrasp_pb2.GraspGroup]: - raise NotImplementedError + def start(self): + log.info(f"Starting grasp server...") + + def onrequest(req): + log.info(f"Got request; computing grasp group...") + payload = req.pkt.payload + pcd = serdes.capnp_to_pcd(payload) + grasp_group = self._get_grasps(pcd) + + log.info(f"Done. Replying with serialized grasp group...") + req.reply(serdes.grasp_group_to_capnp(grasp_group).to_bytes()) + + server = a0.RpcServer(topic_key, onrequest, None) + while True: + pass class GraspClient: - def get_grasps(pcd: open3d.geometry.PointCloud) -> np.ndarray: - raise NotImplementedError + def __init__(self, view_json_path): + self.client = a0.RpcClient(topic_key) + self.view_json_path = view_json_path + + def get_grasps(self, pcd: o3d.geometry.PointCloud) -> graspnetAPI.GraspGroup: + state = [] + def onreply(pkt): + state.append(pkt.payload) + + i = 1 + while True: + downsampled_pcd = pcd.uniform_down_sample(i) + bytes = serdes.pcd_to_capnp(downsampled_pcd).to_bytes() + if len(bytes) > 8 * 1024 * 1024: # a0 default max msg size 16MB; make sure every msg < 1/2 of max + log.warning(f"Downsampling pointcloud...") + i += 1 + else: + break + if i > 1: + log.warning(f"Downsampled to every {i}th point.") + self.client.send(bytes, onreply) + + while not state: + pass + return serdes.capnp_to_grasp_group(state.pop()) + + def visualize_grasp(self, scene_pcd: o3d.geometry.PointCloud, grasp_group: graspnetAPI.GraspGroup, n=5, plot=False, render=False, save_view=False) -> None: + o3d_geometries = grasp_group.to_open3d_geometry_list() + + n = min(n, len(o3d_geometries)) + log.info(f"Visualizing top {n} grasps in Open3D...") + + vis = o3d.visualization.Visualizer() + vis.create_window() + ctr = vis.get_view_control() + param = o3d.io.read_pinhole_camera_parameters(self.view_json_path) + ctr.convert_from_pinhole_camera_parameters(param) + + vis.add_geometry(scene_pcd) + grasp_images = [] + for i in range(n): + scene_points = o3d_geometries[i].sample_points_uniformly(number_of_points=5000) + vis.add_geometry(scene_points) + grasp_image = np.array(vis.capture_screen_float_buffer(do_render=True)) + grasp_images.append(grasp_image) + + if render: + """Render the window. You can rotate it & save the view.""" + # Actually render the window: + log.info(f"Rendering best grasp {i + 1}/{n}") + # import pdb; pdb.set_trace() + vis.run() + if save_view: + # Save the view + param = vis.get_view_control().convert_to_pinhole_camera_parameters() + o3d.io.write_pinhole_camera_parameters(self.view_json_path, param) + + vis.remove_geometry(scene_points) + + vis.destroy_window() + if plot: + log.info("Plotting with matplotlib...") + f, axarr = plt.subplots(1, n) + f.set_size_inches(n * 3, 3) + for i in range(n): + axarr[i].imshow(grasp_images[i]) + axarr[i].axis("off") + axarr[i].set_title(f"Grasp pose top {i + 1}/{n}") + f.show() + +# class GraspServer(polygrasp_pb2_grpc.GraspServer): +# def _get_grasps(self, pcd: o3d.geometry.PointCloud) -> np.ndarray: +# raise NotImplementedError + +# def GetGrasps( +# self, request_iterator: Iterator[polygrasp_pb2.PointCloud], context +# ) -> Iterator[polygrasp_pb2.GraspGroup]: +# raise NotImplementedError + -def serve(port=50053, max_workers=10, *args, **kwargs): - server = grpc.server(futures.ThreadPoolExecutor(max_workers=max_workers)) - polygrasp_pb2_grpc.add_GraspServerServicer_to_server(GraspServer(*args, **kwargs), server) - server.add_insecure_port(f"[::]:{port}") - log.info(f"=== Starting server... ===") - server.start() - log.info(f"=== Done. Server running at port {port}. ===") - server.wait_for_termination() +# class GraspClient: +# def get_grasps(pcd: o3d.geometry.PointCloud) -> np.ndarray: +# raise NotImplementedError -if __name__ == "__main__": - serve() +# def serve(server_impl: GraspServer, port=50053, max_workers=10): +# server = grpc.server(futures.ThreadPoolExecutor(max_workers=max_workers)) +# polygrasp_pb2_grpc.add_GraspServerServicer_to_server(server_impl, server) +# server.add_insecure_port(f"[::]:{port}") +# log.info(f"=== Starting server... ===") +# server.start() +# log.info(f"=== Done. Server running at port {port}. ===") +# server.wait_for_termination() diff --git a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py index 85239e61dd..c94415953f 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py @@ -64,7 +64,7 @@ def get_pcd(self, rgbds: np.ndarray) -> o3d.geometry.PointCloud: pcd.transform(transform) scene_pcd += pcd - o3d.visualization.draw_geometries([scene_pcd]) + # o3d.visualization.draw_geometries([scene_pcd]) return scene_pcd def segment_pcd(self): diff --git a/perception/sandbox/polygrasp/src/polygrasp/serdes.py b/perception/sandbox/polygrasp/src/polygrasp/serdes.py new file mode 100644 index 0000000000..b1cf44e12c --- /dev/null +++ b/perception/sandbox/polygrasp/src/polygrasp/serdes.py @@ -0,0 +1,85 @@ +import numpy as np +from scipy.spatial.transform import Rotation as R +import open3d as o3d +import fairomsg +import capnp + +import io +import numpy as np +import open3d +import graspnetAPI + +std_msgs = fairomsg.get_msgs("std_msgs") +sensor_msgs = fairomsg.get_msgs("sensor_msgs") +geometry_msgs = fairomsg.get_msgs("geometry_msgs") + +"""Byte conversions""" + +def np_to_bytes(arr: np.ndarray): + with io.BytesIO() as f: + np.save(f, arr) + return f.getvalue() + + +def bytes_to_np(bytes_arr: bytes): + with io.BytesIO(bytes_arr) as f: + return np.load(f) + + +def grasp_group_to_bytes(grasp_group: graspnetAPI.grasp.GraspGroup): + return np_to_bytes(grasp_group.grasp_group_array) + + +def bytes_to_grasp_group(arr_bytes: bytes): + return graspnetAPI.grasp.GraspGroup(bytes_to_np(arr_bytes)) + + +def open3d_pcd_to_bytes(cloud: open3d.geometry.PointCloud): + if cloud.has_colors(): + arr = np.hstack([np.asarray(cloud.points), np.asarray(cloud.colors)]) + else: + arr = np.asarray(cloud.points) + return np_to_bytes(arr) + + +def bytes_to_open3d_pcd(arr_bytes: bytes): + arr = bytes_to_np(arr_bytes) + result = open3d.geometry.PointCloud( + open3d.cuda.pybind.utility.Vector3dVector(arr[:, :3]) + ) + if arr.shape[1] == 6: + result.colors = open3d.cuda.pybind.utility.Vector3dVector(arr[:, 3:]) + + return result + +"""Capnp conversions""" + +def pcd_to_capnp(pcd: o3d.geometry.PointCloud): + result = sensor_msgs.PointCloud2() + result.data = open3d_pcd_to_bytes(pcd) + return result + +def capnp_to_pcd(blob): + capnp_pcd = sensor_msgs.PointCloud2.from_bytes(blob) + return bytes_to_open3d_pcd(capnp_pcd.data) + +def grasp_group_to_capnp(grasp_group: graspnetAPI.grasp.GraspGroup): + capnp_gg = std_msgs.ByteMultiArray() + capnp_gg.data = grasp_group_to_bytes(grasp_group) + # capnp_gg = geometry_msgs.PoseArray() + # capnp_poses = capnp_gg.init("poses", len(grasp_group)) + # for pose, grasp in zip(capnp_poses, grasp_group): + # x, y, z = grasp.translation.tolist() + # pose.position = geometry_msgs.Point(x=x, y=y, z=z) + # x, y, z, w = R.from_matrix(grasp.rotation_matrix).as_quat().tolist() + # pose.orientation = geometry_msgs.Quaternion(x=x, y=y, z=z, w=w) + return capnp_gg + +def capnp_to_grasp_group(blob): + capnp_gg = std_msgs.ByteMultiArray.from_bytes(blob) + + # for pose in capnp_gg.poses: + # xyz = pose.position + + gg = bytes_to_grasp_group(capnp_gg.data) + return gg From 2040078ca3e93ac132c85cb04784fd27147888a7 Mon Sep 17 00:00:00 2001 From: 1heart Date: Mon, 18 Apr 2022 17:45:46 -0700 Subject: [PATCH 15/69] Cleanup, working RobotInterface grasp --- .../sandbox/polygrasp/conf/o3d_view.json | 24 +-- .../sandbox/polygrasp/conf/run_grasp.yaml | 2 +- .../sandbox/polygrasp/scripts/run_grasp.py | 20 ++- .../polygrasp/src/polygrasp/grasp_rpc.py | 87 ++++------ .../polygrasp/src/polygrasp/pointcloud_rpc.py | 48 ++---- .../polygrasp/src/polygrasp/polygrasp.proto | 30 ---- .../polygrasp/src/polygrasp/polygrasp_pb2.py | 70 -------- .../src/polygrasp/polygrasp_pb2_grpc.py | 160 ------------------ .../src/polygrasp/robot_interface.py | 84 ++++++++- .../sandbox/polygrasp/src/polygrasp/serdes.py | 10 -- .../sandbox/polygrasp/src/polygrasp/utils.py | 0 11 files changed, 155 insertions(+), 380 deletions(-) delete mode 100644 perception/sandbox/polygrasp/src/polygrasp/polygrasp.proto delete mode 100644 perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2.py delete mode 100644 perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2_grpc.py delete mode 100644 perception/sandbox/polygrasp/src/polygrasp/utils.py diff --git a/perception/sandbox/polygrasp/conf/o3d_view.json b/perception/sandbox/polygrasp/conf/o3d_view.json index a95848bbdd..e73b6e4fa4 100644 --- a/perception/sandbox/polygrasp/conf/o3d_view.json +++ b/perception/sandbox/polygrasp/conf/o3d_view.json @@ -2,21 +2,21 @@ "class_name" : "PinholeCameraParameters", "extrinsic" : [ - -0.17934232072035228, - 0.62824398015079619, - -0.75706395595281406, + 0.28142335070175561, + 0.82567964910260616, + -0.48893150311428485, 0.0, - -0.93071141841725624, - -0.3576959813755009, - -0.076353392429913805, + 0.94624675005352421, + -0.15413178729053639, + 0.28435977240068283, 0.0, - -0.31876729384674551, - 0.69091467368417026, - 0.64886387329047623, + 0.15943019065703956, + -0.54267532577446542, + -0.82467296857762828, 0.0, - -0.32553207564722353, - -0.45523096210618585, - 2.6578988267350927, + -0.11735080584901347, + -0.60509490445918845, + 1.259222836495665, 1.0 ], "intrinsic" : diff --git a/perception/sandbox/polygrasp/conf/run_grasp.yaml b/perception/sandbox/polygrasp/conf/run_grasp.yaml index a85af004a2..ea93a6bc71 100644 --- a/perception/sandbox/polygrasp/conf/run_grasp.yaml +++ b/perception/sandbox/polygrasp/conf/run_grasp.yaml @@ -6,4 +6,4 @@ robot: _target_: polymetis.GripperInterface camera_extrinsics_path: ../eyehandcal/calibration.json -view_json_path: conf/o3d_view.json \ No newline at end of file +view_json_path: conf/o3d_view.json diff --git a/perception/sandbox/polygrasp/scripts/run_grasp.py b/perception/sandbox/polygrasp/scripts/run_grasp.py index 6108cc4160..d08fab22ba 100644 --- a/perception/sandbox/polygrasp/scripts/run_grasp.py +++ b/perception/sandbox/polygrasp/scripts/run_grasp.py @@ -20,6 +20,8 @@ def main(cfg): # Initialize robot & gripper robot = hydra.utils.instantiate(cfg.robot) + robot.gripper_open() + robot.go_home() # Initialize cameras cameras = RealsenseAPI() @@ -34,11 +36,14 @@ def main(cfg): num_iters = 1 for i in range(num_iters): print(f"Grasp {i + 1} / num_iters") + # Get RGBD & pointcloud rgbd = cameras.get_rgbd() + scene_pcd = pcd_client.get_pcd(rgbd) grasp_group = grasp_client.get_grasps(scene_pcd) - grasp_client.visualize_grasp(scene_pcd, grasp_group, plot=True) + + grasp_client.visualize_grasp(scene_pcd, grasp_group, render=False, save_view=False, plot=True) # # Get grasps per object # obj_to_pcd = pcd_client.segment_pcd(scene_pcd) @@ -48,13 +53,14 @@ def main(cfg): # curr_obj, curr_grasps = random.choice(list(obj_to_grasps.items())) # print(f"Picking object with ID {curr_obj}") - # # Choose a grasp for this object - # # TODO: scene-aware motion planning for grasps - # des_ee_pos, des_ee_ori = robot.select_grasp(curr_grasps, scene_pcd) + # Choose a grasp for this object + # TODO: scene-aware motion planning for grasps + curr_grasps = grasp_group + chosen_grasp = robot.select_grasp(curr_grasps, scene_pcd) - # # Execute grasp - # traj, success = robot.grasp(ee_pos=des_ee_pos, ee_ori=des_ee_ori) - # print(f"Grasp success: {success}") + # Execute grasp + traj, success = robot.grasp(chosen_grasp) + print(f"Grasp success: {success}") # if success: # print(f"Moving end-effector up and down") diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py index 0ac4b5a622..49d8da47c1 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py @@ -1,6 +1,5 @@ import logging import numpy as np -import scipy import open3d as o3d from matplotlib import pyplot as plt @@ -12,9 +11,9 @@ log = logging.getLogger(__name__) - topic_key = "grasp_server" + class GraspServer: def _get_grasps(self, pcd: o3d.geometry.PointCloud) -> np.ndarray: raise NotImplementedError @@ -27,8 +26,8 @@ def onrequest(req): payload = req.pkt.payload pcd = serdes.capnp_to_pcd(payload) - grasp_group = self._get_grasps(pcd) - + grasp_group = self._get_grasps(pcd) + log.info(f"Done. Replying with serialized grasp group...") req.reply(serdes.grasp_group_to_capnp(grasp_group).to_bytes()) @@ -36,6 +35,7 @@ def onrequest(req): while True: pass + class GraspClient: def __init__(self, view_json_path): self.client = a0.RpcClient(topic_key) @@ -43,6 +43,7 @@ def __init__(self, view_json_path): def get_grasps(self, pcd: o3d.geometry.PointCloud) -> graspnetAPI.GraspGroup: state = [] + def onreply(pkt): state.append(pkt.payload) @@ -50,7 +51,9 @@ def onreply(pkt): while True: downsampled_pcd = pcd.uniform_down_sample(i) bytes = serdes.pcd_to_capnp(downsampled_pcd).to_bytes() - if len(bytes) > 8 * 1024 * 1024: # a0 default max msg size 16MB; make sure every msg < 1/2 of max + if ( + len(bytes) > 8 * 1024 * 1024 + ): # a0 default max msg size 16MB; make sure every msg < 1/2 of max log.warning(f"Downsampling pointcloud...") i += 1 else: @@ -62,8 +65,16 @@ def onreply(pkt): while not state: pass return serdes.capnp_to_grasp_group(state.pop()) - - def visualize_grasp(self, scene_pcd: o3d.geometry.PointCloud, grasp_group: graspnetAPI.GraspGroup, n=5, plot=False, render=False, save_view=False) -> None: + + def visualize_grasp( + self, + scene_pcd: o3d.geometry.PointCloud, + grasp_group: graspnetAPI.GraspGroup, + n=5, + plot=False, + render=False, + save_view=False, + ) -> None: o3d_geometries = grasp_group.to_open3d_geometry_list() n = min(n, len(o3d_geometries)) @@ -71,62 +82,36 @@ def visualize_grasp(self, scene_pcd: o3d.geometry.PointCloud, grasp_group: grasp vis = o3d.visualization.Visualizer() vis.create_window() - ctr = vis.get_view_control() + vis.add_geometry(scene_pcd, reset_bounding_box=True) + + if render: + """Render the window. You can rotate it & save the view.""" + # Actually render the window: + log.info(f"Rendering scene in Open3D") + vis.run() + param = vis.get_view_control().convert_to_pinhole_camera_parameters() + if save_view: + log.info(f"Saving new view to {self.view_json_path}") + # Save the view + o3d.io.write_pinhole_camera_parameters(self.view_json_path, param) + param = o3d.io.read_pinhole_camera_parameters(self.view_json_path) - ctr.convert_from_pinhole_camera_parameters(param) + vis.get_view_control().convert_from_pinhole_camera_parameters(param) - vis.add_geometry(scene_pcd) grasp_images = [] for i in range(n): scene_points = o3d_geometries[i].sample_points_uniformly(number_of_points=5000) - vis.add_geometry(scene_points) + vis.add_geometry(scene_points, reset_bounding_box=False) grasp_image = np.array(vis.capture_screen_float_buffer(do_render=True)) grasp_images.append(grasp_image) - - if render: - """Render the window. You can rotate it & save the view.""" - # Actually render the window: - log.info(f"Rendering best grasp {i + 1}/{n}") - # import pdb; pdb.set_trace() - vis.run() - if save_view: - # Save the view - param = vis.get_view_control().convert_to_pinhole_camera_parameters() - o3d.io.write_pinhole_camera_parameters(self.view_json_path, param) - - vis.remove_geometry(scene_points) + vis.remove_geometry(scene_points, reset_bounding_box=False) vis.destroy_window() if plot: log.info("Plotting with matplotlib...") - f, axarr = plt.subplots(1, n) - f.set_size_inches(n * 3, 3) + f, axarr = plt.subplots(1, n, figsize=(n * 4.5, 3)) for i in range(n): - axarr[i].imshow(grasp_images[i]) + axarr[i].imshow(grasp_images[i], interpolation='nearest', aspect='auto') axarr[i].axis("off") axarr[i].set_title(f"Grasp pose top {i + 1}/{n}") f.show() - -# class GraspServer(polygrasp_pb2_grpc.GraspServer): -# def _get_grasps(self, pcd: o3d.geometry.PointCloud) -> np.ndarray: -# raise NotImplementedError - -# def GetGrasps( -# self, request_iterator: Iterator[polygrasp_pb2.PointCloud], context -# ) -> Iterator[polygrasp_pb2.GraspGroup]: -# raise NotImplementedError - - -# class GraspClient: -# def get_grasps(pcd: o3d.geometry.PointCloud) -> np.ndarray: -# raise NotImplementedError - - -# def serve(server_impl: GraspServer, port=50053, max_workers=10): -# server = grpc.server(futures.ThreadPoolExecutor(max_workers=max_workers)) -# polygrasp_pb2_grpc.add_GraspServerServicer_to_server(server_impl, server) -# server.add_insecure_port(f"[::]:{port}") -# log.info(f"=== Starting server... ===") -# server.start() -# log.info(f"=== Done. Server running at port {port}. ===") -# server.wait_for_termination() diff --git a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py index c94415953f..c50af6f57e 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py @@ -1,29 +1,17 @@ -from typing import Iterator, List -import logging -from concurrent import futures -import functools +from typing import List import numpy as np import open3d as o3d -import grpc -from polygrasp import polygrasp_pb2 -from polygrasp import polygrasp_pb2_grpc import pyrealsense2 -log = logging.getLogger(__name__) - - -class PointCloudServer(polygrasp_pb2_grpc.PointCloudServer): - def GetPointcloud(self, request_iterator: Iterator[polygrasp_pb2.Image], context) -> Iterator[polygrasp_pb2.PointCloud]: - raise NotImplementedError - - def SegmentPointcloud(self, request_iterator: Iterator[polygrasp_pb2.PointCloud], context) -> Iterator[polygrasp_pb2.ObjectMask]: - raise NotImplementedError - class PointCloudClient: - def __init__(self, camera_intrinsics: List[pyrealsense2.pyrealsense2.intrinsics], camera_extrinsics: np.ndarray): + def __init__( + self, + camera_intrinsics: List[pyrealsense2.pyrealsense2.intrinsics], + camera_extrinsics: np.ndarray, + ): assert len(camera_intrinsics) == len(camera_extrinsics) self.n_cams = len(camera_intrinsics) @@ -49,7 +37,9 @@ def __init__(self, camera_intrinsics: List[pyrealsense2.pyrealsense2.intrinsics] def get_pcd(self, rgbds: np.ndarray) -> o3d.geometry.PointCloud: scene_pcd = o3d.geometry.PointCloud() - for rgbd, intrinsic, transform in zip(rgbds, self.o3_intrinsics, self.extrinsic_transforms): + for rgbd, intrinsic, transform in zip( + rgbds, self.o3_intrinsics, self.extrinsic_transforms + ): # The specific casting here seems to be very important, even though # rgbd should already be in np.uint16 type... img = rgbd[:, :, :3].astype(np.uint8) @@ -58,27 +48,17 @@ def get_pcd(self, rgbds: np.ndarray) -> o3d.geometry.PointCloud: o3d_img = o3d.cuda.pybind.geometry.Image(img) o3d_depth = o3d.cuda.pybind.geometry.Image(depth) - rgbd_image = o3d.geometry.RGBDImage.create_from_color_and_depth(o3d_img,o3d_depth,convert_rgb_to_intensity=False,) + rgbd_image = o3d.geometry.RGBDImage.create_from_color_and_depth( + o3d_img, + o3d_depth, + convert_rgb_to_intensity=False, + ) pcd = o3d.geometry.PointCloud.create_from_rgbd_image(rgbd_image, intrinsic) pcd.transform(transform) scene_pcd += pcd - # o3d.visualization.draw_geometries([scene_pcd]) return scene_pcd def segment_pcd(self): raise NotImplementedError - -def serve(port=50054, max_workers=10, *args, **kwargs): - server = grpc.server(futures.ThreadPoolExecutor(max_workers=max_workers)) - polygrasp_pb2_grpc.add_PointCloudServerServicer_to_server(PointCloudServer(*args, **kwargs), server) - server.add_insecure_port(f"[::]:{port}") - log.info(f"=== Starting server... ===") - server.start() - log.info(f"=== Done. Server running at port {port}. ===") - server.wait_for_termination() - - -if __name__ == "__main__": - serve() diff --git a/perception/sandbox/polygrasp/src/polygrasp/polygrasp.proto b/perception/sandbox/polygrasp/src/polygrasp/polygrasp.proto deleted file mode 100644 index cf4e40f61e..0000000000 --- a/perception/sandbox/polygrasp/src/polygrasp/polygrasp.proto +++ /dev/null @@ -1,30 +0,0 @@ -syntax = "proto3"; - -package polygrasp; - -service GraspServer { - rpc GetGrasps(stream PointCloud) returns (stream GraspGroup) {} -} - -service PointCloudServer { - rpc GetPointcloud(stream Image) returns (stream PointCloud) {} - rpc SegmentPointcloud(stream PointCloud) returns (stream ObjectMask) {} -} - -message Image { - bytes rgbd = 1; -} - -message ObjectMask { - int64 id = 1; - bytes mask = 2; -} - -message PointCloud { - bytes pcd = 1; - bytes color = 2; -} - -message GraspGroup { - bytes grasp_group_array = 1; -} diff --git a/perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2.py b/perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2.py deleted file mode 100644 index 9975579de3..0000000000 --- a/perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2.py +++ /dev/null @@ -1,70 +0,0 @@ -# -*- coding: utf-8 -*- -# Generated by the protocol buffer compiler. DO NOT EDIT! -# source: polygrasp/polygrasp.proto -"""Generated protocol buffer code.""" -from google.protobuf import descriptor as _descriptor -from google.protobuf import descriptor_pool as _descriptor_pool -from google.protobuf import message as _message -from google.protobuf import reflection as _reflection -from google.protobuf import symbol_database as _symbol_database -# @@protoc_insertion_point(imports) - -_sym_db = _symbol_database.Default() - - - - -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x19polygrasp/polygrasp.proto\x12\tpolygrasp\"\x15\n\x05Image\x12\x0c\n\x04rgbd\x18\x01 \x01(\x0c\"&\n\nObjectMask\x12\n\n\x02id\x18\x01 \x01(\x03\x12\x0c\n\x04mask\x18\x02 \x01(\x0c\"(\n\nPointCloud\x12\x0b\n\x03pcd\x18\x01 \x01(\x0c\x12\r\n\x05\x63olor\x18\x02 \x01(\x0c\"\'\n\nGraspGroup\x12\x19\n\x11grasp_group_array\x18\x01 \x01(\x0c\x32N\n\x0bGraspServer\x12?\n\tGetGrasps\x12\x15.polygrasp.PointCloud\x1a\x15.polygrasp.GraspGroup\"\x00(\x01\x30\x01\x32\x9b\x01\n\x10PointCloudServer\x12>\n\rGetPointcloud\x12\x10.polygrasp.Image\x1a\x15.polygrasp.PointCloud\"\x00(\x01\x30\x01\x12G\n\x11SegmentPointcloud\x12\x15.polygrasp.PointCloud\x1a\x15.polygrasp.ObjectMask\"\x00(\x01\x30\x01\x62\x06proto3') - - - -_IMAGE = DESCRIPTOR.message_types_by_name['Image'] -_OBJECTMASK = DESCRIPTOR.message_types_by_name['ObjectMask'] -_POINTCLOUD = DESCRIPTOR.message_types_by_name['PointCloud'] -_GRASPGROUP = DESCRIPTOR.message_types_by_name['GraspGroup'] -Image = _reflection.GeneratedProtocolMessageType('Image', (_message.Message,), { - 'DESCRIPTOR' : _IMAGE, - '__module__' : 'polygrasp.polygrasp_pb2' - # @@protoc_insertion_point(class_scope:polygrasp.Image) - }) -_sym_db.RegisterMessage(Image) - -ObjectMask = _reflection.GeneratedProtocolMessageType('ObjectMask', (_message.Message,), { - 'DESCRIPTOR' : _OBJECTMASK, - '__module__' : 'polygrasp.polygrasp_pb2' - # @@protoc_insertion_point(class_scope:polygrasp.ObjectMask) - }) -_sym_db.RegisterMessage(ObjectMask) - -PointCloud = _reflection.GeneratedProtocolMessageType('PointCloud', (_message.Message,), { - 'DESCRIPTOR' : _POINTCLOUD, - '__module__' : 'polygrasp.polygrasp_pb2' - # @@protoc_insertion_point(class_scope:polygrasp.PointCloud) - }) -_sym_db.RegisterMessage(PointCloud) - -GraspGroup = _reflection.GeneratedProtocolMessageType('GraspGroup', (_message.Message,), { - 'DESCRIPTOR' : _GRASPGROUP, - '__module__' : 'polygrasp.polygrasp_pb2' - # @@protoc_insertion_point(class_scope:polygrasp.GraspGroup) - }) -_sym_db.RegisterMessage(GraspGroup) - -_GRASPSERVER = DESCRIPTOR.services_by_name['GraspServer'] -_POINTCLOUDSERVER = DESCRIPTOR.services_by_name['PointCloudServer'] -if _descriptor._USE_C_DESCRIPTORS == False: - - DESCRIPTOR._options = None - _IMAGE._serialized_start=40 - _IMAGE._serialized_end=61 - _OBJECTMASK._serialized_start=63 - _OBJECTMASK._serialized_end=101 - _POINTCLOUD._serialized_start=103 - _POINTCLOUD._serialized_end=143 - _GRASPGROUP._serialized_start=145 - _GRASPGROUP._serialized_end=184 - _GRASPSERVER._serialized_start=186 - _GRASPSERVER._serialized_end=264 - _POINTCLOUDSERVER._serialized_start=267 - _POINTCLOUDSERVER._serialized_end=422 -# @@protoc_insertion_point(module_scope) diff --git a/perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2_grpc.py b/perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2_grpc.py deleted file mode 100644 index a9f0d07c2d..0000000000 --- a/perception/sandbox/polygrasp/src/polygrasp/polygrasp_pb2_grpc.py +++ /dev/null @@ -1,160 +0,0 @@ -# Generated by the gRPC Python protocol compiler plugin. DO NOT EDIT! -"""Client and server classes corresponding to protobuf-defined services.""" -import grpc - -from polygrasp import polygrasp_pb2 as polygrasp_dot_polygrasp__pb2 - - -class GraspServerStub(object): - """Missing associated documentation comment in .proto file.""" - - def __init__(self, channel): - """Constructor. - - Args: - channel: A grpc.Channel. - """ - self.GetGrasps = channel.stream_stream( - '/polygrasp.GraspServer/GetGrasps', - request_serializer=polygrasp_dot_polygrasp__pb2.PointCloud.SerializeToString, - response_deserializer=polygrasp_dot_polygrasp__pb2.GraspGroup.FromString, - ) - - -class GraspServerServicer(object): - """Missing associated documentation comment in .proto file.""" - - def GetGrasps(self, request_iterator, context): - """Missing associated documentation comment in .proto file.""" - context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') - - -def add_GraspServerServicer_to_server(servicer, server): - rpc_method_handlers = { - 'GetGrasps': grpc.stream_stream_rpc_method_handler( - servicer.GetGrasps, - request_deserializer=polygrasp_dot_polygrasp__pb2.PointCloud.FromString, - response_serializer=polygrasp_dot_polygrasp__pb2.GraspGroup.SerializeToString, - ), - } - generic_handler = grpc.method_handlers_generic_handler( - 'polygrasp.GraspServer', rpc_method_handlers) - server.add_generic_rpc_handlers((generic_handler,)) - - - # This class is part of an EXPERIMENTAL API. -class GraspServer(object): - """Missing associated documentation comment in .proto file.""" - - @staticmethod - def GetGrasps(request_iterator, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.stream_stream(request_iterator, target, '/polygrasp.GraspServer/GetGrasps', - polygrasp_dot_polygrasp__pb2.PointCloud.SerializeToString, - polygrasp_dot_polygrasp__pb2.GraspGroup.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) - - -class PointCloudServerStub(object): - """Missing associated documentation comment in .proto file.""" - - def __init__(self, channel): - """Constructor. - - Args: - channel: A grpc.Channel. - """ - self.GetPointcloud = channel.stream_stream( - '/polygrasp.PointCloudServer/GetPointcloud', - request_serializer=polygrasp_dot_polygrasp__pb2.Image.SerializeToString, - response_deserializer=polygrasp_dot_polygrasp__pb2.PointCloud.FromString, - ) - self.SegmentPointcloud = channel.stream_stream( - '/polygrasp.PointCloudServer/SegmentPointcloud', - request_serializer=polygrasp_dot_polygrasp__pb2.PointCloud.SerializeToString, - response_deserializer=polygrasp_dot_polygrasp__pb2.ObjectMask.FromString, - ) - - -class PointCloudServerServicer(object): - """Missing associated documentation comment in .proto file.""" - - def GetPointcloud(self, request_iterator, context): - """Missing associated documentation comment in .proto file.""" - context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') - - def SegmentPointcloud(self, request_iterator, context): - """Missing associated documentation comment in .proto file.""" - context.set_code(grpc.StatusCode.UNIMPLEMENTED) - context.set_details('Method not implemented!') - raise NotImplementedError('Method not implemented!') - - -def add_PointCloudServerServicer_to_server(servicer, server): - rpc_method_handlers = { - 'GetPointcloud': grpc.stream_stream_rpc_method_handler( - servicer.GetPointcloud, - request_deserializer=polygrasp_dot_polygrasp__pb2.Image.FromString, - response_serializer=polygrasp_dot_polygrasp__pb2.PointCloud.SerializeToString, - ), - 'SegmentPointcloud': grpc.stream_stream_rpc_method_handler( - servicer.SegmentPointcloud, - request_deserializer=polygrasp_dot_polygrasp__pb2.PointCloud.FromString, - response_serializer=polygrasp_dot_polygrasp__pb2.ObjectMask.SerializeToString, - ), - } - generic_handler = grpc.method_handlers_generic_handler( - 'polygrasp.PointCloudServer', rpc_method_handlers) - server.add_generic_rpc_handlers((generic_handler,)) - - - # This class is part of an EXPERIMENTAL API. -class PointCloudServer(object): - """Missing associated documentation comment in .proto file.""" - - @staticmethod - def GetPointcloud(request_iterator, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.stream_stream(request_iterator, target, '/polygrasp.PointCloudServer/GetPointcloud', - polygrasp_dot_polygrasp__pb2.Image.SerializeToString, - polygrasp_dot_polygrasp__pb2.PointCloud.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) - - @staticmethod - def SegmentPointcloud(request_iterator, - target, - options=(), - channel_credentials=None, - call_credentials=None, - insecure=False, - compression=None, - wait_for_ready=None, - timeout=None, - metadata=None): - return grpc.experimental.stream_stream(request_iterator, target, '/polygrasp.PointCloudServer/SegmentPointcloud', - polygrasp_dot_polygrasp__pb2.PointCloud.SerializeToString, - polygrasp_dot_polygrasp__pb2.ObjectMask.FromString, - options, channel_credentials, - insecure, call_credentials, compression, wait_for_ready, timeout, metadata) diff --git a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py index 86a672148c..1b9c57cb46 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py +++ b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py @@ -1,13 +1,87 @@ """polymetis.RobotInterface combined with GripperInterface, with an additional `grasp` method.""" +import numpy as np +from scipy.spatial.transform import Rotation as R +import torch +import open3d as o3d + +import hydra +import graspnetAPI import polymetis + +def compute_des_pose(best_grasp): + grasp_point = best_grasp.translation + + grasp_approach_delta = best_grasp.rotation_matrix @ np.array([-0.3, 0.0, 0]) + grasp_approach_delta_plus = best_grasp.rotation_matrix @ np.array( + [-0.3, 0.1, 0] + ) + grasp_approach_delta_minus = best_grasp.rotation_matrix @ np.array( + [-0.3, -0.1, 0] + ) + bx = -grasp_approach_delta + by = grasp_approach_delta_plus - grasp_approach_delta_minus + bx = bx / np.linalg.norm(bx) + by = by / np.linalg.norm(by) + bz = np.cross(bx, by) + plane_rot = R.from_matrix(np.vstack([bx, by, bz]).T) + + des_ori = ( + plane_rot + * R.from_euler("x", 90, degrees=True) + * R.from_euler("y", 90, degrees=True) + ) + des_ori_quat = des_ori.as_quat() + + return grasp_point, grasp_approach_delta, des_ori_quat + +def grasp_to_pose(grasp: graspnetAPI.Grasp): + return grasp.translation, R.from_matrix(grasp.rotation_matrix).as_quat() + class GraspingRobotInterface(polymetis.RobotInterface): def __init__(self, gripper: polymetis.GripperInterface, *args, **kwargs): - self.gripper = gripper + super().__init__(*args, **kwargs) + self.gripper = hydra.utils.instantiate(gripper) + + def gripper_open(self): + self.gripper.goto(1, 1, 1) + + def gripper_close(self): + self.gripper.goto(0, 1, 1) + + def _move_until_success(self, position, orientation, time_to_go, max_attempts=5): + states = [] + for _ in range(max_attempts): + states += self.move_to_ee_pose(position=position, orientation=orientation, time_to_go=time_to_go) + curr_ee_pos, curr_ee_ori = self.get_ee_pose() + + print(f"Dist to goal: {torch.linalg.norm(curr_ee_pos - position)}") + + if torch.linalg.norm(curr_ee_pos - position) < 0.25: # TODO: orientation diff + break + return states + - def select_grasp(self): - raise NotImplementedError + def select_grasp(self, grasps: graspnetAPI.GraspGroup, scene_pcd: o3d.geometry.PointCloud) -> graspnetAPI.Grasp: + # TODO: do something smarter than this + return grasps[int(input("Choose grasp index (1-indexed):")) - 1] + + def grasp(self, grasp: graspnetAPI.Grasp): + states = [] + grasp_point, grasp_approach_delta, des_ori_quat = compute_des_pose(grasp) + + offset = np.array([0.1, 0, 0.1]) + + self.gripper_open() + states += self._move_until_success(position=torch.Tensor(grasp_point + grasp_approach_delta * 2.0 + offset), orientation=torch.Tensor(des_ori_quat), time_to_go=3) + + grip_ee_pos = torch.Tensor(grasp_point + grasp_approach_delta * 0.8 + offset) + + states += self._move_until_success(position=grip_ee_pos, orientation=torch.Tensor(des_ori_quat), time_to_go=3) + + self.gripper_close() + + success = self.gripper.get_state().width > 0.001 - def grasp(self): - raise NotImplementedError + return states, success diff --git a/perception/sandbox/polygrasp/src/polygrasp/serdes.py b/perception/sandbox/polygrasp/src/polygrasp/serdes.py index b1cf44e12c..d38f47440b 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/serdes.py +++ b/perception/sandbox/polygrasp/src/polygrasp/serdes.py @@ -66,20 +66,10 @@ def capnp_to_pcd(blob): def grasp_group_to_capnp(grasp_group: graspnetAPI.grasp.GraspGroup): capnp_gg = std_msgs.ByteMultiArray() capnp_gg.data = grasp_group_to_bytes(grasp_group) - # capnp_gg = geometry_msgs.PoseArray() - # capnp_poses = capnp_gg.init("poses", len(grasp_group)) - # for pose, grasp in zip(capnp_poses, grasp_group): - # x, y, z = grasp.translation.tolist() - # pose.position = geometry_msgs.Point(x=x, y=y, z=z) - # x, y, z, w = R.from_matrix(grasp.rotation_matrix).as_quat().tolist() - # pose.orientation = geometry_msgs.Quaternion(x=x, y=y, z=z, w=w) return capnp_gg def capnp_to_grasp_group(blob): capnp_gg = std_msgs.ByteMultiArray.from_bytes(blob) - # for pose in capnp_gg.poses: - # xyz = pose.position - gg = bytes_to_grasp_group(capnp_gg.data) return gg diff --git a/perception/sandbox/polygrasp/src/polygrasp/utils.py b/perception/sandbox/polygrasp/src/polygrasp/utils.py deleted file mode 100644 index e69de29bb2..0000000000 From d82b011c2bf67cbf4bd971f615f325bc1b407cae Mon Sep 17 00:00:00 2001 From: 1heart Date: Mon, 18 Apr 2022 19:12:05 -0700 Subject: [PATCH 16/69] Camera pubsub, mrp msetup --- .../sandbox/polygrasp/conf/intrinsics.json | 1 + .../sandbox/polygrasp/conf/run_grasp.yaml | 6 +- perception/sandbox/polygrasp/msetup.py | 14 ++++- .../sandbox/polygrasp/scripts/run_grasp.py | 23 ++++--- .../polygrasp/src/polygrasp/cam_pub_sub.py | 62 +++++++++++++++++++ .../polygrasp/src/polygrasp/grasp_rpc.py | 2 +- .../src/polygrasp/robot_interface.py | 37 ++++++----- .../sandbox/polygrasp/src/polygrasp/serdes.py | 12 ++-- 8 files changed, 118 insertions(+), 39 deletions(-) create mode 100644 perception/sandbox/polygrasp/conf/intrinsics.json create mode 100644 perception/sandbox/polygrasp/src/polygrasp/cam_pub_sub.py diff --git a/perception/sandbox/polygrasp/conf/intrinsics.json b/perception/sandbox/polygrasp/conf/intrinsics.json new file mode 100644 index 0000000000..12a1c91c53 --- /dev/null +++ b/perception/sandbox/polygrasp/conf/intrinsics.json @@ -0,0 +1 @@ +[{"coeffs": [0.0, 0.0, 0.0, 0.0, 0.0], "fx": 616.762939453125, "fy": 616.74951171875, "height": 480, "ppx": 329.696044921875, "ppy": 234.45372009277344, "width": 640}, {"coeffs": [0.0, 0.0, 0.0, 0.0, 0.0], "fx": 617.8477783203125, "fy": 618.071044921875, "height": 480, "ppx": 331.7496032714844, "ppy": 248.904541015625, "width": 640}, {"coeffs": [0.0, 0.0, 0.0, 0.0, 0.0], "fx": 614.17041015625, "fy": 614.19189453125, "height": 480, "ppx": 326.27642822265625, "ppy": 236.0000762939453, "width": 640}] \ No newline at end of file diff --git a/perception/sandbox/polygrasp/conf/run_grasp.yaml b/perception/sandbox/polygrasp/conf/run_grasp.yaml index ea93a6bc71..a566800a59 100644 --- a/perception/sandbox/polygrasp/conf/run_grasp.yaml +++ b/perception/sandbox/polygrasp/conf/run_grasp.yaml @@ -5,5 +5,9 @@ robot: gripper: _target_: polymetis.GripperInterface -camera_extrinsics_path: ../eyehandcal/calibration.json +camera_sub: + _target_: polygrasp.cam_pub_sub.CameraSubscriber + intrinsics_file: conf/intrinsics.json + extrinsics_file: ../eyehandcal/calibration.json + view_json_path: conf/o3d_view.json diff --git a/perception/sandbox/polygrasp/msetup.py b/perception/sandbox/polygrasp/msetup.py index 9ee570c467..e2acf91d69 100644 --- a/perception/sandbox/polygrasp/msetup.py +++ b/perception/sandbox/polygrasp/msetup.py @@ -2,15 +2,23 @@ mrp.process( name="grasp_server", + runtime=mrp.Conda( + run_command=["python", "-m", "graspnet_baseline.mrp_wrapper"], + use_named_env="graspnet-baseline", + ), +) + +mrp.process( + name="cam_pub", runtime=mrp.Host( - run_command=["python", "src/polygrasp/grasp_rpc.py"], + run_command=["python", "-m", "polygrasp.cam_pub_sub"], ), ) mrp.process( - name="pointcloud_server", + name="gripper_server", runtime=mrp.Host( - run_command=["python", "src/polygrasp/pointcloud_rpc.py"], + run_command=["launch_gripper.py", "gripper=robotiq_2f", "gripper.comport=/dev/ttyUSB1"], ), ) diff --git a/perception/sandbox/polygrasp/scripts/run_grasp.py b/perception/sandbox/polygrasp/scripts/run_grasp.py index d08fab22ba..f3d16d41d4 100644 --- a/perception/sandbox/polygrasp/scripts/run_grasp.py +++ b/perception/sandbox/polygrasp/scripts/run_grasp.py @@ -5,13 +5,8 @@ """ import random -import json import hydra -import torch - -from realsense_wrapper import RealsenseAPI - from polygrasp.pointcloud_rpc import PointCloudClient from polygrasp.grasp_rpc import GraspClient @@ -21,13 +16,14 @@ def main(cfg): # Initialize robot & gripper robot = hydra.utils.instantiate(cfg.robot) robot.gripper_open() - robot.go_home() + # robot.go_home() # Initialize cameras - cameras = RealsenseAPI() + cfg.camera_sub.intrinsics_file = hydra.utils.to_absolute_path(cfg.camera_sub.intrinsics_file) + cfg.camera_sub.extrinsics_file = hydra.utils.to_absolute_path(cfg.camera_sub.extrinsics_file) + cameras = hydra.utils.instantiate(cfg.camera_sub) camera_intrinsics = cameras.get_intrinsics() - with open(hydra.utils.to_absolute_path(cfg.camera_extrinsics_path), "r") as f: - camera_extrinsics = json.load(f) + camera_extrinsics = cameras.get_extrinsics() # Connect to grasp candidate selection and pointcloud processor pcd_client = PointCloudClient(camera_intrinsics, camera_extrinsics) @@ -43,7 +39,9 @@ def main(cfg): scene_pcd = pcd_client.get_pcd(rgbd) grasp_group = grasp_client.get_grasps(scene_pcd) - grasp_client.visualize_grasp(scene_pcd, grasp_group, render=False, save_view=False, plot=True) + grasp_client.visualize_grasp( + scene_pcd, grasp_group, render=False, save_view=False, plot=True + ) # # Get grasps per object # obj_to_pcd = pcd_client.segment_pcd(scene_pcd) @@ -59,8 +57,8 @@ def main(cfg): chosen_grasp = robot.select_grasp(curr_grasps, scene_pcd) # Execute grasp - traj, success = robot.grasp(chosen_grasp) - print(f"Grasp success: {success}") + # traj, success = robot.grasp(chosen_grasp) + # print(f"Grasp success: {success}") # if success: # print(f"Moving end-effector up and down") @@ -68,5 +66,6 @@ def main(cfg): # robot.move_to_ee_pose(torch.Tensor([0, 0, 0.1]), delta=True) # robot.move_to_ee_pose(torch.Tensor([0, 0, -0.1]), delta=True) + if __name__ == "__main__": main() diff --git a/perception/sandbox/polygrasp/src/polygrasp/cam_pub_sub.py b/perception/sandbox/polygrasp/src/polygrasp/cam_pub_sub.py new file mode 100644 index 0000000000..0b90f47fd2 --- /dev/null +++ b/perception/sandbox/polygrasp/src/polygrasp/cam_pub_sub.py @@ -0,0 +1,62 @@ +import logging +import json +from types import SimpleNamespace + +import a0 +import realsense_wrapper +from polygrasp import serdes + +log = logging.getLogger(__name__) +topic = "cams/rgbd" + + +class CameraSubscriber: + def __init__(self, intrinsics_file, extrinsics_file): + with open(intrinsics_file, "r") as f: + intrinsics_json = json.load(f) + self.intrinsics = [SimpleNamespace(**d) for d in intrinsics_json] + + with open(extrinsics_file, "r") as f: + self.extrinsics = json.load(f) + + self.sub = a0.SubscriberSync(a0.PubSubTopic(topic), a0.INIT_MOST_RECENT) + + def get_intrinsics(self): + return self.intrinsics + + def get_extrinsics(self): + return self.extrinsics + + def get_rgbd(self): + return serdes.bytes_to_np(self.sub.read().payload) + + +if __name__ == "__main__": + import argparse + + parser = argparse.ArgumentParser() + parser.add_argument( + "--intrinsics", + type=str, + default="conf/intrinsics.json", + help="JSON file to overwrite with current intrinsics.", + ) + args = parser.parse_args() + cameras = realsense_wrapper.RealsenseAPI() + + intrinsics = cameras.get_intrinsics() + intrinsics_py = [ + dict( + coeffs=x.coeffs, fx=x.fx, fy=x.fy, height=x.height, ppx=x.ppx, ppy=x.ppy, width=x.width + ) + for x in intrinsics + ] + with open(args.intrinsics, "w") as f: + json.dump(intrinsics_py, f) + + rgbd_pub = a0.Publisher(topic) + + log.info(f"Starting camera logger with {cameras.get_num_cameras()} cameras...") + while True: + img_bytes = serdes.np_to_bytes(cameras.get_rgbd()) + rgbd_pub.pub(a0.Packet(img_bytes)) diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py index 49d8da47c1..8439382842 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py @@ -111,7 +111,7 @@ def visualize_grasp( log.info("Plotting with matplotlib...") f, axarr = plt.subplots(1, n, figsize=(n * 4.5, 3)) for i in range(n): - axarr[i].imshow(grasp_images[i], interpolation='nearest', aspect='auto') + axarr[i].imshow(grasp_images[i], interpolation="nearest", aspect="auto") axarr[i].axis("off") axarr[i].set_title(f"Grasp pose top {i + 1}/{n}") f.show() diff --git a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py index 1b9c57cb46..ad58ff1094 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py +++ b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py @@ -14,12 +14,8 @@ def compute_des_pose(best_grasp): grasp_point = best_grasp.translation grasp_approach_delta = best_grasp.rotation_matrix @ np.array([-0.3, 0.0, 0]) - grasp_approach_delta_plus = best_grasp.rotation_matrix @ np.array( - [-0.3, 0.1, 0] - ) - grasp_approach_delta_minus = best_grasp.rotation_matrix @ np.array( - [-0.3, -0.1, 0] - ) + grasp_approach_delta_plus = best_grasp.rotation_matrix @ np.array([-0.3, 0.1, 0]) + grasp_approach_delta_minus = best_grasp.rotation_matrix @ np.array([-0.3, -0.1, 0]) bx = -grasp_approach_delta by = grasp_approach_delta_plus - grasp_approach_delta_minus bx = bx / np.linalg.norm(bx) @@ -27,18 +23,16 @@ def compute_des_pose(best_grasp): bz = np.cross(bx, by) plane_rot = R.from_matrix(np.vstack([bx, by, bz]).T) - des_ori = ( - plane_rot - * R.from_euler("x", 90, degrees=True) - * R.from_euler("y", 90, degrees=True) - ) + des_ori = plane_rot * R.from_euler("x", 90, degrees=True) * R.from_euler("y", 90, degrees=True) des_ori_quat = des_ori.as_quat() return grasp_point, grasp_approach_delta, des_ori_quat + def grasp_to_pose(grasp: graspnetAPI.Grasp): return grasp.translation, R.from_matrix(grasp.rotation_matrix).as_quat() + class GraspingRobotInterface(polymetis.RobotInterface): def __init__(self, gripper: polymetis.GripperInterface, *args, **kwargs): super().__init__(*args, **kwargs) @@ -49,11 +43,13 @@ def gripper_open(self): def gripper_close(self): self.gripper.goto(0, 1, 1) - + def _move_until_success(self, position, orientation, time_to_go, max_attempts=5): states = [] for _ in range(max_attempts): - states += self.move_to_ee_pose(position=position, orientation=orientation, time_to_go=time_to_go) + states += self.move_to_ee_pose( + position=position, orientation=orientation, time_to_go=time_to_go + ) curr_ee_pos, curr_ee_ori = self.get_ee_pose() print(f"Dist to goal: {torch.linalg.norm(curr_ee_pos - position)}") @@ -62,8 +58,9 @@ def _move_until_success(self, position, orientation, time_to_go, max_attempts=5) break return states - - def select_grasp(self, grasps: graspnetAPI.GraspGroup, scene_pcd: o3d.geometry.PointCloud) -> graspnetAPI.Grasp: + def select_grasp( + self, grasps: graspnetAPI.GraspGroup, scene_pcd: o3d.geometry.PointCloud + ) -> graspnetAPI.Grasp: # TODO: do something smarter than this return grasps[int(input("Choose grasp index (1-indexed):")) - 1] @@ -74,11 +71,17 @@ def grasp(self, grasp: graspnetAPI.Grasp): offset = np.array([0.1, 0, 0.1]) self.gripper_open() - states += self._move_until_success(position=torch.Tensor(grasp_point + grasp_approach_delta * 2.0 + offset), orientation=torch.Tensor(des_ori_quat), time_to_go=3) + states += self._move_until_success( + position=torch.Tensor(grasp_point + grasp_approach_delta * 2.0 + offset), + orientation=torch.Tensor(des_ori_quat), + time_to_go=3, + ) grip_ee_pos = torch.Tensor(grasp_point + grasp_approach_delta * 0.8 + offset) - states += self._move_until_success(position=grip_ee_pos, orientation=torch.Tensor(des_ori_quat), time_to_go=3) + states += self._move_until_success( + position=grip_ee_pos, orientation=torch.Tensor(des_ori_quat), time_to_go=3 + ) self.gripper_close() diff --git a/perception/sandbox/polygrasp/src/polygrasp/serdes.py b/perception/sandbox/polygrasp/src/polygrasp/serdes.py index d38f47440b..675cc417d7 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/serdes.py +++ b/perception/sandbox/polygrasp/src/polygrasp/serdes.py @@ -1,8 +1,6 @@ import numpy as np -from scipy.spatial.transform import Rotation as R import open3d as o3d import fairomsg -import capnp import io import numpy as np @@ -15,6 +13,7 @@ """Byte conversions""" + def np_to_bytes(arr: np.ndarray): with io.BytesIO() as f: np.save(f, arr) @@ -44,30 +43,33 @@ def open3d_pcd_to_bytes(cloud: open3d.geometry.PointCloud): def bytes_to_open3d_pcd(arr_bytes: bytes): arr = bytes_to_np(arr_bytes) - result = open3d.geometry.PointCloud( - open3d.cuda.pybind.utility.Vector3dVector(arr[:, :3]) - ) + result = open3d.geometry.PointCloud(open3d.cuda.pybind.utility.Vector3dVector(arr[:, :3])) if arr.shape[1] == 6: result.colors = open3d.cuda.pybind.utility.Vector3dVector(arr[:, 3:]) return result + """Capnp conversions""" + def pcd_to_capnp(pcd: o3d.geometry.PointCloud): result = sensor_msgs.PointCloud2() result.data = open3d_pcd_to_bytes(pcd) return result + def capnp_to_pcd(blob): capnp_pcd = sensor_msgs.PointCloud2.from_bytes(blob) return bytes_to_open3d_pcd(capnp_pcd.data) + def grasp_group_to_capnp(grasp_group: graspnetAPI.grasp.GraspGroup): capnp_gg = std_msgs.ByteMultiArray() capnp_gg.data = grasp_group_to_bytes(grasp_group) return capnp_gg + def capnp_to_grasp_group(blob): capnp_gg = std_msgs.ByteMultiArray.from_bytes(blob) From 52770711dfde69bc76d42588b4036bfc05638bd7 Mon Sep 17 00:00:00 2001 From: Yixin Lin <1heart@users.noreply.github.com> Date: Tue, 19 Apr 2022 10:17:38 -0400 Subject: [PATCH 17/69] Update README.md --- perception/sandbox/polygrasp/README.md | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/perception/sandbox/polygrasp/README.md b/perception/sandbox/polygrasp/README.md index b5007ef86a..f1b7ce6598 100644 --- a/perception/sandbox/polygrasp/README.md +++ b/perception/sandbox/polygrasp/README.md @@ -6,14 +6,3 @@ pip install ../../realsense_driver pip install -e . ``` - -## Development - -### Recompiling grasping gRPC server - -```bash -# from root directory -python -m grpc_tools.protoc -I src --python_out=src --grpc_python_out=src polygrasp/polygrasp.proto -``` - -Note that it's important to point the arguments of `-I`, `--python_out`, `grpc_python_out` to `.` so that the `.proto` argument uses the full directory structure instead of attempting to import the `_pb2` file without relative imports, as described in [this comment](https://github.com/grpc/grpc/issues/9575#issuecomment-293934506). From 7ea2eb1f953ba403f96a9de0c7ba1b6406e9845e Mon Sep 17 00:00:00 2001 From: 1heart Date: Tue, 26 Apr 2022 14:25:09 -0700 Subject: [PATCH 18/69] Prev cal --- perception/sandbox/eyehandcal/calibration.json | 2 +- perception/sandbox/eyehandcal/calibration_points.json | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/sandbox/eyehandcal/calibration.json b/perception/sandbox/eyehandcal/calibration.json index f04ca720b0..aed0bf136e 100644 --- a/perception/sandbox/eyehandcal/calibration.json +++ b/perception/sandbox/eyehandcal/calibration.json @@ -1 +1 @@ -[{"camera_base_ori": [[0.26409044817941857, 0.825273138571934, -0.4991798092191058], [0.9525163207711836, -0.14183692424830754, 0.2694344921948697], [0.15155492022669972, -0.5466319910793817, -0.8235439104769516]], "camera_base_pos": [1.1291315251953709, -0.2753188179094922, 0.5569095587922862], "p_marker_ee": [0.015322587564300124, -0.038835170426504806, 0.026367184321188546]}, {"camera_base_ori": [[-0.18867848441225005, 0.7704958715146015, -0.6088813854100419], [0.9809375354448933, 0.1772251307844472, -0.07970448277063993], [0.046497108245525984, -0.6123131265924243, -0.7892468903501708]], "camera_base_pos": [1.1557640304457628, 0.014638761756131623, 0.5888482354657805], "p_marker_ee": [0.0163895039251977, -0.04061809460390124, 0.025997698827580684]}, {"camera_base_ori": [[0.14824094137531774, 0.8257732465467157, -0.5441720027600243], [0.9853957807889722, -0.07671859985098213, 0.15201780040572893], [0.08378411844407617, -0.5587600573811629, -0.8250863104984515]], "camera_base_pos": [1.1854638003698477, -0.12587317688777955, 0.5886276100325791], "p_marker_ee": [0.016426117187848647, -0.03989797101227346, 0.026216040109795787]}] \ No newline at end of file +[{"camera_base_ori": [[0.04213178249284176, 0.9485314384279372, -0.31386784355490094], [0.9975242119833627, -0.05763931980385824, -0.040288401799033556], [-0.05630594472120891, -0.3113933511274391, -0.9486115229442846]], "camera_base_pos": [1.0781682497735519, 0.052421017975615554, 0.9832355189093391], "p_marker_ee": [0.018632195341962598, -0.039411085776512485, 0.02355433363170467]}, {"camera_base_ori": [[-0.6721422222671359, 0.551274174562118, -0.4942890020085942], [0.737457383530098, 0.4387530402092783, -0.5134709117214514], [-0.0661924506476203, -0.7096425538029493, -0.7014456538530197]], "camera_base_pos": [1.074760324686018, 0.7808115202436298, 0.9024470898614998], "p_marker_ee": [0.019223176975672298, -0.04379567245313821, 0.02007640936153143]}, {"camera_base_ori": [[0.932003921776572, 0.1335116552035173, -0.33696190840792195], [0.2915238327504178, -0.8285494838674189, 0.4780372451196057], [-0.21536607144951592, -0.543765014236713, -0.8111331977921696]], "camera_base_pos": [1.0153771490133474, -0.5677143097093243, 0.9542879420150078], "p_marker_ee": [0.016083526835705207, -0.03712218067374231, 0.027612451489165347]}] \ No newline at end of file diff --git a/perception/sandbox/eyehandcal/calibration_points.json b/perception/sandbox/eyehandcal/calibration_points.json index 61c2e1cff3..9cf630d0fa 100644 --- a/perception/sandbox/eyehandcal/calibration_points.json +++ b/perception/sandbox/eyehandcal/calibration_points.json @@ -1 +1 @@ -{"xyz": [[0.7841147184371948, -0.26561641693115234, 0.237627312541008], [0.8307967782020569, 0.02608540467917919, 0.2515111565589905], [0.8506162166595459, -0.02456057071685791, 0.347420334815979], [0.8517714738845825, -0.05609707906842232, 0.4044360816478729], [0.8047099709510803, -0.2907401919364929, 0.3745661973953247], [0.8047105073928833, -0.29073861241340637, 0.37456685304641724]], "quat": [[0.8225067853927612, -0.08389443904161453, 0.4012543261051178, -0.39425790309906006], [0.6798139810562134, -0.3220716714859009, 0.6247647404670715, -0.20926488935947418], [0.5894655585289001, -0.43789276480674744, 0.6651686429977417, -0.13539202511310577]]} \ No newline at end of file +{"xyz": [[0.5875601768493652, -0.34303900599479675, 0.21053236722946167], [0.6805009245872498, -0.3463522493839264, 0.4619373381137848], [0.7666991353034973, 0.2947470247745514, 0.3151533007621765], [0.7246556878089905, 0.30977049469947815, 0.17257899045944214], [0.5803166627883911, 0.2942454218864441, 0.24886415898799896], [0.5926814675331116, 0.28984466195106506, 0.49123769998550415], [0.5296269059181213, -0.24064402282238007, 0.38130486011505127], [0.5437914133071899, -0.22014857828617096, 0.22864440083503723]], "quat": [[0.6456457376480103, -0.45364564657211304, 0.6059600114822388, -0.10079549998044968], [0.7039521932601929, -0.3740551769733429, 0.5697537660598755, -0.1997867226600647], [0.8086528182029724, -0.2923392057418823, 0.44710731506347656, -0.24640098214149475]]} \ No newline at end of file From 8a093f81d497de51dcd4586faf85c2d2883e24f6 Mon Sep 17 00:00:00 2001 From: 1heart Date: Tue, 26 Apr 2022 14:25:13 -0700 Subject: [PATCH 19/69] New cal --- perception/sandbox/eyehandcal/calibration.json | 2 +- perception/sandbox/eyehandcal/calibration_points.json | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/perception/sandbox/eyehandcal/calibration.json b/perception/sandbox/eyehandcal/calibration.json index aed0bf136e..4613e3bf46 100644 --- a/perception/sandbox/eyehandcal/calibration.json +++ b/perception/sandbox/eyehandcal/calibration.json @@ -1 +1 @@ -[{"camera_base_ori": [[0.04213178249284176, 0.9485314384279372, -0.31386784355490094], [0.9975242119833627, -0.05763931980385824, -0.040288401799033556], [-0.05630594472120891, -0.3113933511274391, -0.9486115229442846]], "camera_base_pos": [1.0781682497735519, 0.052421017975615554, 0.9832355189093391], "p_marker_ee": [0.018632195341962598, -0.039411085776512485, 0.02355433363170467]}, {"camera_base_ori": [[-0.6721422222671359, 0.551274174562118, -0.4942890020085942], [0.737457383530098, 0.4387530402092783, -0.5134709117214514], [-0.0661924506476203, -0.7096425538029493, -0.7014456538530197]], "camera_base_pos": [1.074760324686018, 0.7808115202436298, 0.9024470898614998], "p_marker_ee": [0.019223176975672298, -0.04379567245313821, 0.02007640936153143]}, {"camera_base_ori": [[0.932003921776572, 0.1335116552035173, -0.33696190840792195], [0.2915238327504178, -0.8285494838674189, 0.4780372451196057], [-0.21536607144951592, -0.543765014236713, -0.8111331977921696]], "camera_base_pos": [1.0153771490133474, -0.5677143097093243, 0.9542879420150078], "p_marker_ee": [0.016083526835705207, -0.03712218067374231, 0.027612451489165347]}] \ No newline at end of file +[{"camera_base_ori": [[-0.0008351711692040552, 0.9467041262862899, -0.3221033991773923], [0.9999876344084615, 0.0023697313594300013, 0.004372116587222594], [0.004902399339737778, -0.3220957647126033, -0.9466943988610668]], "camera_base_pos": [1.132091239302775, 0.09765527179120626, 0.7987150760861018], "p_marker_ee": [0.01538088407469198, -0.038626082221747446, 0.027503670654543382]}, {"camera_base_ori": [[-0.9837867934727511, -0.08545120494602781, -0.1576757323175443], [-0.03373994307395532, 0.9516773029445347, -0.30524076939619904], [0.17613960721532268, -0.294971867528904, -0.9391306810750794]], "camera_base_pos": [1.044620073945996, 0.978753642811283, 0.7400190717591493], "p_marker_ee": [-0.09874803603370458, -0.012452017614995134, 0.19377999347442204]}, {"camera_base_ori": [[-0.05954743351363026, 0.9652499225808887, -0.25445370918799537], [0.9981345466688237, 0.0541345562643601, -0.028229002183610033], [-0.013473303535552449, -0.25566000229924474, -0.966672867787334]], "camera_base_pos": [1.1158163442477056, -0.2854368661163418, 0.8067607259493821], "p_marker_ee": [0.014149125903098527, -0.03805976262399718, 0.026777494443228165]}] \ No newline at end of file diff --git a/perception/sandbox/eyehandcal/calibration_points.json b/perception/sandbox/eyehandcal/calibration_points.json index 9cf630d0fa..925467bf37 100644 --- a/perception/sandbox/eyehandcal/calibration_points.json +++ b/perception/sandbox/eyehandcal/calibration_points.json @@ -1 +1 @@ -{"xyz": [[0.5875601768493652, -0.34303900599479675, 0.21053236722946167], [0.6805009245872498, -0.3463522493839264, 0.4619373381137848], [0.7666991353034973, 0.2947470247745514, 0.3151533007621765], [0.7246556878089905, 0.30977049469947815, 0.17257899045944214], [0.5803166627883911, 0.2942454218864441, 0.24886415898799896], [0.5926814675331116, 0.28984466195106506, 0.49123769998550415], [0.5296269059181213, -0.24064402282238007, 0.38130486011505127], [0.5437914133071899, -0.22014857828617096, 0.22864440083503723]], "quat": [[0.6456457376480103, -0.45364564657211304, 0.6059600114822388, -0.10079549998044968], [0.7039521932601929, -0.3740551769733429, 0.5697537660598755, -0.1997867226600647], [0.8086528182029724, -0.2923392057418823, 0.44710731506347656, -0.24640098214149475]]} \ No newline at end of file +{"xyz": [[0.5908467173576355, 0.3373607397079468, 0.15122705698013306], [0.7503308057785034, 0.27825140953063965, 0.15255045890808105], [0.7250736951828003, 0.36202582716941833, 0.24055424332618713], [0.7378460168838501, -0.39358294010162354, 0.278826504945755], [0.7247983813285828, -0.3782039284706116, 0.1521162986755371], [0.6834715008735657, -0.36276400089263916, 0.20962005853652954], [0.7435363531112671, -0.3368459939956665, 0.28699222207069397]], "quat": [[0.8627303242683411, -0.11587879806756973, 0.3429616391658783, -0.3530521094799042], [0.8038111925125122, -0.3028760850429535, 0.44565656781196594, -0.252079039812088], [0.7244585156440735, -0.43292275071144104, 0.5195778012275696, -0.1333290934562683]]} \ No newline at end of file From 15e5b92177674724a7ac68ae7463fbec2aa1320c Mon Sep 17 00:00:00 2001 From: 1heart Date: Wed, 27 Apr 2022 14:21:03 -0700 Subject: [PATCH 20/69] Generally working continuous grasping with graspnet --- .../sandbox/polygrasp/conf/intrinsics.json | 2 +- perception/sandbox/polygrasp/msetup.py | 8 ++ .../sandbox/polygrasp/scripts/run_grasp.py | 125 ++++++++++++++---- .../polygrasp/src/polygrasp/grasp_rpc.py | 51 ++++--- .../polygrasp/src/polygrasp/pointcloud_rpc.py | 90 +++++++++++-- .../src/polygrasp/robot_interface.py | 42 ++++-- .../sandbox/polygrasp/src/polygrasp/serdes.py | 10 ++ 7 files changed, 267 insertions(+), 61 deletions(-) diff --git a/perception/sandbox/polygrasp/conf/intrinsics.json b/perception/sandbox/polygrasp/conf/intrinsics.json index 12a1c91c53..cad1fc3cb8 100644 --- a/perception/sandbox/polygrasp/conf/intrinsics.json +++ b/perception/sandbox/polygrasp/conf/intrinsics.json @@ -1 +1 @@ -[{"coeffs": [0.0, 0.0, 0.0, 0.0, 0.0], "fx": 616.762939453125, "fy": 616.74951171875, "height": 480, "ppx": 329.696044921875, "ppy": 234.45372009277344, "width": 640}, {"coeffs": [0.0, 0.0, 0.0, 0.0, 0.0], "fx": 617.8477783203125, "fy": 618.071044921875, "height": 480, "ppx": 331.7496032714844, "ppy": 248.904541015625, "width": 640}, {"coeffs": [0.0, 0.0, 0.0, 0.0, 0.0], "fx": 614.17041015625, "fy": 614.19189453125, "height": 480, "ppx": 326.27642822265625, "ppy": 236.0000762939453, "width": 640}] \ No newline at end of file +[{"coeffs": [0.0, 0.0, 0.0, 0.0, 0.0], "fx": 617.8477783203125, "fy": 618.071044921875, "height": 480, "ppx": 331.7496032714844, "ppy": 248.904541015625, "width": 640}, {"coeffs": [0.0, 0.0, 0.0, 0.0, 0.0], "fx": 616.762939453125, "fy": 616.74951171875, "height": 480, "ppx": 329.696044921875, "ppy": 234.45372009277344, "width": 640}, {"coeffs": [0.0, 0.0, 0.0, 0.0, 0.0], "fx": 614.17041015625, "fy": 614.19189453125, "height": 480, "ppx": 326.27642822265625, "ppy": 236.0000762939453, "width": 640}] \ No newline at end of file diff --git a/perception/sandbox/polygrasp/msetup.py b/perception/sandbox/polygrasp/msetup.py index e2acf91d69..77566fc35d 100644 --- a/perception/sandbox/polygrasp/msetup.py +++ b/perception/sandbox/polygrasp/msetup.py @@ -1,5 +1,13 @@ import mrp +mrp.process( + name="pcd_server", + runtime=mrp.Conda( + run_command=["python", "-m", "utils.mrp_wrapper"], + use_named_env="unseen-object-clustering", + ), +) + mrp.process( name="grasp_server", runtime=mrp.Conda( diff --git a/perception/sandbox/polygrasp/scripts/run_grasp.py b/perception/sandbox/polygrasp/scripts/run_grasp.py index f3d16d41d4..5d9ad02ddf 100644 --- a/perception/sandbox/polygrasp/scripts/run_grasp.py +++ b/perception/sandbox/polygrasp/scripts/run_grasp.py @@ -5,9 +5,10 @@ """ import random +import torch import hydra -from polygrasp.pointcloud_rpc import PointCloudClient +from polygrasp.pointcloud_rpc import PointCloudClient, RgbdFeaturesPointCloudClient from polygrasp.grasp_rpc import GraspClient @@ -16,7 +17,7 @@ def main(cfg): # Initialize robot & gripper robot = hydra.utils.instantiate(cfg.robot) robot.gripper_open() - # robot.go_home() + robot.go_home() # Initialize cameras cfg.camera_sub.intrinsics_file = hydra.utils.to_absolute_path(cfg.camera_sub.intrinsics_file) @@ -25,46 +26,122 @@ def main(cfg): camera_intrinsics = cameras.get_intrinsics() camera_extrinsics = cameras.get_extrinsics() + import numpy as np + # masks = np.ones([3, 480, 640]) + + masks = np.zeros([3, 480, 640]) + masks[0][70:320, 60:400] = 1 + masks[1][100:350, 300:600] = 1 + # masks[2][130:350, 240:480] = 1 + # Connect to grasp candidate selection and pointcloud processor - pcd_client = PointCloudClient(camera_intrinsics, camera_extrinsics) + pcd_client = RgbdFeaturesPointCloudClient(camera_intrinsics, camera_extrinsics, masks=masks) grasp_client = GraspClient(view_json_path=hydra.utils.to_absolute_path(cfg.view_json_path)) - num_iters = 1 + num_iters = 10 for i in range(num_iters): print(f"Grasp {i + 1} / num_iters") - # Get RGBD & pointcloud + print("Getting rgbd and pcds..") rgbd = cameras.get_rgbd() - - scene_pcd = pcd_client.get_pcd(rgbd) - grasp_group = grasp_client.get_grasps(scene_pcd) - - grasp_client.visualize_grasp( - scene_pcd, grasp_group, render=False, save_view=False, plot=True - ) - - # # Get grasps per object + rgbd_masked = rgbd * masks[:, :, :, None] + pcds = pcd_client.get_pcd(rgbd) + + # import matplotlib.pyplot as plt + # f, axarr = plt.subplots(2, 3) + # for i in range(3): + # axarr[0, i].imshow(rgbd[i, :, :, :3].astype(np.uint8)) + # axarr[1, i].imshow(rgbd_masked[i, :, :, :3].astype(np.uint8)) + # f.show() + # import pdb; pdb.set_trace() + + scene_pcd = pcds[0] + for pcd in pcds[1:]: + scene_pcd += pcd + + # import pdb; pdb.set_trace() + # Get RGBD & pointcloud + print("Segmenting image...") + labels = pcd_client.segment_img(rgbd_masked[0]) + from matplotlib import pyplot as plt + obj_to_pcd = {} + obj_to_grasps = {} + num_objs = int(labels.max()) + print(f"Number of objs: {num_objs}") + # for i in range(1, int(num_objs + 1)): + # if num_objs > 0: + # i = 1 + min_mask_size = 2000 + for i in range(1, num_objs + 1): + obj_mask = labels == i + obj_mask_size = obj_mask.sum() + if obj_mask_size < min_mask_size: + continue + + obj_masked_rgbd = rgbd[0] * obj_mask[:, :, None] + + # plt.imshow(obj_masked_rgbd[:, :, :3]) + # plt.title(f"Object {i}, mask size {obj_mask_size}") + # plt.show() + + print(f"Getting obj {i} pcd...") + pcd = pcd_client.get_pcd_i(obj_masked_rgbd, 0) + print(f"Getting obj {i} grasp...") + grasp_group = grasp_client.get_grasps(pcd) + + obj_to_pcd[i] = pcd + obj_to_grasps[i] = grasp_group + break + + # grasp_client.visualize_grasp(scene_pcd, grasp_group, plot=True) + if len(obj_to_pcd) == 0: + print(f"Failed to find any objects with mask size > {min_mask_size}!") + continue + + # import pdb; pdb.set_trace() + + # vis = grasp_client.visualize(scene_pcd, render=True) + # import pdb; pdb.set_trace() + # rgb, d, intrinsics = grasp_client.get_rgbd(vis) + + + # grasp_group = grasp_client.get_grasps(pcd) + # grasp_client.visualize_grasp( + # scene_pcd, grasp_group, render=True, save_view=False, plot=True + # ) + + # Get grasps per object # obj_to_pcd = pcd_client.segment_pcd(scene_pcd) # obj_to_grasps = {obj: grasp_client.get_grasps(pcd) for obj, pcd in obj_to_pcd.items()} - # # Pick a random object to grasp + # Pick a random object to grasp # curr_obj, curr_grasps = random.choice(list(obj_to_grasps.items())) + # curr_obj, curr_grasps = 1, obj_to_grasps[1] # print(f"Picking object with ID {curr_obj}") + curr_grasps = grasp_group # Choose a grasp for this object # TODO: scene-aware motion planning for grasps - curr_grasps = grasp_group + grasp_client.visualize_grasp(scene_pcd, curr_grasps, plot=True) chosen_grasp = robot.select_grasp(curr_grasps, scene_pcd) # Execute grasp - # traj, success = robot.grasp(chosen_grasp) - # print(f"Grasp success: {success}") - - # if success: - # print(f"Moving end-effector up and down") - # curr_pose, curr_ori = robot.get_ee_pose() - # robot.move_to_ee_pose(torch.Tensor([0, 0, 0.1]), delta=True) - # robot.move_to_ee_pose(torch.Tensor([0, 0, -0.1]), delta=True) + traj, success = robot.grasp(chosen_grasp) + print(f"Grasp success: {success}") + + if success: + print(f"Moving end-effector up") + curr_pose, curr_ori = robot.get_ee_pose() + states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0, 0.2]), orientation=curr_ori, time_to_go=3) + states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0.4, 0.2]), orientation=curr_ori, time_to_go=3) + states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0.4, 0.05]), orientation=curr_ori, time_to_go=3) + + robot.gripper_open() + curr_pose, curr_ori = robot.get_ee_pose() + states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.2]), orientation=curr_ori, time_to_go=3) + robot.go_home() + # robot.move_to_ee_pose(torch.Tensor([0, 0, 0.1]), delta=True) + # robot.move_to_ee_pose(torch.Tensor([0, 0, -0.1]), delta=True) if __name__ == "__main__": diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py index 8439382842..2c31763a96 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py @@ -50,9 +50,9 @@ def onreply(pkt): i = 1 while True: downsampled_pcd = pcd.uniform_down_sample(i) - bytes = serdes.pcd_to_capnp(downsampled_pcd).to_bytes() + bits = serdes.pcd_to_capnp(downsampled_pcd).to_bytes() if ( - len(bytes) > 8 * 1024 * 1024 + len(bits) > 8 * 1024 * 1024 ): # a0 default max msg size 16MB; make sure every msg < 1/2 of max log.warning(f"Downsampling pointcloud...") i += 1 @@ -60,26 +60,13 @@ def onreply(pkt): break if i > 1: log.warning(f"Downsampled to every {i}th point.") - self.client.send(bytes, onreply) + self.client.send(bits, onreply) while not state: pass return serdes.capnp_to_grasp_group(state.pop()) - - def visualize_grasp( - self, - scene_pcd: o3d.geometry.PointCloud, - grasp_group: graspnetAPI.GraspGroup, - n=5, - plot=False, - render=False, - save_view=False, - ) -> None: - o3d_geometries = grasp_group.to_open3d_geometry_list() - - n = min(n, len(o3d_geometries)) - log.info(f"Visualizing top {n} grasps in Open3D...") - + + def visualize(self, scene_pcd, plot=False, render=False, save_view=False): vis = o3d.visualization.Visualizer() vis.create_window() vis.add_geometry(scene_pcd, reset_bounding_box=True) @@ -98,6 +85,31 @@ def visualize_grasp( param = o3d.io.read_pinhole_camera_parameters(self.view_json_path) vis.get_view_control().convert_from_pinhole_camera_parameters(param) + return vis + + def get_rgbd(self, vis): + rgb = np.array(vis.capture_screen_float_buffer(do_render=True)) + d = np.array(vis.capture_depth_float_buffer(do_render=True)) + intrinsics = vis.get_view_control().convert_to_pinhole_camera_parameters() + + import pdb; pdb.set_trace() + + + def visualize_grasp( + self, + scene_pcd: o3d.geometry.PointCloud, + grasp_group: graspnetAPI.GraspGroup, + n=5, + plot=False, + render=False, + save_view=False, + ) -> None: + vis = self.visualize(scene_pcd=scene_pcd, plot=plot, render=render, save_view=save_view) + + o3d_geometries = grasp_group.to_open3d_geometry_list() + n = min(n, len(o3d_geometries)) + log.info(f"Visualizing top {n} grasps in Open3D...") + grasp_images = [] for i in range(n): scene_points = o3d_geometries[i].sample_points_uniformly(number_of_points=5000) @@ -106,7 +118,6 @@ def visualize_grasp( grasp_images.append(grasp_image) vis.remove_geometry(scene_points, reset_bounding_box=False) - vis.destroy_window() if plot: log.info("Plotting with matplotlib...") f, axarr = plt.subplots(1, n, figsize=(n * 4.5, 3)) @@ -115,3 +126,5 @@ def visualize_grasp( axarr[i].axis("off") axarr[i].set_title(f"Grasp pose top {i + 1}/{n}") f.show() + + return vis diff --git a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py index c50af6f57e..a7df00fac8 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py @@ -1,9 +1,16 @@ +import logging from typing import List import numpy as np import open3d as o3d +import a0 +from polygrasp import serdes import pyrealsense2 +log = logging.getLogger(__name__) + + +topic_key = "pcd_server" class PointCloudClient: @@ -11,6 +18,7 @@ def __init__( self, camera_intrinsics: List[pyrealsense2.pyrealsense2.intrinsics], camera_extrinsics: np.ndarray, + masks: np.ndarray = None, ): assert len(camera_intrinsics) == len(camera_extrinsics) self.n_cams = len(camera_intrinsics) @@ -34,16 +42,24 @@ def __init__( self.extrinsic_transforms[i] = np.eye(4) self.extrinsic_transforms[i, :3, :3] = calibration["camera_base_ori"] self.extrinsic_transforms[i, :3, 3] = calibration["camera_base_pos"] + + self.client = a0.RpcClient(topic_key) + + if masks is None: + intrinsic = camera_intrinsics[0] + self.masks = np.ones([self.n_cams, intrinsic.width, intrinsic.height]) + else: + self.masks = masks def get_pcd(self, rgbds: np.ndarray) -> o3d.geometry.PointCloud: - scene_pcd = o3d.geometry.PointCloud() - for rgbd, intrinsic, transform in zip( - rgbds, self.o3_intrinsics, self.extrinsic_transforms + pcds = [] + for rgbd, intrinsic, transform, mask in zip( + rgbds, self.o3_intrinsics, self.extrinsic_transforms, self.masks ): # The specific casting here seems to be very important, even though # rgbd should already be in np.uint16 type... - img = rgbd[:, :, :3].astype(np.uint8) - depth = rgbd[:, :, 3].astype(np.uint16) + img = (rgbd[:, :, :3] * mask[:, :, None]).astype(np.uint8) + depth = (rgbd[:, :, 3] * mask).astype(np.uint16) o3d_img = o3d.cuda.pybind.geometry.Image(img) o3d_depth = o3d.cuda.pybind.geometry.Image(depth) @@ -56,9 +72,67 @@ def get_pcd(self, rgbds: np.ndarray) -> o3d.geometry.PointCloud: pcd = o3d.geometry.PointCloud.create_from_rgbd_image(rgbd_image, intrinsic) pcd.transform(transform) - scene_pcd += pcd + pcds.append(pcd) + + return pcds + + def get_pcd_i(self, rgbd, i): + intrinsic = self.o3_intrinsics[i] + transform = self.extrinsic_transforms[i] + mask = self.masks[i] + + img = (rgbd[:, :, :3] * mask[:, :, None]).astype(np.uint8) + depth = (rgbd[:, :, 3] * mask).astype(np.uint16) + + o3d_img = o3d.cuda.pybind.geometry.Image(img) + o3d_depth = o3d.cuda.pybind.geometry.Image(depth) + + rgbd_image = o3d.geometry.RGBDImage.create_from_color_and_depth( + o3d_img, + o3d_depth, + convert_rgb_to_intensity=False, + ) + + pcd = o3d.geometry.PointCloud.create_from_rgbd_image(rgbd_image, intrinsic) + pcd.transform(transform) + + return pcd + + def segment_pcd(self, rgbd, intrinsics): + raise NotImplementedError - return scene_pcd - def segment_pcd(self): +class PointCloudServer: + def _get_segmentations(self, rgbd): raise NotImplementedError + + def start(self): + def onrequest(req): + log.info("Got request; computing segmentations...") + + payload = req.pkt.payload + rgbd = serdes.capnp_to_rgbd(payload) + result = self._get_segmentations(rgbd) + + log.info("Done.Replying with serialized segmentations...") + req.reply(serdes.rgbd_to_capnp(result).to_bytes()) + + server = a0.RpcServer(topic_key, onrequest, None) + log.info("Starting server...") + while True: + pass + +class RgbdFeaturesPointCloudClient(PointCloudClient): + def segment_img(self, rgbd): + state = [] + + def onreply(pkt): + state.append(pkt.payload) + + bits = serdes.rgbd_to_capnp(rgbd).to_bytes() + self.client.send(bits, onreply) + + while not state: + pass + + return serdes.capnp_to_rgbd(state.pop()) diff --git a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py index ad58ff1094..8a5a87cbbc 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py +++ b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py @@ -1,5 +1,6 @@ """polymetis.RobotInterface combined with GripperInterface, with an additional `grasp` method.""" +import time import numpy as np from scipy.spatial.transform import Rotation as R import torch @@ -33,11 +34,16 @@ def grasp_to_pose(grasp: graspnetAPI.Grasp): return grasp.translation, R.from_matrix(grasp.rotation_matrix).as_quat() +def compute_quat_dist(a, b): + return torch.acos((2*(a * b).sum()**2 - 1).clip(-1, 1)) + class GraspingRobotInterface(polymetis.RobotInterface): def __init__(self, gripper: polymetis.GripperInterface, *args, **kwargs): super().__init__(*args, **kwargs) self.gripper = hydra.utils.instantiate(gripper) + self.default_ee_pose = torch.Tensor([ 0.9418, 0.3289, -0.0368, -0.0592]) + def gripper_open(self): self.gripper.goto(1, 1, 1) @@ -54,7 +60,7 @@ def _move_until_success(self, position, orientation, time_to_go, max_attempts=5) print(f"Dist to goal: {torch.linalg.norm(curr_ee_pos - position)}") - if torch.linalg.norm(curr_ee_pos - position) < 0.25: # TODO: orientation diff + if states[-1].prev_command_successful and torch.linalg.norm(curr_ee_pos - position) < 0.2: # TODO: orientation diff break return states @@ -62,29 +68,47 @@ def select_grasp( self, grasps: graspnetAPI.GraspGroup, scene_pcd: o3d.geometry.PointCloud ) -> graspnetAPI.Grasp: # TODO: do something smarter than this - return grasps[int(input("Choose grasp index (1-indexed):")) - 1] + grasps = grasps[:5] + with torch.no_grad(): + rots_as_quat = [torch.Tensor(R.from_matrix(grasp.rotation_matrix).as_quat()) for grasp in grasps] + dists = [compute_quat_dist(rot, self.default_ee_pose) for rot in rots_as_quat] + i = torch.argmin(torch.Tensor(dists)).item() + print(f"Grasp {i} has angle {dists[i]} from neutral") + return grasps[i] + + # print(f"Closest grasp to ee ori, within top 5: {i + 1}") + # return grasps[int(input("Choose grasp index (1-indexed):")) - 1] + + # return grasps[0] def grasp(self, grasp: graspnetAPI.Grasp): + time_to_go = 2 states = [] grasp_point, grasp_approach_delta, des_ori_quat = compute_des_pose(grasp) - offset = np.array([0.1, 0, 0.1]) + offset = np.array([0.1, 0.0, 0.1]) self.gripper_open() states += self._move_until_success( - position=torch.Tensor(grasp_point + grasp_approach_delta * 2.0 + offset), + position=torch.Tensor(grasp_point + grasp_approach_delta * 1.5 + offset), orientation=torch.Tensor(des_ori_quat), - time_to_go=3, + time_to_go=time_to_go, ) - grip_ee_pos = torch.Tensor(grasp_point + grasp_approach_delta * 0.8 + offset) + grip_ee_pos = torch.Tensor(grasp_point + grasp_approach_delta * 0.75 + offset) states += self._move_until_success( - position=grip_ee_pos, orientation=torch.Tensor(des_ori_quat), time_to_go=3 + position=grip_ee_pos, orientation=torch.Tensor(des_ori_quat), time_to_go=time_to_go ) - self.gripper_close() - success = self.gripper.get_state().width > 0.001 + print(f"Waiting for gripper to close...") + time.sleep(1.5) + + gripper_state = self.gripper.get_state() + width = gripper_state.width + print(f"Gripper width: {width}") + + success = width > 0.0005 return states, success diff --git a/perception/sandbox/polygrasp/src/polygrasp/serdes.py b/perception/sandbox/polygrasp/src/polygrasp/serdes.py index 675cc417d7..e5582bcfb8 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/serdes.py +++ b/perception/sandbox/polygrasp/src/polygrasp/serdes.py @@ -75,3 +75,13 @@ def capnp_to_grasp_group(blob): gg = bytes_to_grasp_group(capnp_gg.data) return gg + +def rgbd_to_capnp(rgbd): + img = sensor_msgs.Image() + img.data = np_to_bytes(rgbd) + + return img + +def capnp_to_rgbd(blob): + img = sensor_msgs.Image.from_bytes(blob) + return bytes_to_np(img.data) From 9ad9449651359a6e204396f17e01b5e7e3d5d47f Mon Sep 17 00:00:00 2001 From: 1heart Date: Thu, 28 Apr 2022 06:16:33 -0700 Subject: [PATCH 21/69] Factor out mindist grasp --- .../src/polygrasp/robot_interface.py | 19 +++++++++++-------- 1 file changed, 11 insertions(+), 8 deletions(-) diff --git a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py index 8a5a87cbbc..35ab68535d 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py +++ b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py @@ -37,6 +37,14 @@ def grasp_to_pose(grasp: graspnetAPI.Grasp): def compute_quat_dist(a, b): return torch.acos((2*(a * b).sum()**2 - 1).clip(-1, 1)) +def min_dist_grasp(default_ee_pose, grasps): + with torch.no_grad(): + rots_as_quat = [torch.Tensor(R.from_matrix(grasp.rotation_matrix).as_quat()) for grasp in grasps] + dists = [compute_quat_dist(rot, default_ee_pose) for rot in rots_as_quat] + i = torch.argmin(torch.Tensor(dists)).item() + print(f"Grasp {i} has angle {dists[i]} from reference.") + return grasps[i], i + class GraspingRobotInterface(polymetis.RobotInterface): def __init__(self, gripper: polymetis.GripperInterface, *args, **kwargs): super().__init__(*args, **kwargs) @@ -67,16 +75,11 @@ def _move_until_success(self, position, orientation, time_to_go, max_attempts=5) def select_grasp( self, grasps: graspnetAPI.GraspGroup, scene_pcd: o3d.geometry.PointCloud ) -> graspnetAPI.Grasp: - # TODO: do something smarter than this - grasps = grasps[:5] with torch.no_grad(): - rots_as_quat = [torch.Tensor(R.from_matrix(grasp.rotation_matrix).as_quat()) for grasp in grasps] - dists = [compute_quat_dist(rot, self.default_ee_pose) for rot in rots_as_quat] - i = torch.argmin(torch.Tensor(dists)).item() - print(f"Grasp {i} has angle {dists[i]} from neutral") - return grasps[i] + grasp, i = min_dist_grasp(self.default_ee_pose, grasps[:5]) + print(f"Closest grasp to ee ori, within top 5: {i + 1}") + return grasp - # print(f"Closest grasp to ee ori, within top 5: {i + 1}") # return grasps[int(input("Choose grasp index (1-indexed):")) - 1] # return grasps[0] From ccef94fbea8d409564fd1da7752e3583dfb5799e Mon Sep 17 00:00:00 2001 From: 1heart Date: Wed, 4 May 2022 12:56:23 -0700 Subject: [PATCH 22/69] Prettified new calibration --- .../sandbox/eyehandcal/calibration.json | 108 +++++++++++++++++- 1 file changed, 107 insertions(+), 1 deletion(-) diff --git a/perception/sandbox/eyehandcal/calibration.json b/perception/sandbox/eyehandcal/calibration.json index 4613e3bf46..e432d34c0c 100644 --- a/perception/sandbox/eyehandcal/calibration.json +++ b/perception/sandbox/eyehandcal/calibration.json @@ -1 +1,107 @@ -[{"camera_base_ori": [[-0.0008351711692040552, 0.9467041262862899, -0.3221033991773923], [0.9999876344084615, 0.0023697313594300013, 0.004372116587222594], [0.004902399339737778, -0.3220957647126033, -0.9466943988610668]], "camera_base_pos": [1.132091239302775, 0.09765527179120626, 0.7987150760861018], "p_marker_ee": [0.01538088407469198, -0.038626082221747446, 0.027503670654543382]}, {"camera_base_ori": [[-0.9837867934727511, -0.08545120494602781, -0.1576757323175443], [-0.03373994307395532, 0.9516773029445347, -0.30524076939619904], [0.17613960721532268, -0.294971867528904, -0.9391306810750794]], "camera_base_pos": [1.044620073945996, 0.978753642811283, 0.7400190717591493], "p_marker_ee": [-0.09874803603370458, -0.012452017614995134, 0.19377999347442204]}, {"camera_base_ori": [[-0.05954743351363026, 0.9652499225808887, -0.25445370918799537], [0.9981345466688237, 0.0541345562643601, -0.028229002183610033], [-0.013473303535552449, -0.25566000229924474, -0.966672867787334]], "camera_base_pos": [1.1158163442477056, -0.2854368661163418, 0.8067607259493821], "p_marker_ee": [0.014149125903098527, -0.03805976262399718, 0.026777494443228165]}] \ No newline at end of file +[ + { + "proj_func": "hand_marker_proj_world_camera", + "camera_base_ori": [ + [ + -0.0008352020945225837, + 0.946704225999065, + -0.3221031060281344 + ], + [ + 0.9999876345443985, + 0.0023697486541783266, + 0.004372076121720726 + ], + [ + 0.004902366342838931, + -0.322095471509344, + -0.9466944987890303 + ] + ], + "camera_base_ori_rotvec": [ + -2.0402580936641366, + -2.0436198529334617, + 0.332994523748139 + ], + "camera_base_pos": [ + 1.1320910408929687, + 0.09765525930569187, + 0.7987153450959031 + ], + "p_marker_ee": [ + 0.015380950370067018, + -0.038626121668840545, + 0.027503578643718527 + ] + }, + { + "proj_func": "hand_marker_proj_world_camera", + "camera_base_ori": [ + [ + -0.9922133881149259, + -0.06519269283618447, + 0.10612495110136698 + ], + [ + -0.09927352632119796, + 0.9285196589018803, + -0.3577653001682681 + ], + [ + -0.07521542007630476, + -0.36551491875640796, + -0.9277615451985723 + ] + ], + "camera_base_ori_rotvec": [ + 0.13571071802046047, + -3.1756184770540727, + 0.5968209054914462 + ], + "camera_base_pos": [ + 0.7377671343246434, + 0.6816211283105794, + 0.7112006071246687 + ], + "p_marker_ee": [ + 0.03707060781713541, + -0.04238957588297499, + -0.03219852079586214 + ] + }, + { + "proj_func": "hand_marker_proj_world_camera", + "camera_base_ori": [ + [ + -0.05954772333108995, + 0.9652497576137233, + -0.2544542671537102 + ], + [ + 0.9981345313764363, + 0.054134857884878776, + -0.02822896448201133 + ], + [ + -0.013473155533381062, + -0.2556605612691013, + -0.966672722016889 + ] + ], + "camera_base_ori_rotvec": [ + -2.031492331148569, + -2.1525209650911026, + 0.2937373990872759 + ], + "camera_base_pos": [ + 1.1158166964204739, + -0.2854368798373039, + 0.8067605062937359 + ], + "p_marker_ee": [ + 0.014149151708399116, + -0.03805972655414896, + 0.026777473848637195 + ] + } +] \ No newline at end of file From 6170ce6fcc6dc44c51d0c87a32ea8e9f1b278f8a Mon Sep 17 00:00:00 2001 From: 1heart Date: Wed, 4 May 2022 12:57:24 -0700 Subject: [PATCH 23/69] Collision avoidance --- .../src/polygrasp/collision_detector.py | 129 ++++++++++++++++++ .../src/polygrasp/robot_interface.py | 18 ++- 2 files changed, 142 insertions(+), 5 deletions(-) create mode 100644 perception/sandbox/polygrasp/src/polygrasp/collision_detector.py diff --git a/perception/sandbox/polygrasp/src/polygrasp/collision_detector.py b/perception/sandbox/polygrasp/src/polygrasp/collision_detector.py new file mode 100644 index 0000000000..761a27d45b --- /dev/null +++ b/perception/sandbox/polygrasp/src/polygrasp/collision_detector.py @@ -0,0 +1,129 @@ +""" Collision detection to remove collided grasp pose predictions. +Author: chenxi-wang +""" + +import os +import sys +import numpy as np +import open3d as o3d + +class ModelFreeCollisionDetector(): + """ Collision detection in scenes without object labels. Current finger width and length are fixed. + + Input: + scene_points: [numpy.ndarray, (N,3), numpy.float32] + the scene points to detect + voxel_size: [float] + used for downsample + + Example usage: + mfcdetector = ModelFreeCollisionDetector(scene_points, voxel_size=0.005) + collision_mask = mfcdetector.detect(grasp_group, approach_dist=0.03) + collision_mask, iou_list = mfcdetector.detect(grasp_group, approach_dist=0.03, collision_thresh=0.05, return_ious=True) + collision_mask, empty_mask = mfcdetector.detect(grasp_group, approach_dist=0.03, collision_thresh=0.05, + return_empty_grasp=True, empty_thresh=0.01) + collision_mask, empty_mask, iou_list = mfcdetector.detect(grasp_group, approach_dist=0.03, collision_thresh=0.05, + return_empty_grasp=True, empty_thresh=0.01, return_ious=True) + """ + def __init__(self, scene_points, voxel_size=0.005): + self.finger_width = 0.01 + self.finger_length = 0.06 + self.voxel_size = voxel_size + scene_cloud = o3d.geometry.PointCloud() + scene_cloud.points = o3d.utility.Vector3dVector(scene_points) + scene_cloud = scene_cloud.voxel_down_sample(voxel_size) + self.scene_points = np.array(scene_cloud.points) + + def detect(self, grasp_group, approach_dist=0.03, collision_thresh=0.05, return_empty_grasp=False, empty_thresh=0.01, return_ious=False): + """ Detect collision of grasps. + + Input: + grasp_group: [GraspGroup, M grasps] + the grasps to check + approach_dist: [float] + the distance for a gripper to move along approaching direction before grasping + this shifting space requires no point either + collision_thresh: [float] + if global collision iou is greater than this threshold, + a collision is detected + return_empty_grasp: [bool] + if True, return a mask to imply whether there are objects in a grasp + empty_thresh: [float] + if inner space iou is smaller than this threshold, + a collision is detected + only set when [return_empty_grasp] is True + return_ious: [bool] + if True, return global collision iou and part collision ious + + Output: + collision_mask: [numpy.ndarray, (M,), numpy.bool] + True implies collision + [optional] empty_mask: [numpy.ndarray, (M,), numpy.bool] + True implies empty grasp + only returned when [return_empty_grasp] is True + [optional] iou_list: list of [numpy.ndarray, (M,), numpy.float32] + global and part collision ious, containing + [global_iou, left_iou, right_iou, bottom_iou, shifting_iou] + only returned when [return_ious] is True + """ + approach_dist = max(approach_dist, self.finger_width) + T = grasp_group.translations + R = grasp_group.rotation_matrices + heights = grasp_group.heights[:,np.newaxis] + depths = grasp_group.depths[:,np.newaxis] + widths = grasp_group.widths[:,np.newaxis] + targets = self.scene_points[np.newaxis,:,:] - T[:,np.newaxis,:] + targets = np.matmul(targets, R) + + ## collision detection + # height mask + mask1 = ((targets[:,:,2] > -heights/2) & (targets[:,:,2] < heights/2)) + # left finger mask + mask2 = ((targets[:,:,0] > depths - self.finger_length) & (targets[:,:,0] < depths)) + mask3 = (targets[:,:,1] > -(widths/2 + self.finger_width)) + mask4 = (targets[:,:,1] < -widths/2) + # right finger mask + mask5 = (targets[:,:,1] < (widths/2 + self.finger_width)) + mask6 = (targets[:,:,1] > widths/2) + # bottom mask + mask7 = ((targets[:,:,0] <= depths - self.finger_length)\ + & (targets[:,:,0] > depths - self.finger_length - self.finger_width)) + # shifting mask + mask8 = ((targets[:,:,0] <= depths - self.finger_length - self.finger_width)\ + & (targets[:,:,0] > depths - self.finger_length - self.finger_width - approach_dist)) + + # get collision mask of each point + left_mask = (mask1 & mask2 & mask3 & mask4) + right_mask = (mask1 & mask2 & mask5 & mask6) + bottom_mask = (mask1 & mask3 & mask5 & mask7) + shifting_mask = (mask1 & mask3 & mask5 & mask8) + global_mask = (left_mask | right_mask | bottom_mask | shifting_mask) + + # calculate equivalant volume of each part + left_right_volume = (heights * self.finger_length * self.finger_width / (self.voxel_size**3)).reshape(-1) + bottom_volume = (heights * (widths+2*self.finger_width) * self.finger_width / (self.voxel_size**3)).reshape(-1) + shifting_volume = (heights * (widths+2*self.finger_width) * approach_dist / (self.voxel_size**3)).reshape(-1) + volume = left_right_volume*2 + bottom_volume + shifting_volume + + # get collision iou of each part + global_iou = global_mask.sum(axis=1) / (volume+1e-6) + + # get collison mask + collision_mask = (global_iou > collision_thresh) + + if not (return_empty_grasp or return_ious): + return collision_mask + + ret_value = [collision_mask,] + if return_empty_grasp: + inner_mask = (mask1 & mask2 & (~mask4) & (~mask6)) + inner_volume = (heights * self.finger_length * widths / (self.voxel_size**3)).reshape(-1) + empty_mask = (inner_mask.sum(axis=-1)/inner_volume < empty_thresh) + ret_value.append(empty_mask) + if return_ious: + left_iou = left_mask.sum(axis=1) / (left_right_volume+1e-6) + right_iou = right_mask.sum(axis=1) / (left_right_volume+1e-6) + bottom_iou = bottom_mask.sum(axis=1) / (bottom_volume+1e-6) + shifting_iou = shifting_mask.sum(axis=1) / (shifting_volume+1e-6) + ret_value.append([global_iou, left_iou, right_iou, bottom_iou, shifting_iou]) + return ret_value diff --git a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py index 35ab68535d..c0d6367f0e 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py +++ b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py @@ -10,6 +10,8 @@ import graspnetAPI import polymetis +from polygrasp import collision_detector + def compute_des_pose(best_grasp): grasp_point = best_grasp.translation @@ -75,6 +77,15 @@ def _move_until_success(self, position, orientation, time_to_go, max_attempts=5) def select_grasp( self, grasps: graspnetAPI.GraspGroup, scene_pcd: o3d.geometry.PointCloud ) -> graspnetAPI.Grasp: + # TODO: filter out kinematically infeasible grasps + + # TODO: filter out collisions + collision = collision_detector.ModelFreeCollisionDetector(np.asarray(scene_pcd.points)) + collision_mask = collision.detect(grasps) + print(f"Number of colliding grasps: {collision_mask.sum()}/{len(collision_mask)}") + grasps = grasps[~collision_mask] + + # Choose the grasp closest to the neutral position with torch.no_grad(): grasp, i = min_dist_grasp(self.default_ee_pose, grasps[:5]) print(f"Closest grasp to ee ori, within top 5: {i + 1}") @@ -84,13 +95,10 @@ def select_grasp( # return grasps[0] - def grasp(self, grasp: graspnetAPI.Grasp): - time_to_go = 2 + def grasp(self, grasp: graspnetAPI.Grasp, time_to_go=3, offset=np.array([0.0, 0.0, 0.0])): states = [] grasp_point, grasp_approach_delta, des_ori_quat = compute_des_pose(grasp) - offset = np.array([0.1, 0.0, 0.1]) - self.gripper_open() states += self._move_until_success( position=torch.Tensor(grasp_point + grasp_approach_delta * 1.5 + offset), @@ -98,7 +106,7 @@ def grasp(self, grasp: graspnetAPI.Grasp): time_to_go=time_to_go, ) - grip_ee_pos = torch.Tensor(grasp_point + grasp_approach_delta * 0.75 + offset) + grip_ee_pos = torch.Tensor(grasp_point + grasp_approach_delta * 0.72 + offset) states += self._move_until_success( position=grip_ee_pos, orientation=torch.Tensor(des_ori_quat), time_to_go=time_to_go From 9cc63b1d13b233622a36bcc25868fb6dd689c239 Mon Sep 17 00:00:00 2001 From: 1heart Date: Wed, 4 May 2022 12:57:49 -0700 Subject: [PATCH 24/69] Working continuous 2-bin-pick --- .../sandbox/polygrasp/scripts/run_grasp.py | 245 ++++++++++-------- .../polygrasp/src/polygrasp/grasp_rpc.py | 42 ++- 2 files changed, 173 insertions(+), 114 deletions(-) diff --git a/perception/sandbox/polygrasp/scripts/run_grasp.py b/perception/sandbox/polygrasp/scripts/run_grasp.py index 5d9ad02ddf..ee21eaa294 100644 --- a/perception/sandbox/polygrasp/scripts/run_grasp.py +++ b/perception/sandbox/polygrasp/scripts/run_grasp.py @@ -4,16 +4,34 @@ Runs grasps generated from grasp server. """ -import random -import torch +import time +import os + +import numpy as np +import matplotlib.pyplot as plt +import torch import hydra +import omegaconf + from polygrasp.pointcloud_rpc import PointCloudClient, RgbdFeaturesPointCloudClient from polygrasp.grasp_rpc import GraspClient +def save_rgbd_masked(rgbd, rgbd_masked): + num_cams = rgbd.shape[0] + f, axarr = plt.subplots(2, num_cams) + + for i in range(num_cams): + axarr[0, i].imshow(rgbd[i, :, :, :3].astype(np.uint8)) + axarr[1, i].imshow(rgbd_masked[i, :, :, :3].astype(np.uint8)) + + f.savefig("rgbd_masked") + @hydra.main(config_path="../conf", config_name="run_grasp") def main(cfg): + print(f"Config: {omegaconf.OmegaConf.to_yaml(cfg, resolve=True)}") + print(f"Current working directory: {os.getcwd()}") # Initialize robot & gripper robot = hydra.utils.instantiate(cfg.robot) robot.gripper_open() @@ -26,122 +44,133 @@ def main(cfg): camera_intrinsics = cameras.get_intrinsics() camera_extrinsics = cameras.get_extrinsics() - import numpy as np # masks = np.ones([3, 480, 640]) masks = np.zeros([3, 480, 640]) - masks[0][70:320, 60:400] = 1 - masks[1][100:350, 300:600] = 1 + # masks[0][70:320, 60:400] = 1 # masks[2][130:350, 240:480] = 1 + masks[0][20:460, :440] = 1 + masks[1][100:480, 180:600] = 1 # Connect to grasp candidate selection and pointcloud processor pcd_client = RgbdFeaturesPointCloudClient(camera_intrinsics, camera_extrinsics, masks=masks) grasp_client = GraspClient(view_json_path=hydra.utils.to_absolute_path(cfg.view_json_path)) - num_iters = 10 - for i in range(num_iters): - print(f"Grasp {i + 1} / num_iters") - - print("Getting rgbd and pcds..") - rgbd = cameras.get_rgbd() - rgbd_masked = rgbd * masks[:, :, :, None] - pcds = pcd_client.get_pcd(rgbd) - - # import matplotlib.pyplot as plt - # f, axarr = plt.subplots(2, 3) - # for i in range(3): - # axarr[0, i].imshow(rgbd[i, :, :, :3].astype(np.uint8)) - # axarr[1, i].imshow(rgbd_masked[i, :, :, :3].astype(np.uint8)) - # f.show() - # import pdb; pdb.set_trace() - - scene_pcd = pcds[0] - for pcd in pcds[1:]: - scene_pcd += pcd - - # import pdb; pdb.set_trace() - # Get RGBD & pointcloud - print("Segmenting image...") - labels = pcd_client.segment_img(rgbd_masked[0]) - from matplotlib import pyplot as plt - obj_to_pcd = {} - obj_to_grasps = {} - num_objs = int(labels.max()) - print(f"Number of objs: {num_objs}") - # for i in range(1, int(num_objs + 1)): - # if num_objs > 0: - # i = 1 - min_mask_size = 2000 - for i in range(1, num_objs + 1): - obj_mask = labels == i - obj_mask_size = obj_mask.sum() - if obj_mask_size < min_mask_size: - continue - - obj_masked_rgbd = rgbd[0] * obj_mask[:, :, None] - - # plt.imshow(obj_masked_rgbd[:, :, :3]) - # plt.title(f"Object {i}, mask size {obj_mask_size}") - # plt.show() - - print(f"Getting obj {i} pcd...") - pcd = pcd_client.get_pcd_i(obj_masked_rgbd, 0) - print(f"Getting obj {i} grasp...") - grasp_group = grasp_client.get_grasps(pcd) - - obj_to_pcd[i] = pcd - obj_to_grasps[i] = grasp_group - break - - # grasp_client.visualize_grasp(scene_pcd, grasp_group, plot=True) - if len(obj_to_pcd) == 0: - print(f"Failed to find any objects with mask size > {min_mask_size}!") - continue - - # import pdb; pdb.set_trace() - - # vis = grasp_client.visualize(scene_pcd, render=True) - # import pdb; pdb.set_trace() - # rgb, d, intrinsics = grasp_client.get_rgbd(vis) - - - # grasp_group = grasp_client.get_grasps(pcd) - # grasp_client.visualize_grasp( - # scene_pcd, grasp_group, render=True, save_view=False, plot=True - # ) - - # Get grasps per object - # obj_to_pcd = pcd_client.segment_pcd(scene_pcd) - # obj_to_grasps = {obj: grasp_client.get_grasps(pcd) for obj, pcd in obj_to_pcd.items()} - - # Pick a random object to grasp - # curr_obj, curr_grasps = random.choice(list(obj_to_grasps.items())) - # curr_obj, curr_grasps = 1, obj_to_grasps[1] - # print(f"Picking object with ID {curr_obj}") - curr_grasps = grasp_group - - # Choose a grasp for this object - # TODO: scene-aware motion planning for grasps - grasp_client.visualize_grasp(scene_pcd, curr_grasps, plot=True) - chosen_grasp = robot.select_grasp(curr_grasps, scene_pcd) - - # Execute grasp - traj, success = robot.grasp(chosen_grasp) - print(f"Grasp success: {success}") - - if success: - print(f"Moving end-effector up") + root_dir = os.getcwd() + + for outer_i in range(0, 10): + cam_i = outer_i % 2 + print(f"=== Starting outer loop with cam {cam_i} ===") + + if cam_i == 0: + hori_offset = torch.Tensor([0, 0.4, 0]) + grasp_offset = np.array([0.1, 0.0, 0.05]) + time_to_go = 2 + else: + hori_offset = torch.Tensor([0, -0.4, 0]) + grasp_offset = np.array([0.1, 0.1, 0.1]) + time_to_go = 3 + + num_iters = 10 + for i in range(num_iters): + os.chdir(root_dir) + timestamp = int(time.time()) + os.makedirs(f"{timestamp}") + os.chdir(f"{timestamp}") + + print(f"Grasp {i + 1} / num_iters, in {os.getcwd()}") + + print("Getting rgbd and pcds..") + rgbd = cameras.get_rgbd() + rgbd_masked = rgbd * masks[:, :, :, None] + pcds = pcd_client.get_pcd(rgbd) + + save_rgbd_masked(rgbd, rgbd_masked) + + scene_pcd = pcds[0] + for pcd in pcds[1:]: + scene_pcd += pcd + + # Get RGBD & pointcloud + print("Segmenting image...") + labels = pcd_client.segment_img(rgbd_masked[cam_i]) + + obj_to_grasps = {} + num_objs = int(labels.max()) + print(f"Number of objs: {num_objs}") + # for i in range(1, int(num_objs + 1)): + # if num_objs > 0: + # i = 1 + min_mask_size = 2500 + for obj_i in range(1, num_objs + 1): + obj_mask = labels == obj_i + obj_mask_size = obj_mask.sum() + + if obj_mask_size < min_mask_size: + continue + + obj_masked_rgbd = rgbd_masked[cam_i] * obj_mask[:, :, None] + + plt.imshow(obj_masked_rgbd[:, :, :3]) + plt.title(f"Object {obj_i}, mask size {obj_mask_size}") + plt.savefig(f"object_{obj_i}_masked") + plt.close() + # plt.show() + + print(f"Getting obj {obj_i} pcd...") + pcd = pcd_client.get_pcd_i(obj_masked_rgbd, cam_i) + print(f"Getting obj {obj_i} grasp...") + grasp_group = grasp_client.get_grasps(pcd) + obj_to_grasps[obj_i] = grasp_group + + break + + if len(obj_to_grasps) == 0: + print(f"Failed to find any objects with mask size > {min_mask_size}!") + break + + # import pdb; pdb.set_trace() + + # vis = grasp_client.visualize(scene_pcd, render=True) + # import pdb; pdb.set_trace() + # rgb, d, intrinsics = grasp_client.get_rgbd(vis) + + + # grasp_group = grasp_client.get_grasps(pcd) + # grasp_client.visualize_grasp( + # scene_pcd, grasp_group, render=True, save_view=False, plot=True + # ) + + # Get grasps per object + # obj_to_pcd = pcd_client.segment_pcd(scene_pcd) + # obj_to_grasps = {obj: grasp_client.get_grasps(pcd) for obj, pcd in obj_to_pcd.items()} + + # Pick a random object to grasp + # curr_obj, curr_grasps = random.choice(list(obj_to_grasps.items())) + # curr_obj, curr_grasps = 1, obj_to_grasps[1] + # print(f"Picking object with ID {curr_obj}") + curr_grasps = grasp_group + + # Choose a grasp for this object + # TODO: scene-aware motion planning for grasps + grasp_client.visualize_grasp(pcds[cam_i], curr_grasps) + chosen_grasp = robot.select_grasp(curr_grasps, scene_pcd) + + # Execute grasp + traj, success = robot.grasp(chosen_grasp, offset=grasp_offset, time_to_go=time_to_go) + print(f"Grasp success: {success}") + + if success: + print(f"Moving end-effector up") + curr_pose, curr_ori = robot.get_ee_pose() + states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0, 0.2]), orientation=curr_ori, time_to_go=time_to_go) + states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.2]) + hori_offset, orientation=curr_ori, time_to_go=time_to_go) + states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.05]) + hori_offset, orientation=curr_ori, time_to_go=time_to_go) + + robot.gripper_open() curr_pose, curr_ori = robot.get_ee_pose() - states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0, 0.2]), orientation=curr_ori, time_to_go=3) - states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0.4, 0.2]), orientation=curr_ori, time_to_go=3) - states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0.4, 0.05]), orientation=curr_ori, time_to_go=3) - - robot.gripper_open() - curr_pose, curr_ori = robot.get_ee_pose() - states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.2]), orientation=curr_ori, time_to_go=3) - robot.go_home() - # robot.move_to_ee_pose(torch.Tensor([0, 0, 0.1]), delta=True) - # robot.move_to_ee_pose(torch.Tensor([0, 0, -0.1]), delta=True) + states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.2]), orientation=curr_ori, time_to_go=time_to_go) + robot.go_home() if __name__ == "__main__": diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py index 2c31763a96..f61840a719 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py @@ -1,3 +1,4 @@ +import time import logging import numpy as np import open3d as o3d @@ -104,9 +105,29 @@ def visualize_grasp( render=False, save_view=False, ) -> None: + timestamp = int(time.time()) + o3d_geometries = grasp_group.to_open3d_geometry_list() + + # k = 5 + # total_pts = scene_pcd + # pts = [x.sample_points_uniformly(number_of_points=5000) for x in o3d_geometries[:k]] + # for pt in pts: + # total_pts += pt + # vis = self.visualize(scene_pcd=total_pts, plot=plot, render=render, save_view=save_view) + # grasp_image = np.array(vis.capture_screen_float_buffer(do_render=True)) + # f = plt.figure() + # plt.imshow(grasp_image) + # f.savefig(f"{timestamp}_grasp_top_{k}.png") + # plt.close(f) + # vis.close() + vis = self.visualize(scene_pcd=scene_pcd, plot=plot, render=render, save_view=save_view) - o3d_geometries = grasp_group.to_open3d_geometry_list() + grasp_image = np.array(vis.capture_screen_float_buffer(do_render=True)) + f = plt.figure() + plt.imshow(grasp_image) + f.savefig(f"scene.png") + n = min(n, len(o3d_geometries)) log.info(f"Visualizing top {n} grasps in Open3D...") @@ -116,15 +137,24 @@ def visualize_grasp( vis.add_geometry(scene_points, reset_bounding_box=False) grasp_image = np.array(vis.capture_screen_float_buffer(do_render=True)) grasp_images.append(grasp_image) + f = plt.figure() + plt.imshow(grasp_image) + f.savefig(f"grasp_{i + 1}.png") + plt.close(f) vis.remove_geometry(scene_points, reset_bounding_box=False) if plot: log.info("Plotting with matplotlib...") - f, axarr = plt.subplots(1, n, figsize=(n * 4.5, 3)) + w, h = n // 5, 5 + if n % 5 != 0: + w += 1 + + f, axarr = plt.subplots(w, h, figsize=(w * 5, h * 3)) for i in range(n): - axarr[i].imshow(grasp_images[i], interpolation="nearest", aspect="auto") - axarr[i].axis("off") - axarr[i].set_title(f"Grasp pose top {i + 1}/{n}") + a, b = i // 5, i % 5 + axarr[a, b].imshow(grasp_images[i]) + axarr[a, b].axis("off") + axarr[a, b].set_title(f"Grasp pose top {i + 1}/{n}") f.show() - + return vis From 5ec3c8452beadd01ef83c1a1b5b0113fde62617d Mon Sep 17 00:00:00 2001 From: 1heart Date: Wed, 4 May 2022 12:59:44 -0700 Subject: [PATCH 25/69] Re-add envrc --- perception/sandbox/eyehandcal/.envrc | 1 + 1 file changed, 1 insertion(+) create mode 100644 perception/sandbox/eyehandcal/.envrc diff --git a/perception/sandbox/eyehandcal/.envrc b/perception/sandbox/eyehandcal/.envrc new file mode 100644 index 0000000000..ea148ff778 --- /dev/null +++ b/perception/sandbox/eyehandcal/.envrc @@ -0,0 +1 @@ +layout_miniconda eyehandcal From 4d21a19d9e51c0ec38ba86ebde5946327fd47aad Mon Sep 17 00:00:00 2001 From: 1heart Date: Mon, 9 May 2022 08:55:20 -0700 Subject: [PATCH 26/69] Pretty intrinsincs json dump --- .../sandbox/polygrasp/conf/intrinsics.json | 48 ++++++++++++++++++- .../polygrasp/src/polygrasp/cam_pub_sub.py | 2 +- 2 files changed, 48 insertions(+), 2 deletions(-) diff --git a/perception/sandbox/polygrasp/conf/intrinsics.json b/perception/sandbox/polygrasp/conf/intrinsics.json index cad1fc3cb8..4d24e87672 100644 --- a/perception/sandbox/polygrasp/conf/intrinsics.json +++ b/perception/sandbox/polygrasp/conf/intrinsics.json @@ -1 +1,47 @@ -[{"coeffs": [0.0, 0.0, 0.0, 0.0, 0.0], "fx": 617.8477783203125, "fy": 618.071044921875, "height": 480, "ppx": 331.7496032714844, "ppy": 248.904541015625, "width": 640}, {"coeffs": [0.0, 0.0, 0.0, 0.0, 0.0], "fx": 616.762939453125, "fy": 616.74951171875, "height": 480, "ppx": 329.696044921875, "ppy": 234.45372009277344, "width": 640}, {"coeffs": [0.0, 0.0, 0.0, 0.0, 0.0], "fx": 614.17041015625, "fy": 614.19189453125, "height": 480, "ppx": 326.27642822265625, "ppy": 236.0000762939453, "width": 640}] \ No newline at end of file +[ + { + "coeffs": [ + 0.0, + 0.0, + 0.0, + 0.0, + 0.0 + ], + "fx": 617.8477783203125, + "fy": 618.071044921875, + "height": 480, + "ppx": 331.7496032714844, + "ppy": 248.904541015625, + "width": 640 + }, + { + "coeffs": [ + 0.0, + 0.0, + 0.0, + 0.0, + 0.0 + ], + "fx": 616.762939453125, + "fy": 616.74951171875, + "height": 480, + "ppx": 329.696044921875, + "ppy": 234.45372009277344, + "width": 640 + }, + { + "coeffs": [ + 0.0, + 0.0, + 0.0, + 0.0, + 0.0 + ], + "fx": 614.17041015625, + "fy": 614.19189453125, + "height": 480, + "ppx": 326.27642822265625, + "ppy": 236.0000762939453, + "width": 640 + } +] \ No newline at end of file diff --git a/perception/sandbox/polygrasp/src/polygrasp/cam_pub_sub.py b/perception/sandbox/polygrasp/src/polygrasp/cam_pub_sub.py index 0b90f47fd2..1edf5b4af8 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/cam_pub_sub.py +++ b/perception/sandbox/polygrasp/src/polygrasp/cam_pub_sub.py @@ -52,7 +52,7 @@ def get_rgbd(self): for x in intrinsics ] with open(args.intrinsics, "w") as f: - json.dump(intrinsics_py, f) + json.dump(intrinsics_py, f, indent=4) rgbd_pub = a0.Publisher(topic) From 35ddd8f430a57dc40dcdb05f677de48ade91b99e Mon Sep 17 00:00:00 2001 From: 1heart Date: Tue, 10 May 2022 10:36:00 -0700 Subject: [PATCH 27/69] Collision separation --- perception/sandbox/polygrasp/MANIFEST.in | 3 + .../sandbox/polygrasp/scripts/run_grasp.py | 43 ++--- perception/sandbox/polygrasp/setup.py | 2 +- .../polygrasp/src/polygrasp/grasp_rpc.py | 148 ++++++++++-------- .../polygrasp/src/polygrasp/pointcloud_rpc.py | 24 +-- .../polygrasp/src/polygrasp/polygrasp.capnp | 6 + .../src/polygrasp/robot_interface.py | 41 ++--- .../sandbox/polygrasp/src/polygrasp/serdes.py | 8 + 8 files changed, 144 insertions(+), 131 deletions(-) create mode 100644 perception/sandbox/polygrasp/MANIFEST.in create mode 100644 perception/sandbox/polygrasp/src/polygrasp/polygrasp.capnp diff --git a/perception/sandbox/polygrasp/MANIFEST.in b/perception/sandbox/polygrasp/MANIFEST.in new file mode 100644 index 0000000000..a015a63b08 --- /dev/null +++ b/perception/sandbox/polygrasp/MANIFEST.in @@ -0,0 +1,3 @@ +global-exclude *.pyc +global-exclude __pycache__ +recursive-include src/polygrasp/*.capnp diff --git a/perception/sandbox/polygrasp/scripts/run_grasp.py b/perception/sandbox/polygrasp/scripts/run_grasp.py index ee21eaa294..57390cef5a 100644 --- a/perception/sandbox/polygrasp/scripts/run_grasp.py +++ b/perception/sandbox/polygrasp/scripts/run_grasp.py @@ -14,7 +14,7 @@ import hydra import omegaconf -from polygrasp.pointcloud_rpc import PointCloudClient, RgbdFeaturesPointCloudClient +from polygrasp.pointcloud_rpc import SegmentationPointCloudClient from polygrasp.grasp_rpc import GraspClient def save_rgbd_masked(rgbd, rgbd_masked): @@ -53,7 +53,7 @@ def main(cfg): masks[1][100:480, 180:600] = 1 # Connect to grasp candidate selection and pointcloud processor - pcd_client = RgbdFeaturesPointCloudClient(camera_intrinsics, camera_extrinsics, masks=masks) + pcd_client = SegmentationPointCloudClient(camera_intrinsics, camera_extrinsics, masks=masks) grasp_client = GraspClient(view_json_path=hydra.utils.to_absolute_path(cfg.view_json_path)) root_dir = os.getcwd() @@ -98,9 +98,6 @@ def main(cfg): obj_to_grasps = {} num_objs = int(labels.max()) print(f"Number of objs: {num_objs}") - # for i in range(1, int(num_objs + 1)): - # if num_objs > 0: - # i = 1 min_mask_size = 2500 for obj_i in range(1, num_objs + 1): obj_mask = labels == obj_i @@ -121,38 +118,18 @@ def main(cfg): pcd = pcd_client.get_pcd_i(obj_masked_rgbd, cam_i) print(f"Getting obj {obj_i} grasp...") grasp_group = grasp_client.get_grasps(pcd) - obj_to_grasps[obj_i] = grasp_group - - break + filtered_grasp_group = grasp_client.get_collision(grasp_group, scene_pcd) + if len(filtered_grasp_group) > 0: + obj_to_grasps[obj_i] = filtered_grasp_group + break if len(obj_to_grasps) == 0: print(f"Failed to find any objects with mask size > {min_mask_size}!") break - # import pdb; pdb.set_trace() - - # vis = grasp_client.visualize(scene_pcd, render=True) - # import pdb; pdb.set_trace() - # rgb, d, intrinsics = grasp_client.get_rgbd(vis) - - - # grasp_group = grasp_client.get_grasps(pcd) - # grasp_client.visualize_grasp( - # scene_pcd, grasp_group, render=True, save_view=False, plot=True - # ) - - # Get grasps per object - # obj_to_pcd = pcd_client.segment_pcd(scene_pcd) - # obj_to_grasps = {obj: grasp_client.get_grasps(pcd) for obj, pcd in obj_to_pcd.items()} - - # Pick a random object to grasp - # curr_obj, curr_grasps = random.choice(list(obj_to_grasps.items())) - # curr_obj, curr_grasps = 1, obj_to_grasps[1] - # print(f"Picking object with ID {curr_obj}") curr_grasps = grasp_group # Choose a grasp for this object - # TODO: scene-aware motion planning for grasps grasp_client.visualize_grasp(pcds[cam_i], curr_grasps) chosen_grasp = robot.select_grasp(curr_grasps, scene_pcd) @@ -163,13 +140,13 @@ def main(cfg): if success: print(f"Moving end-effector up") curr_pose, curr_ori = robot.get_ee_pose() - states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0, 0.2]), orientation=curr_ori, time_to_go=time_to_go) - states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.2]) + hori_offset, orientation=curr_ori, time_to_go=time_to_go) - states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.05]) + hori_offset, orientation=curr_ori, time_to_go=time_to_go) + states = robot.move_until_success(position=curr_pose + torch.Tensor([0, 0, 0.2]), orientation=curr_ori, time_to_go=time_to_go) + states = robot.move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.2]) + hori_offset, orientation=curr_ori, time_to_go=time_to_go) + states = robot.move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.05]) + hori_offset, orientation=curr_ori, time_to_go=time_to_go) robot.gripper_open() curr_pose, curr_ori = robot.get_ee_pose() - states = robot._move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.2]), orientation=curr_ori, time_to_go=time_to_go) + states = robot.move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.2]), orientation=curr_ori, time_to_go=time_to_go) robot.go_home() diff --git a/perception/sandbox/polygrasp/setup.py b/perception/sandbox/polygrasp/setup.py index 4477886ddf..68dfed54bc 100644 --- a/perception/sandbox/polygrasp/setup.py +++ b/perception/sandbox/polygrasp/setup.py @@ -14,7 +14,6 @@ "fairomsg", ] - setup( name="polygrasp", author="Yixin Lin", @@ -22,6 +21,7 @@ version="0.1", packages=find_packages(where="src"), package_dir={"": "src"}, + include_package_data=True, scripts=["scripts/run_grasp.py"], install_requires=install_requires, ) diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py index f61840a719..e3d408e4bb 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py @@ -1,28 +1,39 @@ -import time import logging import numpy as np import open3d as o3d - from matplotlib import pyplot as plt import a0 import graspnetAPI from polygrasp import serdes +from polygrasp.serdes import polygrasp_msgs log = logging.getLogger(__name__) topic_key = "grasp_server" +grasp_topic_key = f"{topic_key}/grasp" +collision_topic_key = f"{topic_key}/collision" + + +def save_img(img, name): + f = plt.figure() + plt.imshow(img) + f.savefig(f"{name}.png") + plt.close(f) class GraspServer: def _get_grasps(self, pcd: o3d.geometry.PointCloud) -> np.ndarray: raise NotImplementedError + + def _get_collisions(self, grasps: graspnetAPI.GraspGroup, scene_pcd: o3d.geometry.PointCloud): + raise NotImplementedError def start(self): log.info(f"Starting grasp server...") - def onrequest(req): + def grasp_onrequest(req): log.info(f"Got request; computing grasp group...") payload = req.pkt.payload @@ -31,42 +42,78 @@ def onrequest(req): log.info(f"Done. Replying with serialized grasp group...") req.reply(serdes.grasp_group_to_capnp(grasp_group).to_bytes()) + grasp_server = a0.RpcServer(grasp_topic_key, grasp_onrequest, None) + + def collision_onrequest(req): + log.info(f"Got request; computing collisions...") + + payload = req.pkt.payload + msg = polygrasp_msgs.CollisionRequest.from_bytes(payload) + grasp_group = serdes.bytes_to_grasp_group(msg.grasps) + scene_pcd = serdes.capnp_to_pcd(msg.pcd) + + filtered_grasp_group = self._get_collisions(grasp_group, scene_pcd) + log.info(f"Done. Replying with serialized filtered grasps...") + req.reply(serdes.grasp_group_to_bytes(filtered_grasp_group)) + collision_server = a0.RpcServer(collision_topic_key, collision_onrequest, None) - server = a0.RpcServer(topic_key, onrequest, None) while True: pass class GraspClient: def __init__(self, view_json_path): - self.client = a0.RpcClient(topic_key) + self.grasp_client = a0.RpcClient(grasp_topic_key) + self.collision_client = a0.RpcClient(collision_topic_key) self.view_json_path = view_json_path - def get_grasps(self, pcd: o3d.geometry.PointCloud) -> graspnetAPI.GraspGroup: - state = [] - - def onreply(pkt): - state.append(pkt.payload) - + def downsample_pcd(self, pcd: o3d.geometry.PointCloud, max_num_bits=8 * 1024 * 1024): + # a0 default max msg size 16MB; make sure every msg < 1/2 of max i = 1 while True: downsampled_pcd = pcd.uniform_down_sample(i) bits = serdes.pcd_to_capnp(downsampled_pcd).to_bytes() - if ( - len(bits) > 8 * 1024 * 1024 - ): # a0 default max msg size 16MB; make sure every msg < 1/2 of max + if len(bits) > max_num_bits: log.warning(f"Downsampling pointcloud...") i += 1 else: break if i > 1: log.warning(f"Downsampled to every {i}th point.") - self.client.send(bits, onreply) + + return bits + + def get_grasps(self, pcd: o3d.geometry.PointCloud) -> graspnetAPI.GraspGroup: + state = [] + + def onreply(pkt): + state.append(pkt.payload) + + bits = self.downsample_pcd(pcd) + self.grasp_client.send(bits, onreply) while not state: pass + return serdes.capnp_to_grasp_group(state.pop()) + def get_collision(self, grasps: graspnetAPI.GraspGroup, scene_pcd: o3d.geometry.PointCloud): + state = [] + + def onreply(pkt): + state.append(pkt.payload) + + request = polygrasp_msgs.CollisionRequest() + request.pcd = self.downsample_pcd(scene_pcd) + request.grasps = serdes.grasp_group_to_bytes(grasps) + bits = request.to_bytes() + self.collision_client.send(bits, onreply) + + while not state: + pass + + return serdes.bytes_to_grasp_group(state.pop()) + def visualize(self, scene_pcd, plot=False, render=False, save_view=False): vis = o3d.visualization.Visualizer() vis.create_window() @@ -87,14 +134,6 @@ def visualize(self, scene_pcd, plot=False, render=False, save_view=False): vis.get_view_control().convert_from_pinhole_camera_parameters(param) return vis - - def get_rgbd(self, vis): - rgb = np.array(vis.capture_screen_float_buffer(do_render=True)) - d = np.array(vis.capture_depth_float_buffer(do_render=True)) - intrinsics = vis.get_view_control().convert_to_pinhole_camera_parameters() - - import pdb; pdb.set_trace() - def visualize_grasp( self, @@ -105,56 +144,31 @@ def visualize_grasp( render=False, save_view=False, ) -> None: - timestamp = int(time.time()) - o3d_geometries = grasp_group.to_open3d_geometry_list() - - # k = 5 - # total_pts = scene_pcd - # pts = [x.sample_points_uniformly(number_of_points=5000) for x in o3d_geometries[:k]] - # for pt in pts: - # total_pts += pt - # vis = self.visualize(scene_pcd=total_pts, plot=plot, render=render, save_view=save_view) - # grasp_image = np.array(vis.capture_screen_float_buffer(do_render=True)) - # f = plt.figure() - # plt.imshow(grasp_image) - # f.savefig(f"{timestamp}_grasp_top_{k}.png") - # plt.close(f) - # vis.close() - + grasp_o3d_geometries = grasp_group.to_open3d_geometry_list() + grasp_pointclouds = [ + grasp_o3d_geometry.sample_points_uniformly(number_of_points=5000) + for grasp_o3d_geometry in grasp_o3d_geometries + ] vis = self.visualize(scene_pcd=scene_pcd, plot=plot, render=render, save_view=save_view) + # Save scene grasp_image = np.array(vis.capture_screen_float_buffer(do_render=True)) - f = plt.figure() - plt.imshow(grasp_image) - f.savefig(f"scene.png") + save_img(grasp_image, "scene") - n = min(n, len(o3d_geometries)) + n = min(n, len(grasp_o3d_geometries)) log.info(f"Visualizing top {n} grasps in Open3D...") - grasp_images = [] - for i in range(n): - scene_points = o3d_geometries[i].sample_points_uniformly(number_of_points=5000) - vis.add_geometry(scene_points, reset_bounding_box=False) + # Save scene with each top grasp individually + for i, grasp_pointcloud in enumerate(grasp_pointclouds[:n]): + vis.add_geometry(grasp_pointcloud, reset_bounding_box=False) grasp_image = np.array(vis.capture_screen_float_buffer(do_render=True)) - grasp_images.append(grasp_image) - f = plt.figure() - plt.imshow(grasp_image) - f.savefig(f"grasp_{i + 1}.png") - plt.close(f) - vis.remove_geometry(scene_points, reset_bounding_box=False) - - if plot: - log.info("Plotting with matplotlib...") - w, h = n // 5, 5 - if n % 5 != 0: - w += 1 - - f, axarr = plt.subplots(w, h, figsize=(w * 5, h * 3)) - for i in range(n): - a, b = i // 5, i % 5 - axarr[a, b].imshow(grasp_images[i]) - axarr[a, b].axis("off") - axarr[a, b].set_title(f"Grasp pose top {i + 1}/{n}") - f.show() + save_img(grasp_image, f"scene_with_grasp_{i + 1}") + vis.remove_geometry(grasp_pointcloud, reset_bounding_box=False) + + # Save scene with all grasps + for grasp_pointcloud in grasp_pointclouds[:n]: + vis.add_geometry(grasp_pointcloud, reset_bounding_box=False) + grasp_image = np.array(vis.capture_screen_float_buffer(do_render=True)) + save_img(grasp_image, "scene_with_grasps") return vis diff --git a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py index a7df00fac8..160a93db24 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py @@ -1,12 +1,12 @@ import logging from typing import List +from types import SimpleNamespace import numpy as np import open3d as o3d import a0 from polygrasp import serdes -import pyrealsense2 log = logging.getLogger(__name__) @@ -16,7 +16,7 @@ class PointCloudClient: def __init__( self, - camera_intrinsics: List[pyrealsense2.pyrealsense2.intrinsics], + camera_intrinsics: List[SimpleNamespace], camera_extrinsics: np.ndarray, masks: np.ndarray = None, ): @@ -42,8 +42,6 @@ def __init__( self.extrinsic_transforms[i] = np.eye(4) self.extrinsic_transforms[i, :3, :3] = calibration["camera_base_ori"] self.extrinsic_transforms[i, :3, 3] = calibration["camera_base_pos"] - - self.client = a0.RpcClient(topic_key) if masks is None: intrinsic = camera_intrinsics[0] @@ -75,7 +73,7 @@ def get_pcd(self, rgbds: np.ndarray) -> o3d.geometry.PointCloud: pcds.append(pcd) return pcds - + def get_pcd_i(self, rgbd, i): intrinsic = self.o3_intrinsics[i] transform = self.extrinsic_transforms[i] @@ -98,9 +96,6 @@ def get_pcd_i(self, rgbd, i): return pcd - def segment_pcd(self, rgbd, intrinsics): - raise NotImplementedError - class PointCloudServer: def _get_segmentations(self, rgbd): @@ -114,7 +109,7 @@ def onrequest(req): rgbd = serdes.capnp_to_rgbd(payload) result = self._get_segmentations(rgbd) - log.info("Done.Replying with serialized segmentations...") + log.info("Done. Replying with serialized segmentations...") req.reply(serdes.rgbd_to_capnp(result).to_bytes()) server = a0.RpcServer(topic_key, onrequest, None) @@ -122,17 +117,22 @@ def onrequest(req): while True: pass -class RgbdFeaturesPointCloudClient(PointCloudClient): + +class SegmentationPointCloudClient(PointCloudClient): + def __init__(self, *args, **kwargs): + super().__init__(*args, **kwargs) + self.client = a0.RpcClient(topic_key) + def segment_img(self, rgbd): state = [] def onreply(pkt): state.append(pkt.payload) - + bits = serdes.rgbd_to_capnp(rgbd).to_bytes() self.client.send(bits, onreply) while not state: pass - + return serdes.capnp_to_rgbd(state.pop()) diff --git a/perception/sandbox/polygrasp/src/polygrasp/polygrasp.capnp b/perception/sandbox/polygrasp/src/polygrasp/polygrasp.capnp new file mode 100644 index 0000000000..6172d073db --- /dev/null +++ b/perception/sandbox/polygrasp/src/polygrasp/polygrasp.capnp @@ -0,0 +1,6 @@ +@0xffe8a4b298f1916c; +using Cxx = import "/capnp/c++.capnp"; +struct CollisionRequest { + pcd @0 :Data; + grasps @1 :Data; +} \ No newline at end of file diff --git a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py index c0d6367f0e..5076dab50b 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py +++ b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py @@ -60,7 +60,7 @@ def gripper_open(self): def gripper_close(self): self.gripper.goto(0, 1, 1) - def _move_until_success(self, position, orientation, time_to_go, max_attempts=5): + def move_until_success(self, position, orientation, time_to_go, max_attempts=5): states = [] for _ in range(max_attempts): states += self.move_to_ee_pose( @@ -77,30 +77,35 @@ def _move_until_success(self, position, orientation, time_to_go, max_attempts=5) def select_grasp( self, grasps: graspnetAPI.GraspGroup, scene_pcd: o3d.geometry.PointCloud ) -> graspnetAPI.Grasp: - # TODO: filter out kinematically infeasible grasps - - # TODO: filter out collisions - collision = collision_detector.ModelFreeCollisionDetector(np.asarray(scene_pcd.points)) - collision_mask = collision.detect(grasps) - print(f"Number of colliding grasps: {collision_mask.sum()}/{len(collision_mask)}") - grasps = grasps[~collision_mask] - - # Choose the grasp closest to the neutral position with torch.no_grad(): - grasp, i = min_dist_grasp(self.default_ee_pose, grasps[:5]) + feasible_i = [] + for i, grasp in enumerate(grasps): + grasp_point, grasp_approach_delta, des_ori_quat = compute_des_pose(grasp) + point_a = grasp_point + 1.5 * grasp_approach_delta + point_b = grasp_point + 0.72 * grasp_approach_delta + + def check_feasibility(point): + ik_sol = self.robot_model.inverse_kinematics(torch.Tensor(point), torch.Tensor(des_ori_quat)) + ee_pos, ee_quat = self.robot_model.forward_kinematics(ik_sol) + return torch.linalg.norm(ee_pos - point) < 0.001 + + if check_feasibility(point_a) and check_feasibility(point_b): + feasible_i.append(i) + + if len(feasible_i) < len(grasps): + print(f"Filtered out {len(grasps) - len(feasible_i)}/{len(grasps)} grasps due to kinematic infeasibility.") + + # Choose the grasp closest to the neutral position + grasp, i = min_dist_grasp(self.default_ee_pose, grasps[feasible_i][:5]) print(f"Closest grasp to ee ori, within top 5: {i + 1}") - return grasp - - # return grasps[int(input("Choose grasp index (1-indexed):")) - 1] - - # return grasps[0] + return grasp def grasp(self, grasp: graspnetAPI.Grasp, time_to_go=3, offset=np.array([0.0, 0.0, 0.0])): states = [] grasp_point, grasp_approach_delta, des_ori_quat = compute_des_pose(grasp) self.gripper_open() - states += self._move_until_success( + states += self.move_until_success( position=torch.Tensor(grasp_point + grasp_approach_delta * 1.5 + offset), orientation=torch.Tensor(des_ori_quat), time_to_go=time_to_go, @@ -108,7 +113,7 @@ def grasp(self, grasp: graspnetAPI.Grasp, time_to_go=3, offset=np.array([0.0, 0. grip_ee_pos = torch.Tensor(grasp_point + grasp_approach_delta * 0.72 + offset) - states += self._move_until_success( + states += self.move_until_success( position=grip_ee_pos, orientation=torch.Tensor(des_ori_quat), time_to_go=time_to_go ) self.gripper_close() diff --git a/perception/sandbox/polygrasp/src/polygrasp/serdes.py b/perception/sandbox/polygrasp/src/polygrasp/serdes.py index e5582bcfb8..a1215b4347 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/serdes.py +++ b/perception/sandbox/polygrasp/src/polygrasp/serdes.py @@ -2,15 +2,23 @@ import open3d as o3d import fairomsg +import site +import os import io import numpy as np import open3d import graspnetAPI +import capnp +import polygrasp std_msgs = fairomsg.get_msgs("std_msgs") sensor_msgs = fairomsg.get_msgs("sensor_msgs") geometry_msgs = fairomsg.get_msgs("geometry_msgs") +print("capnp loading polygrasp") +_schema_parser = capnp.SchemaParser() +polygrasp_msgs = _schema_parser.load(os.path.join(polygrasp.__path__[0], "polygrasp.capnp"), imports=site.getsitepackages()) + """Byte conversions""" From d1f33f78e210b928bc588a7ebefd67f0dfa5c4de Mon Sep 17 00:00:00 2001 From: 1heart Date: Tue, 10 May 2022 15:21:58 -0700 Subject: [PATCH 28/69] Cleanup, working on hardware --- .../sandbox/polygrasp/conf/masks/bin1/1.png | Bin 0 -> 2061 bytes .../sandbox/polygrasp/conf/masks/bin1/2.png | Bin 0 -> 1159 bytes .../sandbox/polygrasp/conf/masks/bin1/3.png | Bin 0 -> 1159 bytes .../sandbox/polygrasp/conf/masks/bin2/1.png | Bin 0 -> 1159 bytes .../sandbox/polygrasp/conf/masks/bin2/2.png | Bin 0 -> 2495 bytes .../sandbox/polygrasp/conf/masks/bin2/3.png | Bin 0 -> 1159 bytes .../sandbox/polygrasp/conf/run_grasp.yaml | 10 ++ .../sandbox/polygrasp/scripts/run_grasp.py | 134 ++++++++++-------- perception/sandbox/polygrasp/setup.py | 1 - .../src/polygrasp/collision_detector.py | 129 ----------------- .../polygrasp/src/polygrasp/grasp_rpc.py | 10 +- .../polygrasp/src/polygrasp/pointcloud_rpc.py | 109 +++++++------- .../src/polygrasp/robot_interface.py | 59 +++++--- .../sandbox/polygrasp/src/polygrasp/serdes.py | 18 ++- 14 files changed, 202 insertions(+), 268 deletions(-) create mode 100644 perception/sandbox/polygrasp/conf/masks/bin1/1.png create mode 100644 perception/sandbox/polygrasp/conf/masks/bin1/2.png create mode 100644 perception/sandbox/polygrasp/conf/masks/bin1/3.png create mode 100644 perception/sandbox/polygrasp/conf/masks/bin2/1.png create mode 100644 perception/sandbox/polygrasp/conf/masks/bin2/2.png create mode 100644 perception/sandbox/polygrasp/conf/masks/bin2/3.png delete mode 100644 perception/sandbox/polygrasp/src/polygrasp/collision_detector.py diff --git a/perception/sandbox/polygrasp/conf/masks/bin1/1.png b/perception/sandbox/polygrasp/conf/masks/bin1/1.png new file mode 100644 index 0000000000000000000000000000000000000000..7b1c4d8bd654a26108a116e01a50a003015d7180 GIT binary patch literal 2061 zcmeAS@N?(olHy`uVBq!ia0y~yU}|7sV0^#<6krh8)oj7Qz<$Nk#WAFU@$JDzUIqi6 zLmQs_Uwl(iSajQ&8Wm&tlV{wGK2IctnJ9IVw=Gk}Tw>Y8I|(z~ike3SM#Ez?IgI9p q(ZXP~EF7&HNUR!3sd*7@BCm9be<7Z&wIN1xvXDzj1Lzk9@`EoVLV;^T-G@yGywo5 C(Nrb? literal 0 HcmV?d00001 diff --git a/perception/sandbox/polygrasp/conf/masks/bin1/3.png b/perception/sandbox/polygrasp/conf/masks/bin1/3.png new file mode 100644 index 0000000000000000000000000000000000000000..d14f87f6d419f4fdf2646ebc1747a86d1c7db7f9 GIT binary patch literal 1159 zcmeAS@N?(olHy`uVBq!ia0y~yU}|7sV0^#<6krh8)oj7Qz~blW;uuoF`1YV7BT%q; z!Oi_&l74XL2yS#aA|&YTGRhbYgwd2RnhS``1?>Dzj1Lzk9@`EoVLV;^T-G@yGywo5 C(Nrb? literal 0 HcmV?d00001 diff --git a/perception/sandbox/polygrasp/conf/masks/bin2/1.png b/perception/sandbox/polygrasp/conf/masks/bin2/1.png new file mode 100644 index 0000000000000000000000000000000000000000..d14f87f6d419f4fdf2646ebc1747a86d1c7db7f9 GIT binary patch literal 1159 zcmeAS@N?(olHy`uVBq!ia0y~yU}|7sV0^#<6krh8)oj7Qz~blW;uuoF`1YV7BT%q; z!Oi_&l74XL2yS#aA|&YTGRhbYgwd2RnhS``1?>Dzj1Lzk9@`EoVLV;^T-G@yGywo5 C(Nrb? literal 0 HcmV?d00001 diff --git a/perception/sandbox/polygrasp/conf/masks/bin2/2.png b/perception/sandbox/polygrasp/conf/masks/bin2/2.png new file mode 100644 index 0000000000000000000000000000000000000000..a1ac0680b7b053a74e2a7c97f29952b45f6451dc GIT binary patch literal 2495 zcmeAS@N?(olHy`uVBq!ia0y~yU}|7sV0^#<6krh8)oj7Qz}e>M;uuoF`1asNUIqi6 z!v-(^FTO0k$&}5<>#BRu*NGvuDxvb8qfAIRELga1vMi^`mC{YhjcvR9%2X}{TtC^z zBK6AZ=0peQSaoZmj1{j_+?jYw=f3e6RXiFRqiJI_r;HW_qXpw=H8EOg;%OC}W7c?A V`@v2?D+<&y^K|udS?83{1OR`tKFk0B literal 0 HcmV?d00001 diff --git a/perception/sandbox/polygrasp/conf/masks/bin2/3.png b/perception/sandbox/polygrasp/conf/masks/bin2/3.png new file mode 100644 index 0000000000000000000000000000000000000000..d14f87f6d419f4fdf2646ebc1747a86d1c7db7f9 GIT binary patch literal 1159 zcmeAS@N?(olHy`uVBq!ia0y~yU}|7sV0^#<6krh8)oj7Qz~blW;uuoF`1YV7BT%q; z!Oi_&l74XL2yS#aA|&YTGRhbYgwd2RnhS``1?>Dzj1Lzk9@`EoVLV;^T-G@yGywo5 C(Nrb? literal 0 HcmV?d00001 diff --git a/perception/sandbox/polygrasp/conf/run_grasp.yaml b/perception/sandbox/polygrasp/conf/run_grasp.yaml index a566800a59..94c7788f4d 100644 --- a/perception/sandbox/polygrasp/conf/run_grasp.yaml +++ b/perception/sandbox/polygrasp/conf/run_grasp.yaml @@ -10,4 +10,14 @@ camera_sub: intrinsics_file: conf/intrinsics.json extrinsics_file: ../eyehandcal/calibration.json +masks_1: + - conf/masks/bin1/1.png + - conf/masks/bin1/2.png + - conf/masks/bin1/3.png +masks_2: + - conf/masks/bin2/1.png + - conf/masks/bin2/2.png + - conf/masks/bin2/3.png + view_json_path: conf/o3d_view.json +min_mask_size: 2500 \ No newline at end of file diff --git a/perception/sandbox/polygrasp/scripts/run_grasp.py b/perception/sandbox/polygrasp/scripts/run_grasp.py index 57390cef5a..50e0043375 100644 --- a/perception/sandbox/polygrasp/scripts/run_grasp.py +++ b/perception/sandbox/polygrasp/scripts/run_grasp.py @@ -16,6 +16,8 @@ from polygrasp.pointcloud_rpc import SegmentationPointCloudClient from polygrasp.grasp_rpc import GraspClient +from polygrasp.serdes import load_bw_img + def save_rgbd_masked(rgbd, rgbd_masked): num_cams = rgbd.shape[0] @@ -25,128 +27,142 @@ def save_rgbd_masked(rgbd, rgbd_masked): axarr[0, i].imshow(rgbd[i, :, :, :3].astype(np.uint8)) axarr[1, i].imshow(rgbd_masked[i, :, :, :3].astype(np.uint8)) - f.savefig("rgbd_masked") + f.savefig("rgbd_masked.png") + plt.close(f) + + +def save_obj_masked(obj_masked_rgbd, obj_i, obj_mask_size): + plt.imshow(obj_masked_rgbd[:, :, :3]) + plt.title(f"Object {obj_i}, mask size {obj_mask_size}") + plt.savefig(f"object_{obj_i}_masked") + plt.close() @hydra.main(config_path="../conf", config_name="run_grasp") def main(cfg): print(f"Config: {omegaconf.OmegaConf.to_yaml(cfg, resolve=True)}") print(f"Current working directory: {os.getcwd()}") - # Initialize robot & gripper + + print("Initialize robot & gripper") robot = hydra.utils.instantiate(cfg.robot) robot.gripper_open() robot.go_home() - # Initialize cameras + print("Initializing cameras") cfg.camera_sub.intrinsics_file = hydra.utils.to_absolute_path(cfg.camera_sub.intrinsics_file) cfg.camera_sub.extrinsics_file = hydra.utils.to_absolute_path(cfg.camera_sub.extrinsics_file) cameras = hydra.utils.instantiate(cfg.camera_sub) + + print("Loading camera intrinsics & extrinsics") camera_intrinsics = cameras.get_intrinsics() camera_extrinsics = cameras.get_extrinsics() - # masks = np.ones([3, 480, 640]) + print("Loading camera workspace masks") + masks_1 = np.array( + [load_bw_img(hydra.utils.to_absolute_path(x)) for x in cfg.masks_1], dtype=np.float64 + ) + masks_2 = np.array( + [load_bw_img(hydra.utils.to_absolute_path(x)) for x in cfg.masks_2], dtype=np.float64 + ) - masks = np.zeros([3, 480, 640]) - # masks[0][70:320, 60:400] = 1 - # masks[2][130:350, 240:480] = 1 - masks[0][20:460, :440] = 1 - masks[1][100:480, 180:600] = 1 - - # Connect to grasp candidate selection and pointcloud processor - pcd_client = SegmentationPointCloudClient(camera_intrinsics, camera_extrinsics, masks=masks) + print("Connect to grasp candidate selection and pointcloud processor") + pcd_client = SegmentationPointCloudClient(camera_intrinsics, camera_extrinsics) grasp_client = GraspClient(view_json_path=hydra.utils.to_absolute_path(cfg.view_json_path)) - root_dir = os.getcwd() - - for outer_i in range(0, 10): + root_working_dir = os.getcwd() + for outer_i in range(1, 10): cam_i = outer_i % 2 print(f"=== Starting outer loop with cam {cam_i} ===") if cam_i == 0: + masks = masks_1 hori_offset = torch.Tensor([0, 0.4, 0]) grasp_offset = np.array([0.1, 0.0, 0.05]) time_to_go = 2 else: + masks = masks_2 hori_offset = torch.Tensor([0, -0.4, 0]) grasp_offset = np.array([0.1, 0.1, 0.1]) time_to_go = 3 num_iters = 10 for i in range(num_iters): - os.chdir(root_dir) + # Create directory for current grasp iteration + os.chdir(root_working_dir) timestamp = int(time.time()) os.makedirs(f"{timestamp}") os.chdir(f"{timestamp}") - - print(f"Grasp {i + 1} / num_iters, in {os.getcwd()}") + print(f"Grasp {i + 1}/{num_iters}, logging to {os.getcwd()}") print("Getting rgbd and pcds..") rgbd = cameras.get_rgbd() rgbd_masked = rgbd * masks[:, :, :, None] - pcds = pcd_client.get_pcd(rgbd) - + scene_pcd = pcd_client.get_pcd(rgbd) + cam_pcd = pcd_client.get_pcd_i(rgbd[cam_i], cam_i) save_rgbd_masked(rgbd, rgbd_masked) - scene_pcd = pcds[0] - for pcd in pcds[1:]: - scene_pcd += pcd - # Get RGBD & pointcloud print("Segmenting image...") - labels = pcd_client.segment_img(rgbd_masked[cam_i]) - - obj_to_grasps = {} - num_objs = int(labels.max()) - print(f"Number of objs: {num_objs}") - min_mask_size = 2500 - for obj_i in range(1, num_objs + 1): - obj_mask = labels == obj_i - obj_mask_size = obj_mask.sum() - - if obj_mask_size < min_mask_size: - continue - - obj_masked_rgbd = rgbd_masked[cam_i] * obj_mask[:, :, None] + obj_masked_rgbds, obj_masks = pcd_client.segment_img( + rgbd_masked[cam_i], min_mask_size=cfg.min_mask_size + ) + if len(obj_masked_rgbds) == 0: + print(f"Failed to find any objects with mask size > {cfg.min_mask_size}!") + break - plt.imshow(obj_masked_rgbd[:, :, :3]) - plt.title(f"Object {obj_i}, mask size {obj_mask_size}") - plt.savefig(f"object_{obj_i}_masked") - plt.close() - # plt.show() + for obj_i, (obj_masked_rgbd, obj_mask) in enumerate(zip(obj_masked_rgbds, obj_masks)): + obj_mask_size = obj_mask.sum() + save_obj_masked(obj_masked_rgbd, obj_i, obj_mask_size) print(f"Getting obj {obj_i} pcd...") pcd = pcd_client.get_pcd_i(obj_masked_rgbd, cam_i) print(f"Getting obj {obj_i} grasp...") grasp_group = grasp_client.get_grasps(pcd) - filtered_grasp_group = grasp_client.get_collision(grasp_group, scene_pcd) + filtered_grasp_group = grasp_client.get_collision(grasp_group, cam_pcd) + if len(filtered_grasp_group) < len(grasp_group): + print( + f"Filtered {len(grasp_group) - len(filtered_grasp_group)}/{len(grasp_group)} grasps due to collision." + ) if len(filtered_grasp_group) > 0: - obj_to_grasps[obj_i] = filtered_grasp_group break - if len(obj_to_grasps) == 0: - print(f"Failed to find any objects with mask size > {min_mask_size}!") - break - - curr_grasps = grasp_group - # Choose a grasp for this object - grasp_client.visualize_grasp(pcds[cam_i], curr_grasps) - chosen_grasp = robot.select_grasp(curr_grasps, scene_pcd) + grasp_client.visualize_grasp(scene_pcd, filtered_grasp_group) + chosen_grasp = robot.select_grasp(filtered_grasp_group) # Execute grasp traj, success = robot.grasp(chosen_grasp, offset=grasp_offset, time_to_go=time_to_go) print(f"Grasp success: {success}") if success: - print(f"Moving end-effector up") + print("Placing object in hand") curr_pose, curr_ori = robot.get_ee_pose() - states = robot.move_until_success(position=curr_pose + torch.Tensor([0, 0, 0.2]), orientation=curr_ori, time_to_go=time_to_go) - states = robot.move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.2]) + hori_offset, orientation=curr_ori, time_to_go=time_to_go) - states = robot.move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.05]) + hori_offset, orientation=curr_ori, time_to_go=time_to_go) - + states = robot.move_until_success( + position=curr_pose + torch.Tensor([0, 0, 0.2]), + orientation=curr_ori, + time_to_go=time_to_go, + ) + states = robot.move_until_success( + position=curr_pose + torch.Tensor([0, 0.0, 0.2]) + hori_offset, + orientation=curr_ori, + time_to_go=time_to_go, + ) + states = robot.move_until_success( + position=curr_pose + torch.Tensor([0, 0.0, 0.05]) + hori_offset, + orientation=curr_ori, + time_to_go=time_to_go, + ) + + print("Opening gripper") robot.gripper_open() curr_pose, curr_ori = robot.get_ee_pose() - states = robot.move_until_success(position=curr_pose + torch.Tensor([0, 0.0, 0.2]), orientation=curr_ori, time_to_go=time_to_go) + states = robot.move_until_success( + position=curr_pose + torch.Tensor([0, 0.0, 0.2]), + orientation=curr_ori, + time_to_go=time_to_go, + ) + + print("Going home") robot.go_home() diff --git a/perception/sandbox/polygrasp/setup.py b/perception/sandbox/polygrasp/setup.py index 68dfed54bc..a6b51119ab 100644 --- a/perception/sandbox/polygrasp/setup.py +++ b/perception/sandbox/polygrasp/setup.py @@ -9,7 +9,6 @@ install_requires = [ - "grpcio-tools", "mrp", "fairomsg", ] diff --git a/perception/sandbox/polygrasp/src/polygrasp/collision_detector.py b/perception/sandbox/polygrasp/src/polygrasp/collision_detector.py deleted file mode 100644 index 761a27d45b..0000000000 --- a/perception/sandbox/polygrasp/src/polygrasp/collision_detector.py +++ /dev/null @@ -1,129 +0,0 @@ -""" Collision detection to remove collided grasp pose predictions. -Author: chenxi-wang -""" - -import os -import sys -import numpy as np -import open3d as o3d - -class ModelFreeCollisionDetector(): - """ Collision detection in scenes without object labels. Current finger width and length are fixed. - - Input: - scene_points: [numpy.ndarray, (N,3), numpy.float32] - the scene points to detect - voxel_size: [float] - used for downsample - - Example usage: - mfcdetector = ModelFreeCollisionDetector(scene_points, voxel_size=0.005) - collision_mask = mfcdetector.detect(grasp_group, approach_dist=0.03) - collision_mask, iou_list = mfcdetector.detect(grasp_group, approach_dist=0.03, collision_thresh=0.05, return_ious=True) - collision_mask, empty_mask = mfcdetector.detect(grasp_group, approach_dist=0.03, collision_thresh=0.05, - return_empty_grasp=True, empty_thresh=0.01) - collision_mask, empty_mask, iou_list = mfcdetector.detect(grasp_group, approach_dist=0.03, collision_thresh=0.05, - return_empty_grasp=True, empty_thresh=0.01, return_ious=True) - """ - def __init__(self, scene_points, voxel_size=0.005): - self.finger_width = 0.01 - self.finger_length = 0.06 - self.voxel_size = voxel_size - scene_cloud = o3d.geometry.PointCloud() - scene_cloud.points = o3d.utility.Vector3dVector(scene_points) - scene_cloud = scene_cloud.voxel_down_sample(voxel_size) - self.scene_points = np.array(scene_cloud.points) - - def detect(self, grasp_group, approach_dist=0.03, collision_thresh=0.05, return_empty_grasp=False, empty_thresh=0.01, return_ious=False): - """ Detect collision of grasps. - - Input: - grasp_group: [GraspGroup, M grasps] - the grasps to check - approach_dist: [float] - the distance for a gripper to move along approaching direction before grasping - this shifting space requires no point either - collision_thresh: [float] - if global collision iou is greater than this threshold, - a collision is detected - return_empty_grasp: [bool] - if True, return a mask to imply whether there are objects in a grasp - empty_thresh: [float] - if inner space iou is smaller than this threshold, - a collision is detected - only set when [return_empty_grasp] is True - return_ious: [bool] - if True, return global collision iou and part collision ious - - Output: - collision_mask: [numpy.ndarray, (M,), numpy.bool] - True implies collision - [optional] empty_mask: [numpy.ndarray, (M,), numpy.bool] - True implies empty grasp - only returned when [return_empty_grasp] is True - [optional] iou_list: list of [numpy.ndarray, (M,), numpy.float32] - global and part collision ious, containing - [global_iou, left_iou, right_iou, bottom_iou, shifting_iou] - only returned when [return_ious] is True - """ - approach_dist = max(approach_dist, self.finger_width) - T = grasp_group.translations - R = grasp_group.rotation_matrices - heights = grasp_group.heights[:,np.newaxis] - depths = grasp_group.depths[:,np.newaxis] - widths = grasp_group.widths[:,np.newaxis] - targets = self.scene_points[np.newaxis,:,:] - T[:,np.newaxis,:] - targets = np.matmul(targets, R) - - ## collision detection - # height mask - mask1 = ((targets[:,:,2] > -heights/2) & (targets[:,:,2] < heights/2)) - # left finger mask - mask2 = ((targets[:,:,0] > depths - self.finger_length) & (targets[:,:,0] < depths)) - mask3 = (targets[:,:,1] > -(widths/2 + self.finger_width)) - mask4 = (targets[:,:,1] < -widths/2) - # right finger mask - mask5 = (targets[:,:,1] < (widths/2 + self.finger_width)) - mask6 = (targets[:,:,1] > widths/2) - # bottom mask - mask7 = ((targets[:,:,0] <= depths - self.finger_length)\ - & (targets[:,:,0] > depths - self.finger_length - self.finger_width)) - # shifting mask - mask8 = ((targets[:,:,0] <= depths - self.finger_length - self.finger_width)\ - & (targets[:,:,0] > depths - self.finger_length - self.finger_width - approach_dist)) - - # get collision mask of each point - left_mask = (mask1 & mask2 & mask3 & mask4) - right_mask = (mask1 & mask2 & mask5 & mask6) - bottom_mask = (mask1 & mask3 & mask5 & mask7) - shifting_mask = (mask1 & mask3 & mask5 & mask8) - global_mask = (left_mask | right_mask | bottom_mask | shifting_mask) - - # calculate equivalant volume of each part - left_right_volume = (heights * self.finger_length * self.finger_width / (self.voxel_size**3)).reshape(-1) - bottom_volume = (heights * (widths+2*self.finger_width) * self.finger_width / (self.voxel_size**3)).reshape(-1) - shifting_volume = (heights * (widths+2*self.finger_width) * approach_dist / (self.voxel_size**3)).reshape(-1) - volume = left_right_volume*2 + bottom_volume + shifting_volume - - # get collision iou of each part - global_iou = global_mask.sum(axis=1) / (volume+1e-6) - - # get collison mask - collision_mask = (global_iou > collision_thresh) - - if not (return_empty_grasp or return_ious): - return collision_mask - - ret_value = [collision_mask,] - if return_empty_grasp: - inner_mask = (mask1 & mask2 & (~mask4) & (~mask6)) - inner_volume = (heights * self.finger_length * widths / (self.voxel_size**3)).reshape(-1) - empty_mask = (inner_mask.sum(axis=-1)/inner_volume < empty_thresh) - ret_value.append(empty_mask) - if return_ious: - left_iou = left_mask.sum(axis=1) / (left_right_volume+1e-6) - right_iou = right_mask.sum(axis=1) / (left_right_volume+1e-6) - bottom_iou = bottom_mask.sum(axis=1) / (bottom_volume+1e-6) - shifting_iou = shifting_mask.sum(axis=1) / (shifting_volume+1e-6) - ret_value.append([global_iou, left_iou, right_iou, bottom_iou, shifting_iou]) - return ret_value diff --git a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py index e3d408e4bb..bf1df72305 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/grasp_rpc.py @@ -26,8 +26,10 @@ def save_img(img, name): class GraspServer: def _get_grasps(self, pcd: o3d.geometry.PointCloud) -> np.ndarray: raise NotImplementedError - - def _get_collisions(self, grasps: graspnetAPI.GraspGroup, scene_pcd: o3d.geometry.PointCloud): + + def _get_collisions( + self, grasps: graspnetAPI.GraspGroup, scene_pcd: o3d.geometry.PointCloud + ) -> graspnetAPI.GraspGroup: raise NotImplementedError def start(self): @@ -42,6 +44,7 @@ def grasp_onrequest(req): log.info(f"Done. Replying with serialized grasp group...") req.reply(serdes.grasp_group_to_capnp(grasp_group).to_bytes()) + grasp_server = a0.RpcServer(grasp_topic_key, grasp_onrequest, None) def collision_onrequest(req): @@ -55,6 +58,7 @@ def collision_onrequest(req): filtered_grasp_group = self._get_collisions(grasp_group, scene_pcd) log.info(f"Done. Replying with serialized filtered grasps...") req.reply(serdes.grasp_group_to_bytes(filtered_grasp_group)) + collision_server = a0.RpcServer(collision_topic_key, collision_onrequest, None) while True: @@ -96,7 +100,7 @@ def onreply(pkt): pass return serdes.capnp_to_grasp_group(state.pop()) - + def get_collision(self, grasps: graspnetAPI.GraspGroup, scene_pcd: o3d.geometry.PointCloud): state = [] diff --git a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py index 160a93db24..a28fcdc2cd 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py +++ b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py @@ -18,11 +18,13 @@ def __init__( self, camera_intrinsics: List[SimpleNamespace], camera_extrinsics: np.ndarray, - masks: np.ndarray = None, ): assert len(camera_intrinsics) == len(camera_extrinsics) self.n_cams = len(camera_intrinsics) + self.width = camera_intrinsics[0].width + self.height = camera_intrinsics[0].height + # Convert to open3d intrinsics self.o3_intrinsics = [ o3d.camera.PinholeCameraIntrinsic( @@ -43,42 +45,15 @@ def __init__( self.extrinsic_transforms[i, :3, :3] = calibration["camera_base_ori"] self.extrinsic_transforms[i, :3, 3] = calibration["camera_base_pos"] - if masks is None: - intrinsic = camera_intrinsics[0] - self.masks = np.ones([self.n_cams, intrinsic.width, intrinsic.height]) - else: - self.masks = masks - - def get_pcd(self, rgbds: np.ndarray) -> o3d.geometry.PointCloud: - pcds = [] - for rgbd, intrinsic, transform, mask in zip( - rgbds, self.o3_intrinsics, self.extrinsic_transforms, self.masks - ): - # The specific casting here seems to be very important, even though - # rgbd should already be in np.uint16 type... - img = (rgbd[:, :, :3] * mask[:, :, None]).astype(np.uint8) - depth = (rgbd[:, :, 3] * mask).astype(np.uint16) - - o3d_img = o3d.cuda.pybind.geometry.Image(img) - o3d_depth = o3d.cuda.pybind.geometry.Image(depth) - - rgbd_image = o3d.geometry.RGBDImage.create_from_color_and_depth( - o3d_img, - o3d_depth, - convert_rgb_to_intensity=False, - ) - - pcd = o3d.geometry.PointCloud.create_from_rgbd_image(rgbd_image, intrinsic) - pcd.transform(transform) - pcds.append(pcd) - - return pcds + def get_pcd_i(self, rgbd: np.ndarray, cam_i: int, mask: np.ndarray = None): + if mask is None: + mask = np.ones([self.height, self.width]) - def get_pcd_i(self, rgbd, i): - intrinsic = self.o3_intrinsics[i] - transform = self.extrinsic_transforms[i] - mask = self.masks[i] + intrinsic = self.o3_intrinsics[cam_i] + transform = self.extrinsic_transforms[cam_i] + # The specific casting here seems to be very important, even though + # rgbd should already be in np.uint16 type... img = (rgbd[:, :, :3] * mask[:, :, None]).astype(np.uint8) depth = (rgbd[:, :, 3] * mask).astype(np.uint16) @@ -96,6 +71,50 @@ def get_pcd_i(self, rgbd, i): return pcd + def get_pcd(self, rgbds: np.ndarray, masks: np.ndarray = None) -> o3d.geometry.PointCloud: + if masks is None: + masks = np.ones([self.n_cams, self.height, self.width]) + pcds = [self.get_pcd_i(rgbds[i], i, masks[i]) for i in range(len(rgbds))] + result = pcds[0] + for pcd in pcds[1:]: + result += pcd + return result + + +class SegmentationPointCloudClient(PointCloudClient): + def __init__(self, *args, **kwargs): + super().__init__(*args, **kwargs) + self.client = a0.RpcClient(topic_key) + + def segment_img(self, rgbd, min_mask_size=2500): + state = [] + + def onreply(pkt): + state.append(pkt.payload) + + bits = serdes.rgbd_to_capnp(rgbd).to_bytes() + self.client.send(bits, onreply) + + while not state: + pass + + obj_masked_rgbds = [] + obj_masks = [] + + labels = serdes.capnp_to_rgbd(state.pop()) + num_objs = int(labels.max()) + for obj_i in range(1, num_objs + 1): + obj_mask = labels == obj_i + + obj_mask_size = obj_mask.sum() + if obj_mask_size < min_mask_size: + continue + obj_masked_rgbd = rgbd * obj_mask[:, :, None] + obj_masked_rgbds.append(obj_masked_rgbd) + obj_masks.append(obj_mask) + + return obj_masked_rgbds, obj_masks + class PointCloudServer: def _get_segmentations(self, rgbd): @@ -116,23 +135,3 @@ def onrequest(req): log.info("Starting server...") while True: pass - - -class SegmentationPointCloudClient(PointCloudClient): - def __init__(self, *args, **kwargs): - super().__init__(*args, **kwargs) - self.client = a0.RpcClient(topic_key) - - def segment_img(self, rgbd): - state = [] - - def onreply(pkt): - state.append(pkt.payload) - - bits = serdes.rgbd_to_capnp(rgbd).to_bytes() - self.client.send(bits, onreply) - - while not state: - pass - - return serdes.capnp_to_rgbd(state.pop()) diff --git a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py index 5076dab50b..5200939993 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py +++ b/perception/sandbox/polygrasp/src/polygrasp/robot_interface.py @@ -10,8 +10,6 @@ import graspnetAPI import polymetis -from polygrasp import collision_detector - def compute_des_pose(best_grasp): grasp_point = best_grasp.translation @@ -37,22 +35,30 @@ def grasp_to_pose(grasp: graspnetAPI.Grasp): def compute_quat_dist(a, b): - return torch.acos((2*(a * b).sum()**2 - 1).clip(-1, 1)) + return torch.acos((2 * (a * b).sum() ** 2 - 1).clip(-1, 1)) + def min_dist_grasp(default_ee_pose, grasps): with torch.no_grad(): - rots_as_quat = [torch.Tensor(R.from_matrix(grasp.rotation_matrix).as_quat()) for grasp in grasps] + rots_as_quat = [ + torch.Tensor(R.from_matrix(grasp.rotation_matrix).as_quat()) for grasp in grasps + ] dists = [compute_quat_dist(rot, default_ee_pose) for rot in rots_as_quat] i = torch.argmin(torch.Tensor(dists)).item() print(f"Grasp {i} has angle {dists[i]} from reference.") return grasps[i], i + class GraspingRobotInterface(polymetis.RobotInterface): - def __init__(self, gripper: polymetis.GripperInterface, *args, **kwargs): + def __init__( + self, gripper: polymetis.GripperInterface, k_approach=1.5, k_grasp=0.72, *args, **kwargs + ): super().__init__(*args, **kwargs) self.gripper = hydra.utils.instantiate(gripper) - self.default_ee_pose = torch.Tensor([ 0.9418, 0.3289, -0.0368, -0.0592]) + self.default_ee_pose = torch.Tensor([0.9418, 0.3289, -0.0368, -0.0592]) + self.k_approach = k_approach + self.k_grasp = k_grasp def gripper_open(self): self.gripper.goto(1, 1, 1) @@ -60,7 +66,9 @@ def gripper_open(self): def gripper_close(self): self.gripper.goto(0, 1, 1) - def move_until_success(self, position, orientation, time_to_go, max_attempts=5): + def move_until_success( + self, position, orientation, time_to_go, max_attempts=5, success_dist=0.2 + ): states = [] for _ in range(max_attempts): states += self.move_to_ee_pose( @@ -70,48 +78,59 @@ def move_until_success(self, position, orientation, time_to_go, max_attempts=5): print(f"Dist to goal: {torch.linalg.norm(curr_ee_pos - position)}") - if states[-1].prev_command_successful and torch.linalg.norm(curr_ee_pos - position) < 0.2: # TODO: orientation diff + if ( + states[-1].prev_command_successful + and torch.linalg.norm(curr_ee_pos - position) < success_dist + ): # TODO: orientation diff break return states - def select_grasp( - self, grasps: graspnetAPI.GraspGroup, scene_pcd: o3d.geometry.PointCloud - ) -> graspnetAPI.Grasp: + def select_grasp(self, grasps: graspnetAPI.GraspGroup) -> graspnetAPI.Grasp: with torch.no_grad(): feasible_i = [] for i, grasp in enumerate(grasps): grasp_point, grasp_approach_delta, des_ori_quat = compute_des_pose(grasp) - point_a = grasp_point + 1.5 * grasp_approach_delta - point_b = grasp_point + 0.72 * grasp_approach_delta + point_a = grasp_point + self.k_approach * grasp_approach_delta + point_b = grasp_point + self.k_grasp * grasp_approach_delta def check_feasibility(point): - ik_sol = self.robot_model.inverse_kinematics(torch.Tensor(point), torch.Tensor(des_ori_quat)) + ik_sol = self.robot_model.inverse_kinematics( + torch.Tensor(point), torch.Tensor(des_ori_quat) + ) ee_pos, ee_quat = self.robot_model.forward_kinematics(ik_sol) return torch.linalg.norm(ee_pos - point) < 0.001 if check_feasibility(point_a) and check_feasibility(point_b): feasible_i.append(i) - + if len(feasible_i) < len(grasps): - print(f"Filtered out {len(grasps) - len(feasible_i)}/{len(grasps)} grasps due to kinematic infeasibility.") + print( + f"Filtered out {len(grasps) - len(feasible_i)}/{len(grasps)} grasps due to kinematic infeasibility." + ) # Choose the grasp closest to the neutral position grasp, i = min_dist_grasp(self.default_ee_pose, grasps[feasible_i][:5]) print(f"Closest grasp to ee ori, within top 5: {i + 1}") return grasp - def grasp(self, grasp: graspnetAPI.Grasp, time_to_go=3, offset=np.array([0.0, 0.0, 0.0])): + def grasp( + self, + grasp: graspnetAPI.Grasp, + time_to_go=3, + offset=np.array([0.0, 0.0, 0.0]), + gripper_width_success_threshold=0.0005, + ): states = [] grasp_point, grasp_approach_delta, des_ori_quat = compute_des_pose(grasp) self.gripper_open() states += self.move_until_success( - position=torch.Tensor(grasp_point + grasp_approach_delta * 1.5 + offset), + position=torch.Tensor(grasp_point + grasp_approach_delta * self.k_approach + offset), orientation=torch.Tensor(des_ori_quat), time_to_go=time_to_go, ) - grip_ee_pos = torch.Tensor(grasp_point + grasp_approach_delta * 0.72 + offset) + grip_ee_pos = torch.Tensor(grasp_point + grasp_approach_delta * self.k_grasp + offset) states += self.move_until_success( position=grip_ee_pos, orientation=torch.Tensor(des_ori_quat), time_to_go=time_to_go @@ -125,6 +144,6 @@ def grasp(self, grasp: graspnetAPI.Grasp, time_to_go=3, offset=np.array([0.0, 0. width = gripper_state.width print(f"Gripper width: {width}") - success = width > 0.0005 + success = width > gripper_width_success_threshold return states, success diff --git a/perception/sandbox/polygrasp/src/polygrasp/serdes.py b/perception/sandbox/polygrasp/src/polygrasp/serdes.py index a1215b4347..178075e0d0 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/serdes.py +++ b/perception/sandbox/polygrasp/src/polygrasp/serdes.py @@ -11,13 +11,17 @@ import capnp import polygrasp +import cv2 + std_msgs = fairomsg.get_msgs("std_msgs") sensor_msgs = fairomsg.get_msgs("sensor_msgs") geometry_msgs = fairomsg.get_msgs("geometry_msgs") print("capnp loading polygrasp") _schema_parser = capnp.SchemaParser() -polygrasp_msgs = _schema_parser.load(os.path.join(polygrasp.__path__[0], "polygrasp.capnp"), imports=site.getsitepackages()) +polygrasp_msgs = _schema_parser.load( + os.path.join(polygrasp.__path__[0], "polygrasp.capnp"), imports=site.getsitepackages() +) """Byte conversions""" @@ -84,12 +88,24 @@ def capnp_to_grasp_group(blob): gg = bytes_to_grasp_group(capnp_gg.data) return gg + def rgbd_to_capnp(rgbd): img = sensor_msgs.Image() img.data = np_to_bytes(rgbd) return img + def capnp_to_rgbd(blob): img = sensor_msgs.Image.from_bytes(blob) return bytes_to_np(img.data) + + +def load_bw_img(path): + grayscale_img = cv2.imread(path, cv2.IMREAD_GRAYSCALE) + thresh, bw_img = cv2.threshold(grayscale_img, 128, 255, cv2.THRESH_BINARY | cv2.THRESH_OTSU) + return bw_img.astype(bool) + + +def save_bw_img(img, name): + cv2.imwrite(f"{name}.png", img * 255) From 11bc040dd88c03539ed5ad514d4835ec6283d050 Mon Sep 17 00:00:00 2001 From: 1heart Date: Tue, 10 May 2022 15:38:13 -0700 Subject: [PATCH 29/69] Update readme --- perception/sandbox/polygrasp/README.md | 32 +++++++++++++++++++++++++- perception/sandbox/polygrasp/setup.py | 9 ++++++++ 2 files changed, 40 insertions(+), 1 deletion(-) diff --git a/perception/sandbox/polygrasp/README.md b/perception/sandbox/polygrasp/README.md index f1b7ce6598..26d4fd4b28 100644 --- a/perception/sandbox/polygrasp/README.md +++ b/perception/sandbox/polygrasp/README.md @@ -2,7 +2,37 @@ ## Installation +In a new conda environment, [install Polymetis](https://facebookresearch.github.io/fairo/polymetis/installation.html#simple). + +Install the package itself: + ```bash -pip install ../../realsense_driver pip install -e . ``` + +Then, follow the instructions in the forked repos to create the necessary isolated conda environments: + +1. [UnseenObjectClustering](https://github.com/1heart/UnseenObjectClustering) +1. [graspnet-baseline](https://github.com/1heart/graspnet-baseline) + +## Usage + +Make necessary configuration modifications. For example: +- [conf/run_grasp.yaml](./conf/run_grasp.yaml) contains the configuration, e.g. robot IP. +- [conf/masks/](./conf/masks/) contains a folder to define workspace masks for each camera, for each bin. +- We expect calibrated camera parameters out of [eyehandcal](../eyehandcal). + + +Start the necessary pointcloud/grasping/gripper servers: + +```bash +mrp up +``` + +The script to bring everything together and execute the grasps: + +```bash +python scripts/run_grasp.py # Connect to robot, gripper, servers; run grasp +``` + +This continuously grasps from one bin to the other until there are no more objects detected in the workspace; then it moves the objects the other direction. diff --git a/perception/sandbox/polygrasp/setup.py b/perception/sandbox/polygrasp/setup.py index a6b51119ab..2beb05ba5a 100644 --- a/perception/sandbox/polygrasp/setup.py +++ b/perception/sandbox/polygrasp/setup.py @@ -10,7 +10,15 @@ install_requires = [ "mrp", + "graspnetAPI", + "open3d", "fairomsg", + "realsense_wrapper", +] + +dependency_links = [ + "git+https://github.com/facebookresearch/fairo.git@main#subdirectory=msg", + "git+https://github.com/facebookresearch/fairo.git@main#subdirectory=perception/realsense_driver", ] setup( @@ -23,4 +31,5 @@ include_package_data=True, scripts=["scripts/run_grasp.py"], install_requires=install_requires, + dependency_links=dependency_links, ) From f4ecc86b37d3fb5169e16d36508e2458bc37d904 Mon Sep 17 00:00:00 2001 From: 1heart Date: Thu, 12 May 2022 14:34:08 -0700 Subject: [PATCH 30/69] Segmentation separate service, move pcd to cam --- .../sandbox/polygrasp/conf/run_grasp.yaml | 2 +- perception/sandbox/polygrasp/msetup.py | 2 +- .../sandbox/polygrasp/scripts/run_grasp.py | 16 +- .../polygrasp/src/polygrasp/cam_pub_sub.py | 76 +++++++++- .../polygrasp/src/polygrasp/pointcloud_rpc.py | 137 ------------------ .../src/polygrasp/segmentation_rpc.py | 64 ++++++++ 6 files changed, 142 insertions(+), 155 deletions(-) delete mode 100644 perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py create mode 100644 perception/sandbox/polygrasp/src/polygrasp/segmentation_rpc.py diff --git a/perception/sandbox/polygrasp/conf/run_grasp.yaml b/perception/sandbox/polygrasp/conf/run_grasp.yaml index 94c7788f4d..416e3ed99f 100644 --- a/perception/sandbox/polygrasp/conf/run_grasp.yaml +++ b/perception/sandbox/polygrasp/conf/run_grasp.yaml @@ -6,7 +6,7 @@ robot: _target_: polymetis.GripperInterface camera_sub: - _target_: polygrasp.cam_pub_sub.CameraSubscriber + _target_: polygrasp.cam_pub_sub.PointCloudSubscriber intrinsics_file: conf/intrinsics.json extrinsics_file: ../eyehandcal/calibration.json diff --git a/perception/sandbox/polygrasp/msetup.py b/perception/sandbox/polygrasp/msetup.py index 77566fc35d..a458baaf7f 100644 --- a/perception/sandbox/polygrasp/msetup.py +++ b/perception/sandbox/polygrasp/msetup.py @@ -1,7 +1,7 @@ import mrp mrp.process( - name="pcd_server", + name="segmentation_server", runtime=mrp.Conda( run_command=["python", "-m", "utils.mrp_wrapper"], use_named_env="unseen-object-clustering", diff --git a/perception/sandbox/polygrasp/scripts/run_grasp.py b/perception/sandbox/polygrasp/scripts/run_grasp.py index 50e0043375..ad4bbd6acc 100644 --- a/perception/sandbox/polygrasp/scripts/run_grasp.py +++ b/perception/sandbox/polygrasp/scripts/run_grasp.py @@ -14,7 +14,7 @@ import hydra import omegaconf -from polygrasp.pointcloud_rpc import SegmentationPointCloudClient +from polygrasp.segmentation_rpc import SegmentationClient from polygrasp.grasp_rpc import GraspClient from polygrasp.serdes import load_bw_img @@ -53,10 +53,6 @@ def main(cfg): cfg.camera_sub.extrinsics_file = hydra.utils.to_absolute_path(cfg.camera_sub.extrinsics_file) cameras = hydra.utils.instantiate(cfg.camera_sub) - print("Loading camera intrinsics & extrinsics") - camera_intrinsics = cameras.get_intrinsics() - camera_extrinsics = cameras.get_extrinsics() - print("Loading camera workspace masks") masks_1 = np.array( [load_bw_img(hydra.utils.to_absolute_path(x)) for x in cfg.masks_1], dtype=np.float64 @@ -66,7 +62,7 @@ def main(cfg): ) print("Connect to grasp candidate selection and pointcloud processor") - pcd_client = SegmentationPointCloudClient(camera_intrinsics, camera_extrinsics) + segmentation_client = SegmentationClient() grasp_client = GraspClient(view_json_path=hydra.utils.to_absolute_path(cfg.view_json_path)) root_working_dir = os.getcwd() @@ -97,13 +93,13 @@ def main(cfg): print("Getting rgbd and pcds..") rgbd = cameras.get_rgbd() rgbd_masked = rgbd * masks[:, :, :, None] - scene_pcd = pcd_client.get_pcd(rgbd) - cam_pcd = pcd_client.get_pcd_i(rgbd[cam_i], cam_i) + scene_pcd = cameras.get_pcd(rgbd) + cam_pcd = cameras.get_pcd_i(rgbd[cam_i], cam_i) save_rgbd_masked(rgbd, rgbd_masked) # Get RGBD & pointcloud print("Segmenting image...") - obj_masked_rgbds, obj_masks = pcd_client.segment_img( + obj_masked_rgbds, obj_masks = segmentation_client.segment_img( rgbd_masked[cam_i], min_mask_size=cfg.min_mask_size ) if len(obj_masked_rgbds) == 0: @@ -115,7 +111,7 @@ def main(cfg): save_obj_masked(obj_masked_rgbd, obj_i, obj_mask_size) print(f"Getting obj {obj_i} pcd...") - pcd = pcd_client.get_pcd_i(obj_masked_rgbd, cam_i) + pcd = cameras.get_pcd_i(obj_masked_rgbd, cam_i) print(f"Getting obj {obj_i} grasp...") grasp_group = grasp_client.get_grasps(pcd) filtered_grasp_group = grasp_client.get_collision(grasp_group, cam_pcd) diff --git a/perception/sandbox/polygrasp/src/polygrasp/cam_pub_sub.py b/perception/sandbox/polygrasp/src/polygrasp/cam_pub_sub.py index 1edf5b4af8..af1d94a20f 100644 --- a/perception/sandbox/polygrasp/src/polygrasp/cam_pub_sub.py +++ b/perception/sandbox/polygrasp/src/polygrasp/cam_pub_sub.py @@ -2,6 +2,9 @@ import json from types import SimpleNamespace +import numpy as np +import open3d as o3d + import a0 import realsense_wrapper from polygrasp import serdes @@ -21,16 +24,77 @@ def __init__(self, intrinsics_file, extrinsics_file): self.sub = a0.SubscriberSync(a0.PubSubTopic(topic), a0.INIT_MOST_RECENT) - def get_intrinsics(self): - return self.intrinsics - - def get_extrinsics(self): - return self.extrinsics - def get_rgbd(self): return serdes.bytes_to_np(self.sub.read().payload) +class PointCloudSubscriber(CameraSubscriber): + def __init__(self, *args, **kwargs): + super().__init__(*args, **kwargs) + + assert len(self.intrinsics) == len(self.extrinsics) + self.n_cams = len(self.intrinsics) + + self.width = self.intrinsics[0].width + self.height = self.intrinsics[0].height + + # Convert to open3d intrinsics + self.o3_intrinsics = [ + o3d.camera.PinholeCameraIntrinsic( + width=intrinsic.width, + height=intrinsic.height, + fx=intrinsic.fx, + fy=intrinsic.fy, + cx=intrinsic.ppx, + cy=intrinsic.ppy, + ) + for intrinsic in self.intrinsics + ] + + # Convert to numpy homogeneous transforms + self.extrinsic_transforms = np.empty([self.n_cams, 4, 4]) + for i, calibration in enumerate(self.extrinsics): + self.extrinsic_transforms[i] = np.eye(4) + self.extrinsic_transforms[i, :3, :3] = calibration["camera_base_ori"] + self.extrinsic_transforms[i, :3, 3] = calibration["camera_base_pos"] + + def get_pcd_i(self, rgbd: np.ndarray, cam_i: int, mask: np.ndarray = None): + if mask is None: + mask = np.ones([self.height, self.width]) + + intrinsic = self.o3_intrinsics[cam_i] + transform = self.extrinsic_transforms[cam_i] + + # The specific casting here seems to be very important, even though + # rgbd should already be in np.uint16 type... + img = (rgbd[:, :, :3] * mask[:, :, None]).astype(np.uint8) + depth = (rgbd[:, :, 3] * mask).astype(np.uint16) + + o3d_img = o3d.cuda.pybind.geometry.Image(img) + o3d_depth = o3d.cuda.pybind.geometry.Image(depth) + + rgbd_image = o3d.geometry.RGBDImage.create_from_color_and_depth( + o3d_img, + o3d_depth, + convert_rgb_to_intensity=False, + ) + + pcd = o3d.geometry.PointCloud.create_from_rgbd_image(rgbd_image, intrinsic) + pcd.transform(transform) + + return pcd + + def get_pcd(self, rgbds: np.ndarray, masks: np.ndarray = None) -> o3d.geometry.PointCloud: + if masks is None: + masks = np.ones([self.n_cams, self.height, self.width]) + pcds = [self.get_pcd_i(rgbds[i], i, masks[i]) for i in range(len(rgbds))] + result = pcds[0] + for pcd in pcds[1:]: + result += pcd + return result + + + if __name__ == "__main__": import argparse diff --git a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py deleted file mode 100644 index a28fcdc2cd..0000000000 --- a/perception/sandbox/polygrasp/src/polygrasp/pointcloud_rpc.py +++ /dev/null @@ -1,137 +0,0 @@ -import logging -from typing import List -from types import SimpleNamespace - -import numpy as np -import open3d as o3d -import a0 -from polygrasp import serdes - -log = logging.getLogger(__name__) - - -topic_key = "pcd_server" - - -class PointCloudClient: - def __init__( - self, - camera_intrinsics: List[SimpleNamespace], - camera_extrinsics: np.ndarray, - ): - assert len(camera_intrinsics) == len(camera_extrinsics) - self.n_cams = len(camera_intrinsics) - - self.width = camera_intrinsics[0].width - self.height = camera_intrinsics[0].height - - # Convert to open3d intrinsics - self.o3_intrinsics = [ - o3d.camera.PinholeCameraIntrinsic( - width=intrinsic.width, - height=intrinsic.height, - fx=intrinsic.fx, - fy=intrinsic.fy, - cx=intrinsic.ppx, - cy=intrinsic.ppy, - ) - for intrinsic in camera_intrinsics - ] - - # Convert to numpy homogeneous transforms - self.extrinsic_transforms = np.empty([self.n_cams, 4, 4]) - for i, calibration in enumerate(camera_extrinsics): - self.extrinsic_transforms[i] = np.eye(4) - self.extrinsic_transforms[i, :3, :3] = calibration["camera_base_ori"] - self.extrinsic_transforms[i, :3, 3] = calibration["camera_base_pos"] - - def get_pcd_i(self, rgbd: np.ndarray, cam_i: int, mask: np.ndarray = None): - if mask is None: - mask = np.ones([self.height, self.width]) - - intrinsic = self.o3_intrinsics[cam_i] - transform = self.extrinsic_transforms[cam_i] - - # The specific casting here seems to be very important, even though - # rgbd should already be in np.uint16 type... - img = (rgbd[:, :, :3] * mask[:, :, None]).astype(np.uint8) - depth = (rgbd[:, :, 3] * mask).astype(np.uint16) - - o3d_img = o3d.cuda.pybind.geometry.Image(img) - o3d_depth = o3d.cuda.pybind.geometry.Image(depth) - - rgbd_image = o3d.geometry.RGBDImage.create_from_color_and_depth( - o3d_img, - o3d_depth, - convert_rgb_to_intensity=False, - ) - - pcd = o3d.geometry.PointCloud.create_from_rgbd_image(rgbd_image, intrinsic) - pcd.transform(transform) - - return pcd - - def get_pcd(self, rgbds: np.ndarray, masks: np.ndarray = None) -> o3d.geometry.PointCloud: - if masks is None: - masks = np.ones([self.n_cams, self.height, self.width]) - pcds = [self.get_pcd_i(rgbds[i], i, masks[i]) for i in range(len(rgbds))] - result = pcds[0] - for pcd in pcds[1:]: - result += pcd - return result - - -class SegmentationPointCloudClient(PointCloudClient): - def __init__(self, *args, **kwargs): - super().__init__(*args, **kwargs) - self.client = a0.RpcClient(topic_key) - - def segment_img(self, rgbd, min_mask_size=2500): - state = [] - - def onreply(pkt): - state.append(pkt.payload) - - bits = serdes.rgbd_to_capnp(rgbd).to_bytes() - self.client.send(bits, onreply) - - while not state: - pass - - obj_masked_rgbds = [] - obj_masks = [] - - labels = serdes.capnp_to_rgbd(state.pop()) - num_objs = int(labels.max()) - for obj_i in range(1, num_objs + 1): - obj_mask = labels == obj_i - - obj_mask_size = obj_mask.sum() - if obj_mask_size < min_mask_size: - continue - obj_masked_rgbd = rgbd * obj_mask[:, :, None] - obj_masked_rgbds.append(obj_masked_rgbd) - obj_masks.append(obj_mask) - - return obj_masked_rgbds, obj_masks - - -class PointCloudServer: - def _get_segmentations(self, rgbd): - raise NotImplementedError - - def start(self): - def onrequest(req): - log.info("Got request; computing segmentations...") - - payload = req.pkt.payload - rgbd = serdes.capnp_to_rgbd(payload) - result = self._get_segmentations(rgbd) - - log.info("Done. Replying with serialized segmentations...") - req.reply(serdes.rgbd_to_capnp(result).to_bytes()) - - server = a0.RpcServer(topic_key, onrequest, None) - log.info("Starting server...") - while True: - pass diff --git a/perception/sandbox/polygrasp/src/polygrasp/segmentation_rpc.py b/perception/sandbox/polygrasp/src/polygrasp/segmentation_rpc.py new file mode 100644 index 0000000000..34ac20c0f4 --- /dev/null +++ b/perception/sandbox/polygrasp/src/polygrasp/segmentation_rpc.py @@ -0,0 +1,64 @@ +import logging +import a0 +import numpy as np + +from polygrasp import serdes + +topic_key = "segmentation" + +log = logging.getLogger(__name__) + + +class SegmentationClient: + def __init__(self): + self.client = a0.RpcClient(topic_key) + + def segment_img(self, rgbd, min_mask_size=2500): + state = [] + + def onreply(pkt): + state.append(pkt.payload) + + bits = serdes.rgbd_to_capnp(rgbd).to_bytes() + self.client.send(bits, onreply) + + while not state: + pass + + obj_masked_rgbds = [] + obj_masks = [] + + labels = serdes.capnp_to_rgbd(state.pop()) + num_objs = int(labels.max()) + for obj_i in range(1, num_objs + 1): + obj_mask = labels == obj_i + + obj_mask_size = obj_mask.sum() + if obj_mask_size < min_mask_size: + continue + obj_masked_rgbd = rgbd * obj_mask[:, :, None] + obj_masked_rgbds.append(obj_masked_rgbd) + obj_masks.append(obj_mask) + + return obj_masked_rgbds, obj_masks + + +class SegmentationServer: + def _get_segmentations(self, rgbd: np.ndarray): + raise NotImplementedError + + def start(self): + def onrequest(req): + log.info("Got request; computing segmentations...") + + payload = req.pkt.payload + rgbd = serdes.capnp_to_rgbd(payload) + result = self._get_segmentations(rgbd) + + log.info("Done. Replying with serialized segmentations...") + req.reply(serdes.rgbd_to_capnp(result).to_bytes()) + + server = a0.RpcServer(topic_key, onrequest, None) + log.info("Starting server...") + while True: + pass From a2eb75634893203c555e5985a49776438fe40643 Mon Sep 17 00:00:00 2001 From: 1heart Date: Thu, 12 May 2022 15:12:59 -0700 Subject: [PATCH 31/69] Update README --- perception/sandbox/polygrasp/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/perception/sandbox/polygrasp/README.md b/perception/sandbox/polygrasp/README.md index 26d4fd4b28..6f20e4b466 100644 --- a/perception/sandbox/polygrasp/README.md +++ b/perception/sandbox/polygrasp/README.md @@ -23,16 +23,16 @@ Make necessary configuration modifications. For example: - We expect calibrated camera parameters out of [eyehandcal](../eyehandcal). -Start the necessary pointcloud/grasping/gripper servers: +Ensure Polymetis is running on the machine connected to the robot. Then, start the necessary pointcloud/grasping/gripper servers: ```bash mrp up ``` -The script to bring everything together and execute the grasps: +The example script to bring everything together and execute the grasps: ```bash python scripts/run_grasp.py # Connect to robot, gripper, servers; run grasp ``` -This continuously grasps from one bin to the other until there are no more objects detected in the workspace; then it moves the objects the other direction. +This continuously grasps from bin 1 to bin 2 until there are no more objects detected in the bin 1 workspace; then it moves the objects back from bin 2 to bin 1, and repeats. From e8a6157ebe9e4a690777e975dccd400b18e43dc9 Mon Sep 17 00:00:00 2001 From: 1heart Date: Thu, 12 May 2022 16:06:01 -0700 Subject: [PATCH 32/69] Added mocked data --- perception/sandbox/polygrasp/README.md | 10 +++++ .../sandbox/polygrasp/conf/cam/cam_mock.yaml | 5 +++ .../polygrasp/conf/cam/cam_realsense.yaml | 4 ++ .../polygrasp/conf/robot/robot_hw.yaml | 6 +++ .../polygrasp/conf/robot/robot_mock.yaml | 2 + .../sandbox/polygrasp/conf/run_grasp.yaml | 14 ++---- perception/sandbox/polygrasp/data/rgbd.npy | Bin 0 -> 7372928 bytes .../sandbox/polygrasp/scripts/run_grasp.py | 8 ++-- .../src/polygrasp/robot_interface.py | 2 +- .../polygrasp/src/polygrasp_test/__init__.py | 0 .../polygrasp/src/polygrasp_test/mocked.py | 40 ++++++++++++++++++ 11 files changed, 75 insertions(+), 16 deletions(-) create mode 100644 perception/sandbox/polygrasp/conf/cam/cam_mock.yaml create mode 100644 perception/sandbox/polygrasp/conf/cam/cam_realsense.yaml create mode 100644 perception/sandbox/polygrasp/conf/robot/robot_hw.yaml create mode 100644 perception/sandbox/polygrasp/conf/robot/robot_mock.yaml create mode 100644 perception/sandbox/polygrasp/data/rgbd.npy create mode 100644 perception/sandbox/polygrasp/src/polygrasp_test/__init__.py create mode 100644 perception/sandbox/polygrasp/src/polygrasp_test/mocked.py diff --git a/perception/sandbox/polygrasp/README.md b/perception/sandbox/polygrasp/README.md index 6f20e4b466..6eb3fc8793 100644 --- a/perception/sandbox/polygrasp/README.md +++ b/perception/sandbox/polygrasp/README.md @@ -36,3 +36,13 @@ python scripts/run_grasp.py # Connect to robot, gripper, servers; run grasp ``` This continuously grasps from bin 1 to bin 2 until there are no more objects detected in the bin 1 workspace; then it moves the objects back from bin 2 to bin 1, and repeats. + +### Mocked data + +To test without a robot or cameras, run + +```bash +python scripts/run_grasp.py robot=robot_mock cam=cam_mock +``` + +which runs the loop without connecting to a real robot and loading the RGBD images from [data/rgbd.npy](data/rgbd.npy). diff --git a/perception/sandbox/polygrasp/conf/cam/cam_mock.yaml b/perception/sandbox/polygrasp/conf/cam/cam_mock.yaml new file mode 100644 index 0000000000..a7511cc076 --- /dev/null +++ b/perception/sandbox/polygrasp/conf/cam/cam_mock.yaml @@ -0,0 +1,5 @@ +cam: + _target_: polygrasp_test.mocked.MockedCam + rgbd_path: data/rgbd.npy + intrinsics_file: conf/intrinsics.json + extrinsics_file: ../eyehandcal/calibration.json \ No newline at end of file diff --git a/perception/sandbox/polygrasp/conf/cam/cam_realsense.yaml b/perception/sandbox/polygrasp/conf/cam/cam_realsense.yaml new file mode 100644 index 0000000000..5bbaf3da34 --- /dev/null +++ b/perception/sandbox/polygrasp/conf/cam/cam_realsense.yaml @@ -0,0 +1,4 @@ +cam: + _target_: polygrasp.cam_pub_sub.PointCloudSubscriber + intrinsics_file: conf/intrinsics.json + extrinsics_file: ../eyehandcal/calibration.json diff --git a/perception/sandbox/polygrasp/conf/robot/robot_hw.yaml b/perception/sandbox/polygrasp/conf/robot/robot_hw.yaml new file mode 100644 index 0000000000..98e35f8cbc --- /dev/null +++ b/perception/sandbox/polygrasp/conf/robot/robot_hw.yaml @@ -0,0 +1,6 @@ +robot: + _target_: polygrasp.robot_interface.GraspingRobotInterface + ip_address: "100.67.224.116" + enforce_version: false + gripper: + _target_: polymetis.GripperInterface diff --git a/perception/sandbox/polygrasp/conf/robot/robot_mock.yaml b/perception/sandbox/polygrasp/conf/robot/robot_mock.yaml new file mode 100644 index 0000000000..b2d1ec0def --- /dev/null +++ b/perception/sandbox/polygrasp/conf/robot/robot_mock.yaml @@ -0,0 +1,2 @@ +robot: + _target_: polygrasp_test.mocked.MockedGraspingRobotInterface diff --git a/perception/sandbox/polygrasp/conf/run_grasp.yaml b/perception/sandbox/polygrasp/conf/run_grasp.yaml index 416e3ed99f..7b43942f07 100644 --- a/perception/sandbox/polygrasp/conf/run_grasp.yaml +++ b/perception/sandbox/polygrasp/conf/run_grasp.yaml @@ -1,14 +1,6 @@ -robot: - _target_: polygrasp.robot_interface.GraspingRobotInterface - ip_address: "100.67.224.116" - enforce_version: false - gripper: - _target_: polymetis.GripperInterface - -camera_sub: - _target_: polygrasp.cam_pub_sub.PointCloudSubscriber - intrinsics_file: conf/intrinsics.json - extrinsics_file: ../eyehandcal/calibration.json +defaults: + - robot: robot_hw + - cam: cam_realsense masks_1: - conf/masks/bin1/1.png diff --git a/perception/sandbox/polygrasp/data/rgbd.npy b/perception/sandbox/polygrasp/data/rgbd.npy new file mode 100644 index 0000000000000000000000000000000000000000..ecb3f379fc22fdf62812e1d40ed763c65b64a780 GIT binary patch literal 7372928 zcmbUKX|HYBk?!~H)8#oQ8@5HV$YPW1+q!M3EMJ!lSXb6N8Ik}SFkryAuu9Mi!!qu* z{l@U8@K^JY9Sh!JDNGh@#6|Nh_nZ~v?R z`hWlI;s5dQ|NQBH_t*d7|Mc&F`fon{>0kZd|J6@__32Ol`~UIZ|KI-ozx%)ZAOFXH z|KI(!eIjci}}}I{QOs+{=Yu` zpZNFT!^7K$|Lox(UOYU!e)wNJ_-dKcfBNu`FP=}mzZ`rv_y1z>Veq@x`IishzOH}v@WsJb zbLW?@@~elR-Qb7Q@}E!n?X>W#hu^(;HTazyd@<+$Y|5{v-tS$Yzz~8HB!8o5ie0A{o z{PQQ*(N}Z+_b*;d|6dKhe8g7|FR$z0%ysU2JIB@Y$>6gaoQ^zvZT`RbZ0;l1R}XJ4 zIgo4e{@~#UbKI3*e)#`PmCql(H28dK`*@HX>iP2-ch~*tg)is2%3qxR8Nn9@pUw4^ zpU-$4zeV<-42=UCAAB|K{llftPX?dQae7~TIsg6bIllO6&U|yqi*Kj4Kbi6e*Ep)T z`kz16PgDB$Vn$xSesF{2qrCW~ssB4u{>mKx-r%21`NOOHFcSRzi%%|T|NceV{Qa~` z`oEw4_@npd7t){d;vRpB^usbcU!PuH_D`D6cYV;3Zw{VnPzEjEIWuKu$t5`TF3`jlM}{^JXM`?HyM>iE_*AD`Xfhf~wbIj-+7 z2J8DldU}}Si>`h(9coc)k^1e`qWk}N*`ZrsUiHl_bKms!rBS?m zc>dD7`10V3DSdVDgDHRW4$a8tFG+uV)6`?+$|O>Kqt~hD()U$=^YNOOSJ`>((tmQL zeRil!a-ZSVk11aLdU*KbqkSG!&)4R-)~B7T-fvHth5Xqgz8xf;kFV=K7<>D}oPRZb zAo+hZsMWXE@q2x)en{ud$d{ZUJ-i;d>+4qr^NZ|2yO6zU=VAPD{rTo2&ie4!PvbJ5 zm0vu3{}KPig|8m|)yUQH|K$z7nfibA@WJTiVb+tEFZJUGgUa8h*6H8R2U*FluKQj- z;)_{_)c5S+Utak9v-2Txef)9e8~gj?i;t%Ke9$^a&x`Eu)yOgXN^c)ta(y-Sr>s8uQ=jXs3x9a@ zukhvA>mSA+Kfm;w-v02YN5|9CV){#O-~X`Z`{H%GWwN_1(9h|2Chm`855wJmqJo3*%?6 z{)Bc8`umn2pW{3sJK;Imlm6b~v$1#Q={x-NI{$3epX_Vaq&fdE`sYvd{Gj90x2r#m zYsbBKYaf4@dHXQ))IKUS-cP5@PksNIf6r%sV;(-6{SBml^Ka4qMEQdm5xrW^v!mA| zSEKuA4zj}W{nvQsUw1f7Uu9^2Gi%9bs9pDm^upeteL`h+oxVc$?7I44y;i1y{1McS z<5n~F+6h}W$9`X{>y&vA$ES)5=RXJA z*JV$03=o<)!zJ2id_V<5%_P+k>?8>7aW4 z{5r1R&cB#_^Xu!n?_6jx9+{3eta+^ zImjD)amu{N7p8sJ%^vcq=fgqk()9JR$GP`q`-cx+etfm_!At&iboTM)&=`Yl;mvg~fa$Tp#^elc!f8V;$zDAipQ{Thvdti3Kq((#5Jk*uCT7th7^Lv2Uk;^ms5mYLC5C?}v9N-gJD?OjHipr*S<+{yRId6QFPY zkX@v&(7dR;_*7qwOZ~f3IeJeLM30V8-?KbUye0ZsM6&7jL&{-hXS3znLrXdFub>AnS0Pwtsko>b>Rv zv=GnqdfM>Eg8VJoU-}Evv;NV${>J+qWLe7t)_)#s`9J#-9&3@mY~1mHYX07w*U#jm z|NdT0zeBd749zDz0=vX3S>5nPT2U|i#VhIWE&t~T9?%u>fA#@eE}jtAJ71hngUa^z zFdoqSaoxdZv(Hox&F`;I`5-&&y#8EPI9Qyfee?95|NHJ^zrvRj_uy||jeLIh!uo{| zUgRI%Oc|&A!Q7Wl5B~ql|K+Fk*9sZ`i0>tjw=*97`EW3QpWKwmkA7}3d*eU4Utir% zPwF!tTyH+nZ1!h{kWM=(N1xApYJ7MvR`riB@P7C>b>Q=?5BOJg(93ja=H<~(`>FUd zJZ$^te|W4H&&GoAe<6M0*|PWI%=o|B&A-Rzy`AfLP4Q>PPkgs!e$@T!SH1S@c)$3N ze|*ut5+7)MpU?jphkn+7{GaRpFm|B__&_?#)~&1?GHz8q(EOREdF+Oty6A(rf z7<+X;zf&ClXLrc%41ygdk69n?%HJLN8OP$EPnn(ni^p~KuWnGgznU_s;Q!3$9}Jom z-yc-<&*px;i|>2+@XxOLUrZd^e&C;9_X;t_v&;qz%PxyJuJ zoBk@lnDM8Fd;ahF_*cj8`M>lKAL~5+9-p?jykGGu`=HtP@qhF{-t6u0f9+??Gy7Ec z#iKZmS7~2^|D$(23qO5O|I**#ZJ+Xg@h#TF8x*7(GrjbCoA*xzK(v zdEN70$-yP@MS7n6D(`U?+x=s+)86$r?f56YW{zC@8_2G;zsS!nZxRo5&9JElpQ%2p zHM@ZA)2GK%-^Db{@%D)a&;Il~*L~sv_s9PwkL(T)==hA}>Tm6-S-awo#&!Hddi;3i zm(hPRsJ`!B^X>WU6Y{@5cs&07$8!9iemYN2i|j=lxyTOL!QuZ}hnMHluj}tK`SRD~ zxp@2>zo`H0GQD~3puP0HXuR3&;w}GIf8zi0Pfz*3<<%FBr*`9|w;$$(Ba$@J!EAc@5pR%}2yFa_| z#XN`Z{PKP8@_)s9;t%6myygE|=RTM?i08)3jS2?amx%-YBmVbKyu-(X>|eaf&x;>j zFTS=On4gRG57Xy~qwX<(YMlOAq!*Tauyu9$zlXuBk#EI2@UYJxdB5jZJgb~udtN%XU+uzclvf$U%dYr)ajQ7x z@PO>)tC!yGhw;942K25|?17#S>TkRsy{OmBt6fO@?By1hH-pB>z785!^}zc56zli+ zlIy-{@v;Zw$u8r|W>4~2y?ViZ^%swA{Op`Rs(o>W@{Xf%rSJIOk=&!+$@8B7+woss`x?QioQKXc2=|^wU4}5!-@qg-hAOH8U ztLHv)!q>9%TmG+omT`JM7w`AcpyTN^-jBZH0ga6P$)ouHh5w^L^VSG={^qavbx|OH zz>iuV@Ji<0V)J8pz~%iG5AV19A1RR2waO1-Ub1T*RJrr>-%}<({u3WX)Au}J_HMk{ zz4@^7Dt~6)$`_zN&!Oq{*~34-(Ei+E`D-IgbA$ZM+}t$OB{@j=z~Q9*~tN>*u#GoY_C^nP2k7vhPJl`D1xwZ>I(0 zGXD>fr~BIvJI=CQZ{IEN%yaie{WMR0H@t=`jL-8Fye0nEA3ppRUp|)g*ID^Hr2XN= z+o=VQx5!(3ZOZ%^y|7Dqso(fee(IoE^3^FHWGBYoeIyVchkth5ItB57)$97~|MwR^ z@bxL1HS+wPqSfb%b9^ee`kmiBJfIQQUip9Y_vzK1@z<_APwm6m8(;eV;*6Uecuw=- zATAUS7(ceS`G4%hAN$agr&xdF1GZjNetwntZDs4T^ZZ4;-y(iAfA6}NkK+uDFFEqt z#^ZUxEiV6O-{bFt8IM19Ml0e_d<>1t+q2Hao58P6fABN>q`W%!d~N!}zvE%Ex1*Qk z{}!`P*RxZ+pz$6akiN7}F8H?ecaZ(#jr8)P>pCmNyZm3*73Ud;>-D#G4_a^I14HA{ z?&9)(i_8Blejfi<9MV47y3u%)*=K%UJeRxX$T*S|d`I-2?~fb_mitE-n2eFA0Dp# z(q9ge(=GpJ9{=z<{%qoF*T?^{{$E`6eDGQR-_NhIeDd}Ii+?d?`|CGz83X7ZZfBdWK`Gtd8J$aky@lWQwamNELzcahL=^wje zhsD3jR{C39o)D5x*Sjvh=3R{UYd&Zo@&df1w^}R~+ze`_8W&$4B>EV#n{i=M`$X&08i#`L3}0*Dl?!-9_^udkp3ODKGzL zB+B?2a<5!mlN{KieL_5-ogjJO0jKf#U;GKoKFZ@WkCf%hLHiZ>!6Og2_~NtcT+dI4 zoE;UGJx9Pjfqe|7!N;s5fl_DkJYUZ8z>^~ERhPs-%W&hf1Lr+6&CD-V!7e)1U4 z{NNGAYx?yric5@Vv3MvR#`=!GiGNs(ABxu-*>VcGgVPN?nfvZh zJ9s934F8cm$A{tf)DzFgZ>gUjgVssN-_&kM|M6wFyr24S%TLGGK9c>9Rn7hBX)zv% z9*Qx{Cqqfzuzlgq!{zv=wO{+AcNxc2#GYx#fHrJgVFd*1gGr_Gvn`8D}2{3E|Wu8XzTI@kWwK7}8%Zy}$a zudzStA%D+Lj_$AXb_MD+f7NRpa-Q7DQCa@slb^qz` zAEfq|7kUp^`NMhd3VuBK5%`IZh96YM`@v5xKF)RcHq!t4h1P$3)|-o;vHIZe7PaSn zP4#wYRDxBMi% ze=^7Q_m=nLU6j@Lr8`{yZ;^(`gXG@D?Edh7@qOgPPvMR5SoiqlDd#t#c~t(OcAA%X z#J3j@X%@u$d5&HC?1jDIapSef6aN8O>MdG9@W&*oUq&4Nhlk~tD_aTZf!^c$LLQsF z`qMstrhIrnd6C5fcuoG^xXj!5L73j&hxYT;OK<9r_lpPoXsmwrXY-eJT;A=9_p}rb zgZFEni}y1F4qET=u%3s=)8w_uAI~5U6Uy&g%y0g~BfsXjbtk^i`?mRwd&CbqzKAzc zhV8!&?(xO;MdDlgo-+=!FkaKx@qzy0G4-Q<9-h!R@r3O=|8Vib^8eb8{_*kn@@wMP z>DrhCuWp~d>oTcY2lPu^)cia+zW+MEXugR97mauK`FKF};{UYMd%Ad+;!*Lkc_O|n zj?q6W|Lt+>kMoP>Iljp{R6V!(f9B7=|GPX~`F_RGq_lZ|u>IZP|FYlo7cZ!t!~f;~ z*qwg3?$!AHc!u}o|Cu-P5Esn@JYf9{=X(${>ExXh-~9NJ*YzEUk>9J&^7nrAsE?lw z+Nb{fD&zg=CnWzLJ=Uil^W~>^=zYoBTm19K^Z)EZ&mWzCn0CYE{eFIp!+s>WfBTZ3 z_r%E&I!?~FxIBe@Kzs$>0(*w1Yrm1c;{i45z1@&L@HX^@ud#aLg;;I;M|`g1%GquD z^4{p`m%ZTQ+gBW1{?BZnzx1S^^8cW`5V-s`kKFjy{_gp{J%9M1%@Yh+O!9jdjmyXm z^3M39Mg4g3*dN%uJv@!FdR@PKn*QZ)>i5pScp&@H^gJ>jyhOV?}qIo<9Wy> zdtF{7j87pyenf4>-;4T}Kd>LQjlY{<8ADU)p}*1G0Pl zY#;6VGp~A{kzee%_MNX^@qYF*%I4wi`Q@j@pN^Z!-N!Gl9Tg{%%dNhqF!JNy^Ml#P z^1$KpaQ1V~FAunQc)88rincbn)7!7kV$H@-6R2|H`3wMEtSX_3;_;8}>!wZ*~_SV4c5>(?t%- zVg9V^<$JWw9&Eil{9n&c`Ywbxr+q|x;f!hesi($ogp0fWo0nE5@icolykF~d$DKD1 z^AGv6?1J6cPu=7C$>qnhNBghr?0(+l2lS4g*m-yGdf(@2-~J-Mc8`qTaoBu5=k;%5 zuu@8#E%ujA(T!PcYr zVC|&$&qwu+kGkrIMt69-ct5-Wsl-d#3DnP!{WK3@`l~(T+kP(Qhw%~SOK3dVF}pXv zmj7FR?BM1BE?#WM^jlnwcNCw|L;HvFFY#N&525*8`~YddeI(huoO>V3_GvU@|K_^( z+2pBe&`tn=hQ@f)#gIu)w%-`sp-W2i!#^3&= z`D#_R?xdH)|D|v8c0as48*K0kK`~dU3SJlC-?mM`*=Y88_8YQ z&CI#%UfDPoN79dWyY}C_NY3RUw-24+OnpB!thxUuk9gLj!~glNll8Cfec=N=4~q9= zU*bckzBB)mC;m_GtgGaXM_gp}*4agIse0JM=yL3~b-3r}hgVyD>o=YaZ}s(&-$x_u zZ_fC!1^XQX@6U@Xzkcz4&u6`q@AvHD|JX0SZ+!pUiTAUQl%Hyy-gPy3f8#3eb2$5q z*4wXrhWv-P;Nbd&Mg9FxhWEgy{F_0$G5p^mHsxRI#MIJt7zx*ZczsU~mXGy%+OHmb zoBH7Le2eU9^SJOh?AU!~A3lfO_Z`0vCa>f0ezNd>Jmq-@dh!P2|L}lVw(kt`+IYw2 zh4#%8Jfip%&-V5@?`>c0ZJCvPJmnCNmhkVfJG@lyGZgZhof3h_an>nhv78IScp-s+RVdp=S<{LEs!+$o>?^*27y z``1Ta+F4$(yfn;g{aAj^`0bJ)KZCz&98ezP@_*!j$5O^?z3+PKdHkgMiffJQ&D5J- zBImcOdY5{L2>x^Dp$l&(M$Se}D0Ucue~$d|&b^?+?G-y4`r1A4X`L_BZ-t z=IN*U?y>iy@dAezB#+H6b6@^QKY3E)v3}`?^?vglm-k!zeEx5F!14fnXU*TqtKwg$ z=4)LVoBa%TJzdlf?+fae{c-t!;sT!00>yq8+s`kr5Vp@R9@oC_LEIv{Q(koC;REAE z%l{Lf#+M)dkKFN!^zijT_7U$V&%C%A&&2M$7nmI$Y@CNDavtyZ6zL~k+rEfhh_BPX z_kXotp4jG(h3=D&xTqhS2k1M1=F8+eKcan{d=qh4Xm|X}S$EBcpI+;*eL>GNe{o^& z(b4A*uj`)jf6r&#n9k0)e)NdnzwpIe@A$j?;4dGq`^6*vX!_s%@iX{U^1=UEufBZA zcjGxLrRx{j5BaknJWG7W;!}N^XZRWG2Y#mYC7uRvLSFKn+%I2hdBFV6@;K#($r~$P z#s@BsdyhIAe;Kl;?8Y}l8%N(+^ZXz=-1C3td&d`_p1&`bA6Wn0N7Ile)qiLHP-aiRL~KiMI)8;m#IafjrC_jkVUJmlZ>v+o>S&vC~-?0cuu`QJhI z;{BgnEFU4B((%Ll#sAT3cD5L=xAylRnIACs@9qxH%rjd=+2Wr=B=EKc?)wxXlO-w!gMMu$*(e>khwX zzRV8en%CA_db~yYY+Y_W?tbg8Gui!qhro5mkKNCo>^u8g`)oa?$NV|_)!Y2itv}Sx zy}g-l_`;`XJp8QV`m=a@eEG-qMPx&-MxU2|G-3iQlrH(7(m@(}({X8BPo2JE|XC-fwaFzs2;?d;9X;%rkub za8uLrna9oR+9hx8L;E!SQxE;^coykpX7r^W=q`3q+`~_~@}Tif-PgEb^Yo0jIDGp- zZ|3za@=r&;>F4lMJHFn_Ebk9*B|hTMSiL+i{s>uh#$7Q~C5g zS97L#gn!as$GeZe;;#?V|2_wpIWgDg_Z&~&>RbNGeBxgg%flQQUUH+q7k2Trt8Cp!&z}xzci#tUeZ-6OodNqQJgjwW zz724V|0^?E@z~6*u`BUe`#HT;)}Hfv=etaLE3R|?9`!dq)qT#lUkmv;&*eTDE7rbw z(f8uhGySA@`2g%eo)-R7d*%Q6Zf5+S_tf!!y+@DFQ+9pvIv%yMSsedopJ6>+^qfBb z5lk`T|N9B&o>C$5gKgY<^a3h_i+?mb=hhM&8|csO>Bud=?J`uL~Y z`kQ}^TRr53CpF)e_p2Y>=eYN1*{^!H%&y)}d3?;+<-swik+=He0k!YDf{V@j!;9%} zyeb~nb>{PJdw6s0zI^PbcuT+So0CKBX~%osjeoJ{gz`6W&yE@}!Ut5+(y7t!mR*!ieFSv1As73Lde#W!m$MVzV z>wufB2est9Ug$<5T`Gf9X7nIH+FpVfk;pXxv?=AFf|yulM|)dE&h1 zE%6d~KyvLpQu~$Ur5^h@xZ`O*kN+cg-}lp>^ZxJhgZ43-|MzV6)A&C)K79V(<^Rk> z>ucjX*gl6tW&b_5wq7K!aF4^iE^L2mAD_P4PviUY-{QpHJIl`TdCU9R#~dEeJh8uK zNA~mVa?AJ)$DvV*Kk3E$nWW?WP4fc}s9pJ6VeeUgapdQI`C;|@KhFPUuP47X`=;04 zH(aFuZ%)0Ws~`G}|8u|Z657w+=L5RF_^5dK{0_+XN51UlCwJ)k5Z3P(7oUfh#n0JS ze*dcH;VMt@5ueZcksdlPkEQlLeZ(J3efk@|c;pM8U-fsq>(z5V4m`oeapX`t_xXSE ze%9;wKkInENm>-CL%x_n}-p$HvRiHy#i!FWCFL zb|b!%YWBy^Ef2^}i-*J=jpH7l@_)rk-fwZ;{w~Po0ebFNeR%5j9n}~A#~+9%ip#Xu z`@oChu+HQCjK6rqcVNXOo)g@n{ws&cv-nWFnZG;O`dePberH|3HePH#6j$R9?Bk}+ ztDe!xd(cQ6hs`^}H*cW+-|~JPzh7^ir*Hh0^LW2SwZ{L2+4udtUO%%ud;Fg_I-brK z_4YgF`5X#BS*-pF1;(C>hb73yEOiL z{;zhki{g|W-^!tJHs1UwUOaikU*hM|L;hUeXY(V!Ju~1@?#kB1gUzSo&$CZ_qIPR< z^B>uJd;$CDdl~pu-%(lAPv60ySL+wFo`t?QU|(=ho(ul-OQT=MdvCYzHn1=Dusj}Q zP4;i)-S0IWwEryL3tRuSqnzI~kL(}l-MrZ61a^J@dUy`f`=1T6 z;`037%EUC?!92r!vngn_j^CO%CvwdH0$5x1MzkEK>VHGy}{1z7K!+o4H)5e^YmlBjd1n5JU{iD2lWT) zclm#K|M)dL)b`)`cueiboAsT%@;LQpdCKwu*|&a~&j<6*_`dYoa~tLOO6ykdUDKm} z@+=400X~rb>V4qO^RwO;cGmG*#E0cy>o@zz?^NFLg#1e5HooTPZ9ZUmdh9@c6}{lY z7F!>S>-P6=w^0$=9U0HvUS7rTPd$nJVx6Yn7pS5*Czpd|w z$0RTHk?5Af`qBLPd~BVt?{5FiPVB=M>8&s7dHJV&FZnXrVW`ZWoF^A?HlEZzJwD*@H|)}To2(WOrz}5D*?0QLT^^wN#n)+4`C{$6f7|bUMbg(F+QBb%UOdi!7nd*Z^qs5R_x05K z!;zQu`X`rMA7))i-uOKI{Qgy6IL!=ir@qB!bG`B+ezA7L=U0976d(BVYR_&~d#vy$ zkJtZj`rr6=9Ptq3+4!Bmeg9HB_BpQOze4=0^763w4tnW*UGq5o!2IGtb|8*yy*j+f zmg#Zx{^C)r3+cD_xUImaOn&;cNIzelGWo?Ddv1*fS!5saX^X{)R(#`)_gm!O@HC70 zgW}`&#h2PY@AaxrO~s+N$8WDIE+x16b<6)Hm*!9Lw|Q7UcV6P*w7R_IiRbON_5WaT z^C)%tiKl5^6<7BB+Wu|%6!(!!`*Za){_f8Yh-{jf6?EPQ;R%UOZdDiz` z7wgyI0jnoFVF&D&U4_Yu9#&5JmtL0tTe&VC9)R5I_bsOH#+jXKkG(_Q8t=E|{K~Oo zWp>NXn-89!D}Qi}yY)W%jJLDDS$#tDta3byeX{bwJs$FZUB7%{{2vc+>}mB;e^+kt zGq?Po@$K`B{Vr>WA7=M2uje78SRUZ3@yl~?{^z|+JYe=?J&mV}_hYx&6}!vND0?32 ze)}QF&);L`&voUe+V8EM-eY`X`55FT4l@sYf2r}gzWhM*Q2qvcl5YUfikV-phT5|I2R71M*N$exx!#Nx6Zy1XJNv8jbM{&Kd&?i% zH`Ci<^Ne3j|Mp|-e)W#0Vh8QZio5X&>;`|BJkoFRzT?OLs#kl9w0X<_<Fw7vG-zD|$1& z_SO3DI{P{DY&b@4Bde<) z%j>dV{mG8y!AxZ%N6#0@4gaYE*@srg~RiS=g52dc%k?V4>)aH>kWIvUlrfDPM#OuukYV3 zj!Z7OEM{+bK;PAOz44LXnZL@$@B4{Q`9Ig;5!orZ?tRJ4ym~$T#V_KI0M_g3(5A3ed3=R1s!zn$+b#nZ{pb3J~}ssUN!PX|Ak)_yixkvB$rC9rwI6-tU_?$h+YI?J8Z@{=;?R7w-qh z|7{*1#3Q9gs7D9$U*+fF0rR7`Xq`U%UwktjMLgbnl=vX_?f&IcZqae;q`W%qQ{My z`2##^{NbW`V?5>!UQXF~l<}JJMC!2);1~Fhcm@5=k91!D+V5*$T&17(rLa7}c>Hr+ z>rDO9@0IiFHGPtgb<+F6GToK&FNX)@$MAye3EyX*pzNsYdfw!EE5|LyV>XWEPnKWS zj{R(UcwauC@x^;Cvhc(IsTUune~xEY2h00g9`Nvgw>%)8Zu!5~vBUqhU&!9^d+jqC z$I1JPmsZvv{na1i(YyG+=85r`7wspzUb%Hc{CYp0+Asg_ed9A;d5+5q8ZUVqWEptC zangew$NxEwKXd=`fZ}TRFIq=iPnP#H&#VLNwDmXKb)n;DU((j68U;AxwY4#f*AimX4?{W5C;G($Me7VKq>iQG!Bk!j1Y&rff{&weS zdQRWz4gc5tK4_l!ed+MV`$?Ge=`oTYm z%m3l~y1snC%?tEiu=f1^d{}+1$2*97Z&5s_ycj>j`r;j)@_$y!_(Hq}dB)d;^tk%C z<>~f#@?ZYpo;PtHIV|rNk3w%pzu9x&Z;W5L=l^CP7yn1T{}lgMzu%2d$tV6T9w~o7 zKYg!|wJ+ZyzGMgSNC)4?^W}%Nr^b7X_luu0e(fJL{^k?ZzBqT0-fsDx_P-|%$$u?h zIZe;?<@NO(UVq|k>|e!o9pCH7L%h?ti(B#w#VdP0d{>^vvG$N2o4?85yrZv!^j6;A zV)k(6yPa5evvGZPvv!jGx!(Dw`q3_VFB%vAf>zX%zTHR9&6B>5>%4w?Q^WJCp7W?j zd9nRL&xJfMa(tf~#hcszt2h3f+}QEKcjsIDJN~bEciz`;{+oY$f8*JHH$UH%S9;2R z?bp~-s2<;AIOzFCek5K{UY@djI(v%uV=u*Z^x*iSeL!XFkn6-RwFh5Ldyb2zx~}r_ zfqkD)ee5&2!Qv?T%AU;&$M-t&sw_@&eDTze4=ipwNDhvN)gOO|&&;k4zhm7I|1M_l zhtFwU>O48@x@@0E9z73Rz9YWR;Mzyv9pY0K^9!vXpU1o3@_+XAc)fVU?4JK&mykYg z{fF``pQoIC9>3pnApBo;#!r(kB%j;)xbr{E?)Z=9#qu3{{Mcpn=wJLJyUy=b*{&jtJouA(R+~a8{y^#;U(eGK=*R(&Wf8?yccq{e9w}$x_cC5U-+p!PvGke;6 zA&569zaTq_$MJk>dF)Q9l2gGNH`{g+tp2)bhyI6bYJbxTd z6Yly@Tyxfg*2ly9<%ij)qEB2n1}ec^nbfAPF}~JTQ|;n*>}0z z_xieDl;uGyz~Lypep@9KBsK6c*t z^#kvvJ^KsDpY*(??-i=g_YD1hDEw%~8-M3`_u;F&-|GGD4=?0L_PeaEtG}+V{`#pM zua5fH_M;XhwI%p@6cZQ zVQ=&iPj-v(e#`&G2c$3YoBHW}F}*ck=vCP|xEMc^{jh_0-9_Vzr!3B@OyBh%-^*Ve z{?Gi_JipER^ZZPliYFbNjl6Hsyg7NN*>m=`&!6S{9ecZfA0@j#ezJK@uI!Edd^q1% zir@Rig?=v)fA(hb{=9Gdh4~)3^6TOCpx-ltuO=SC(|tU=p7(LTFmcmwCNBT-@PW#E z-0$_e?#<)-y1mEC`&3W7pM8w$@OVGIu3!Go`(xUJzn*!{Zhk%M%iFpC*Av&*j<2u9 zA9{ZJn-~Ah!~fyoudng=h2X~bcCd92ALF@ld<>ol53I~T;)B{R9Ny3RAKyV@<+I^A zvNQaNeg5b3eOuqT&h>bpc(T?v{o;4xv+#dg&acHA;R#!B^b=!y@bmb;b3DG2eH&-< zcQO9&@K zd}4ktxh>CVT-i5$`ktr$#rLI0=joH&csl3h#i}RX4*}r)j#{0Q``98;8zvbIJzxM0B&um;|@QBv;U%}p35Gz?@fR4aq$iG zdA~3B96os*mp=evW6y2Pf7Ue<43Co{v9~XJ`HKI|2HS|1%%(1nOr8 z>My?5Pv!7^_DFB`y}t9=zToh@uFp@2U$axcGi|=$0gcc1%Ixp)W@8|;{vMp-)j#L= zcZBuZ{NC>v_CB-x6Y}-`Tyk}tarhln^A|tIPk!(5{{3Bqc)N$kOZGeHtB24y=*KwaVWy9R^e9eT?7Z>N zU%0&A`|>;ES8nqSpYnf|@`#Hkj;?>^eSYH}4}aT!t};7gc>h!RKfIiI1GUQ!vy1qA z{+XQZ_>NvyPp&6__b31OLgjceaff#D8JA!1eF**`bf0p#{NK(4_nQap+vqEP zPwV`e-juI;@@qHG7V5Y2i^V7Wh&YcQ_Wcw6l?P&6cxu3{R`mbY7ePMqhyc!>Bp^28(LSMG6ny1hSsuJ?+`ukz;q z70;?_?N(f)-mSm-mj4r%IA7e>c)A`B!%p}6N4J>&D860Z@5G}W-}v_y^Jm33<-@Sk zEl(gc;}H+%|4tm^xIEiM=i{S{xBMgXkv^^Gt;6vVPxGwsRIY>V3$6dVF6SSNn}5hI z*#Z3=zAd}0ynJ;5fof0{S? zr60Hbt6wM2)_9JeNN)KH`xs?>qPW+4%<**gEA|5&_dN{yaGmjVAGx((`aBeu9zAEj z#n*T_`w4NY{e(E2|6>PT*L;i@*?69vs}I)i<@eGnyP)4t|FbLg<~M5BJU#WqE2Ss( zR(AgO{`8a_@KgDj^*aamc>X7QBCqV6JlXA*&-%aT@3HolFW>iAVEJpy)9t*vNAp#C zp>f4);2Vlp@ge-J`pkcPigBNLCaxgQ?DycxBYCk4`8fH}&BtyY@lWhC-cYn=9+#)* zdj8t|@|~4Eha=DY?qd5;a>t86zXxzI{*OK4|EfQKZ9dd*cHFvq_`t?@>~8rV^Re$P zEV9dZ>3C~)MvmnfE@prE)8zr-(L?&kzVT@Cn&i`!ht|FlZ)^SPdvEd{2`#Xq_W+!+;^DREw`TV}`_L;}a z>*l{^AdmA`9E|^4OkT}z>+yg4@V|TbZw9|KwUj5y?(uy+myi!=-0^;RJ^hux7Z0c( z^8F5qhYtTYoa@y0^5vK3KJv#m`%dB)M%vyhmbb``mWO9IemBv+?8uqjbUgiLNAZRB zm-)B$7q73pKJ!4{9`F3i;m>Fn4`}!M(;Kw@$H#eJ*ZGgGvR#_|JF5m>Z;#vMDPu+A z0T1t2Uf;?4!{03rxTw8-&lm64eE#*s{jaCpUr&2}KiGYqr^ZwM>4oMw-jDnm*Owl7 zEj(ZApEEWgdVY8?DSJYf7K-et@3AeH4^)^6y%YWpO4nKTZK>lV$Mu5+B< zgU0d6W4ZT{`TKZ5{V*>5QZL>wJB$Zw+}b<5T+ea4-tqc_-(ykne!Y+E`A+$Obd9p%+JH8xqtKQ;=zii8pq-N*qJ!%p8sQS)qjiL|5e`a0OI4a2YjHF z@L=uNPx5;@p4Nr*gAcX-8P_eUzw4gzfANgB@6Y40Zu!40e;&r?HE#En=Xbsj*m?O* zcEWfMJn$`=56U6CD?W}-$qw7U-scsy|L^+F$Afeq`#-#c{fV;uiFtU7^j3VjaW$U9 zJXC&vfAOLE8&B$Yw&&U2XT0B^PMLrB#-(TLDSd~n>-6n;?Xk1^_mq!L?>(m|Z#BOe z|HppXAK&BG9*^(uf9sF+HC`~jqWw~Ng7}N}Z_5{M{$O#x-!-5;$o_7zbuPZ_+gCk) zmqR__h9XFMSuuy`u|&;82P!#bD$Grq=u`tQ8s>N76u7hZHR zo;w{ixTt%%_9a3+1QCPaM0?&#IT-eHZh~j(ehPyq@@(AD+J`iwv4Kl@Bj< zJKoc;`dPotPwTsR?E9SNXL)V;tv&zw{9pP!{9k$%XV61@1KuGyEFQnm{98YAu(Bd|{rY?)r{&9F>-A#u0KZ5+ z_&)lzj-~Hy?_l*c-|e$@TszOqBmRUP;QyO%*;{#j%d5m^u$!JYgw>PX#T#}VFT6Zr z_8QNgePqAvYUj`DE4{N9`;z#Seg|FLcU$&+MwuVXPD0mZ5260x9rS06a{h<6U^nFv zm2aBA?0EcM{D*j1K1HbBeebxu!~9Uk?|=WHcs}{w_V1SebA0(s<0&o@|7VW}`HT7; zuh@K8-oy0ly z#{9&qh{y3*_=d`Ot1ah`<6-a;#_RgtKjDYurLYtF%3kni$-Cp(XZA*)Jttahow!{G z{r;PA$M2i>`Typz_SI{ivuE~quyI!2>*|knss4rK#j0oXV_hFF1K)lB-gWU1{8G;y zdv7luu#QCph{f^h^JDc$f z$;EN&T=mj>{ZT*px+X-=T)V1&>RsMbd$nu4?9TkBXP6!E zhHE#;HQsgoYWV`}%l@l%0O~h=Ca3I@y_yHwjXx>xiQibh%D!=VLA*M>;S-uaAwGj% z@%h!)b@JLa4{Q0D@|N&_`8B`8Xr9?`lk@6v@hSh8U&w!&PtBj?R5|`W|7YH^U)S4b z88`oC9i=D7@xtj1pJ#vId#kSN`_ubH^x8R%Or{ewMdD$7i zq`tn3fREA7#r+-|Y`h2aJBJTUPVe%5^p9`KzVLqR)%&M@U)J^V;SSH&`gF?qF}xi6 zTRgl}dX@)hp6>VR&i(BZ;tlbA`q}qc`LFUs`|e%u`?l`(oJanjdFprm#51@2U+)3q z0bh?E{AT>n7iON|2j#QkC-3>K&G$>bznkAr?e`}- ze)6LZZ^sXx{J-Mx!=Ie{;`{i)eGmAb;{UQQ{0hH&kX_-=(jWecK9xHjuXA|7<@r7j z>u)?B-fzpdi0@mT?|ta~;O0%dptAnK_I2@N9qpK&xE@+!Zuyv2ARc4mgMOZ^LP^WUmtQ=*-|~Oy z*KvOF*t_F+$ko%1)BX$JxoF==4%WN)KXHC#*g6#Nhxgw6Nb5CT)3_Q3K6c9|5AgGN zzdfFQZ@(L8=VZU6MKil=iiS)N|^NI7x zEq>wP#@XWT_+-69?V{}&cde?I?Le4xMf$p`tb_wi@O?{^FqY4eu<(?8=oC?6m`;k}E)Qt@d)?mG zeo(#f@$|g``uFGsowG*m5V!X`M~_Zv3v4i?~CND{1gulXuXbaT7Cxqn7>s| zd}nrD`>tDF=P51^xJch84iT4#lNaMd>^$S0qzM7Bn>-hb* z({J+xpJ4u2Z=Tvm?U^S#K3@FODO(+WG}wN1QM>kmP+nc_Za?0K+yCsFo!FPZ*cj&%_}^= zGjjiXBlg|wQeKAo%Dd3d%BTIVvk!OO*5^Cr_2ZVWOpf9s{x7@VdGJ2WF2yIkU)Q>{ zWpSc_w8uklV#`M`Lo_-FH6ewKNHUpVuB=TZ9%?_2o(5_!FzI6wKs1JdKUuQ;In zQv4~uRy@yM$p03#L!ab8U;HKe#m^T3#=Hr}M^f zd%XOmV<-CIeESx>0y)=j$G7afezHHutLNCu{ra(X0Mp0Hd--JiAA6#A>wtP;@t-o@ z;o!EvXrFIhiU;`%`(S*4JOR%amRDI`&;Ho_TWnnMUY;wEllL}5JWcZrf8jk1@vrr9 z(RKLF#hq{DfJfi*!QM;H{_>kWH;MOiU*D0oFEnoRn?2b##($cx$-m?DQNGaO1=pU) zou1a;KIQ-NSM+FpL-UV*$vwI3d#k?ZYJdIdp!EUYrCxFi@j~Pge-qDYzlYE3z4GE} z=lh+ei;tJh1Zo)O+&(mj9DKhHr{LjJK0#)_C5<+V4G9{8e`6 zI(8Tzh(BIFviYAM$4iRS@PA?UX5O$j>k~U6&+L(&l5cr*e;hu>_x0ErUguzT`!4?{ zZk2cX6qD;YzUAc^0OGodei{HurmYVzntTqCWy z{Nnfgo|gQ??>wUNaH-=@de67-ZHf=&1#>h`K6?53@O$|sJfL+4Zy3+09p~HM zcn|r*nIDJ$%a0zuD!$J9zvPUEGU7#i$bCLkJb}0wUl7V~TE3+E@G0tvpSk7#;^pFD zw3l6pui4A{ar5dnk8bk?9bf)Wy?CUjykGtJ?KRKjt<}GS#&PljPhOvV$L0Ct`E9v* z^)CO%f4I(gmiL3jHwWWi@Q$~ymMcCQ1AVwM;7uf z|EK-(`tVTkd0~8?aoqBLwX?k6B7MdGSx@B08Sm!F-SUF&*AM6Q%l@VD#q$-XcAj0h z4z8T|PyATC*TLlh>3R7x_SSv(cDnETvYXbIFuPfKF0WZXx8M3_JUh-s>+$>ezx-tS z$$qUz%6Ki~tG@KG`l;V99>@9ov+*t;csnlkb1R4V!}KpNQhD#QU*aJS|JS^h7iiq} z)#mfT_`mp%cscTDpH;pf9{4H0(Dk?P)22uJ-@^xrBgr$~rh2k_$F;NVz8}?ZA5p*g z_r@tcXx~FF_Myr9PY3Ofl-pmDKRzHkTb_3FQ1eU6L+j_!WBW8^eB#z0|0lkuS9}=z z@OwY{6F=tpxcFaQ!1nLl=X%G@Yk7-i=eGv!qyFsixN`eH@sWKX`S{(e+QD~jJ?+=4 z@7&k@@qqHq)gx}eH@v?1g+=R#_k{IFz98$t|FzDX{_!sAmzAcUvf#cu*z+f7U3Z`7 zefnvAxReFT(vtL`jtLx?E zx-V>A?fin(3*9HKN$&CGzROJBi{?x5Y`nSOxnRHE1A+E&i~4Qfrv1Zv>^O`|`@a|@ z&wqB6KX}BKv#+il^3Z>%zP`_CJUh{>0P>G3MtPME(?FMki&wff7qdWzYjcxw4S^XR-^ng13q$6Mro zZu4-;)7m&uJRqJF50DqXhKJ(s`d);1oZQcMWpBSH;dt|zA1i-Ix%KiO{o=F4Tkbb* z_SN{=&%S5A{9f~ry)>_~Z}#u`kgw912kC=1y;qU(14Z@GP~x>*w$X zm zmG*t)|8R{nzJ)yFy`8T%Mi=F!fd!%MFm>E-GA^He`akLk5~-Zv z{o$SL`{gy7_m%ry3Ov33mH)SPh|j~{mk-B(=kFKe!w#>mAMEqkY5eqhKY7b* z{Py7H0UrL(^XC1XotN{zv)`$4-RrTF^nHujZ~UL%=gPiYPwfwk57IY2y7_X>pCw=K)nobjZi|0MxS3P; z-G9sb<;TjG!ygup#+UWJupQ9yfA6B}oqslduJ1O+Pul0u6FuV<@$cmwmXD|1@)>1} z);@kOe(4^aPoMf#dyC0qk9!Z^c|0;XE$?^o0BbiMMZaBl&nL!nb^PSbHNL0(OXXYs zW$n&7jejeT?H0|LcFYo66(G&YL zZtY|TE2o3xw|uGZEvBz{KI1Zu+utE>T!)w6@?vtfPqq`bZzlivkKUhVPw}FQ%Zu*& z{Cx+@_~Sor`MB)Cew$qEhu{6aq58DHeA+D^lN`F=asAVe>=pKXH+s9z z%h|H^?7kj6S^F3Jf8Q+@zuDixS63XWzW5pAIq^aKpZKD9wsE@eeB z#xG%UvbffK-@Md)PhDP|enRrfK35O7^MM@A%dVpr_pwL!nHRS_M0u|A?mGX23;n)! z_t&2OC@+?$M=n2{JdK_ohe(z0Lyk7nFd&~IvuK)fc#{0c|?nR}+~LR}``F(j%HHHPIZltAk3TS;c#*I;oP6U+$g%79cht8WZoAtLe3R=J z=}~#Vi@N;E;@-FQZ2v-b#=ch`+4U_i=)5>N%)e9?-?bhb-0S!~;}>V+8+M+w-ktYO zt)t{?9d#W)u;X93CZ~rvPtR*7`mY=|KMtQ&eCK(gJd1dXv!YrzNh^z zuU;J2`JO8*&lx6v{wW?R{VB`GvQG89;@O<<`GI{w=gCjJAzy5<^(}rT-h1c4Q(Sw+ zZ)dOkqvvoxx$4JXb^3}I?RhW0FCK{8@D@GSCRh8v@L~M4`LURM;sxXV@OSpv z@p#687YWsCJ=^>%ydC~4{luT(58H3y`|OMUFnL<`Ny^R7{T@wxuKsR*Y`oue@8bVj z7n29S%dX=^?GMZ|`@wiW*gD8Q{0^Ms_@?aT)(@}$iO0&m_@(Xl>T&HMKa_r4S3lAt z`5Zr#|IPoz7df9jkdx;F-iO9p#QVv=(ogx8`d!|bcpo2QpM9I(Z2gJ znT*4Gz>Y5;SRSB#{qvXKne46~42n`Tmt1bqK2ts)UK#I%r#(EN{`Fq*;tE{c zyL{h1M_T(xuIvu)%0Afbu?N2&;Q5%}5&gk6UU_l!&2DE>4ARSDbg``z*kpHJSP-<>JHFnh^v>K{2Dz2N(lp}a=C-(u@n{ig?A{KfET_G^EB@oOK= zKI?Czk_>zG5&A)Mm!RG#aG4uL2>rM_!ILGkFviXf#3h~)t=|m z+6&_q_1}z#G<*0z{M{L^_owk32l<-PHh^JDnl<;{{0zL%YacrxYX%gQfh zr>C85FMV}fKb7Cd`|a`UQT^<4c_HJro-}^r^gKyDq#VB|KF0%!kMKnCMau)Gzs7x= z|0pk=eAMSSy&2D9<3D^~<5I>CxQ_jOKGNeYe^*%?>Uj0w>B?{2dg4)*|AW~-ex$s+ z^k`pfyzSQ^f8;&t#pGt+O@8mm$$n<-2J8lMhHwo<9_)JuUY>{8vZct`GTjdbaPNe|}aTa(O-Cl;Rq3Q2PAtb)Dyb z>Hk}U=Jz)T^ZWPc`Z;}F?>v5>IPRXOh_|r+IQ?kfT{(V3Ttq+iBVoJ(zCii;tQ#=i z;-EYN`jrRR`R`x-vcK0q@tbkrhm^%TuJe2g+6T~&-@DRp@6$O>pUUxL%kv$?Bj5wA ztB3z=eWUl{z3LMu*k@#i#dq;M?Qfi?H+Co9t}LEY78maQ@vZ8SC)089WXJ2r#;fsq z_GOJH6hEA@{d4+>XDXg{{_wENKg92u)H7r+6NviKfwLsk=|cYpMB`Y5yoFWf%pKg;CZIF z?d`}>|LbRZIq|VyIr;INH=Z9{_r1FKY31y5c{hAb@=vbze@7qmx_WXxy{C`#+C0(E zA6@tP9qjJ^@g44Qd|>C}>z+^l)ayIa&6}TG=a>Im>^k$h`|CHqp&h${pMO@5`d>Z# ztE;}}^L_B@jrV&ok&UwW_7?GM%JCh>z5HH$55AMWi?_+Wyupy(#L?L)d}<%|<@6(N z5+9Z?;(Gc|&c%_%``S@HnEfoD_H5+ceLo&d&t1QKVE312qaE>(cH&3MyE*n)Jnp*q zuEXPP9^4*}7h4`>kzcI+d)#{7%Hq1^@lyxZg}fY)w{eI zf6Tt*j~~DNdge)Xygc8oL-Fm;CO$HcT9?+3E+#McAD%HDo;_7>^8r7ryu3fVQQmp6 zcz8nny{&io!1%*>$Mk#rQ|s-KhkcRxW&dg(i68ha`z`$3o?ncQaNPPtAN*AMq386M z|J&yt!-^U-DD?{DxoOb-Vs|-tqb$FU${< z-#!0lJo4IlUzJ?R@t`<=^9aks>N~3TeRvz|*U1-bJo4w9kMF}T9zKU3a6SGV;t%jo zzQf`@?=M{Zk^Sg!7IWObGd>D$XguW;k~ba-|M&dLA1sf}_~M-$&wk27RMzgncs{&W zyx8IY_)q!c;<@FW`FrKV@3F7^`6Byer;Dzqr+72h+czq={_gpMJ-3xVW<85vx<&G9 z9^muEz5LHV#s9IR?3ex%|r>{ zR^%5KFNfEU-^1HsTYflbJ^SvUJoZ~G{&T%?$MZS=dg{j?el+&z{=KgCURhlAx6?j7 zX-8buaeQC%6k1pCf&4Ds((}E=c)$2Ra;WS*;t|Q*=R1V>LwrscKXUl2cp>?5Mi$S9 z$6;r1dAxb|dL;1M`EF&$=bNgd$#Z_MTiom8=kSGi3;Ym2d-y+o7k{!CzfpPf0P!u$ z|LuFZc)i}!#S_N=;pO5R4=&Fc59s~r_&##|=#dAMFUeneZ#us5@Ovw-_{Q=E2MZ%gj?d>&qJkFy8$DYK)VBg99?mx_~n{~Pbz^Tg~B50rmmZ~X4^Ncv+w z9l0m}_@eT{;`_*9`62h`2V92-P@lZbgZ-{-{2#lHSHzo?KiBy2A&tLs@+z+}-rVyY z?Y7Rx<9QD;J>X5)r}z?2Tlw&Y-KTx^-(u@&^N)NyCyN*LzGl3dJUIR&_3-{@h=mUviv(I+(vU9y}j@%f3Q?D&OMj4aOT8-<#Pd(xd&Ud4xAQ{cfM5?D?zf z#I^KoU*>xIhK_&hJ;ysw-}s}0#*a4(%@_N(?C8@$*DK$mekw0^o%qvneq8;F)|vYE z%|Y`^ee_;G#H;luo(^A9IgHQHf4oO|OYsizAb7#r3&~Fz|I_jMV_)6z>h)d0&M$8m z+V4AVzfXVmd*-R%v#RWP`i372-?O;=Dvrbd=y&mCJP>=@{H)?Z?ZoHZ@`S~?#fO_e z7LrHx#xHGNR#-f%AIlf9BW3NFSMi{&=eO4_|4A;6+c$OJ#;M!C@)Zvs7;m|GDDmOi z!_&2YJ@G~J@RZ5Nb=kGJLEL+b$$RMOIb6NN>|^znJeNnf=NAs&z4DKLTYh`GVtar;qpT@x@!d(D*8sALu^(-@#W8e{t0p_MBS%-dm}i zwews4V|kbKm44$3_$TG^Wtzw2>bo}3`z{CdulU`1*nRkB$KxxCUzJzS;tA!&?8d&| z@%#Kb`<9>0asK!xkN3&naeufxVc5Rg`L)a9o1R0c2fx($_?9;pFW~r(u71-uxh=Ab z{^nWl>5@mhMfp_umEwAG zRmPil{9x-^dRpF>9P~S0h#yLS*+D!Ny~Hmpue5k?FVAM(jsJr^N5PY|UXvreC(q^E z;^V9ruA>jDUZXK%f{?SJE_o!jx)-zC5NR(#*`d5~NW%F`nM<^ROT&WF{nzODBuK6~_&`~*KI z-qRoYIptmV7VXnqACKp{cs=&l^Oo?o-^;)0U;C!|X*_FJ#h;C@>l=UjjmD9`h|e>w zC-+96?kXM^_h`j7w9 zulSpHc}%Bwn?Z1u3K0BW0mIrMA_4)oOo}zmB@BGao z{>nT#n7ownjR(aQcvXgr4{X04|F_>ifZ4-S#M9Yl^&TyrsC{lcVc!=d&-g$5kURo; zV%9X;M4N1 zTiFf1j~qPLvL4t6n&$^=Z+W-F$2AY*|L7ABxcnbJxcBeN|NFtnSv=qGe8lsTV|=mr z_waz`q2r77xBOGj-L}8!QQqR0XMcsq`*@zO;`MyzFTSsQKkYhR9^mqL?XUi3#%up^ zu>Hy3%=Phu@xXXJc@T%!TYfKo@^2=8SYF`Y%ysy`zZrew|Nds?k^2AkGxR(>{*Zq! zZ&3fpJ!CIV%~XA+Is7IisE*1!A~9R{_-Zv>$6_tyUaVh*t5|Klz)zA z<#+L7o|ktYUQ+w|TV8ABc*61rYu9%h$>-cZrv2ECcuW0$w?}(;ual=|oyO;p!!6eC zZ?AUAJAU)XkNkV@+52eZgI6Sv@+R4j^UB6=pC*sAbw@v~p9j;=;ZfuN>gV!|@p9f5 zs~_0|{x$vTCwo+0)bIFD@^W1m55~T%*YSMn#RGPK?R+xpE8YZtXV5&vL$t2P1Acps z)2r*+AHX-`=awIe$G}683nYgh+@Rz3v*d-xkPjtqth^WP_>Ka8BR*~UHFkr?T;4AJ z*!|_l>W}mJ_xpXaeNlRVeOIk|@rdLmU(R;{?4$1azNhso>)*8@;vf#-s6n^%oyyT=*>B3%?gn0_|@OzqWj!ebFrsSpV4pKYY+Q@MiS+qpKc% zg&oOjs@{8^58t3&c7qQWZ{DJHCHujz6+d)6d#7J~A-jp6vwmft+pl;y{9?!BA2zRP z`Hw~XhU*qR59_|IKRJpkyRQ1h@3-aU9mOqw6oOI?R&S**LZLiQ)_0FU}xW@zC;co(BDJ%Dpcp z9%(=7x|1&?&Jb@O?0WG4yL8-qzsGo^_zLogXIM19#5LuaR8Rd9|ETZweOmKVoVR&$ z@(BO@@)v%ujof^<89pDoNsjSu%j4bJ)7sVhP+aM_`_gBAT>I>xJiX>c?QJ{T?&9)( zxBOw_;NR5e{=*~w^0EKni^>1%y8mRxeRx0bttit+@g@F>KUf|+p5WO1<_i^1#z!Py zayH+Sx41buLUAUH*HB)&3ZL>7?Ef|o=qcYsp4E4o_m`a6&GKr?|J~YK{c0TMRsD-^ zSe}x9Vn1)E9rNPt*a5lpebeQiw%qv1KY!x`dE3D z&tsoye#O7!hq`~qqdxbMlk;0&JVEzaPxA}T=MUl;?#uc`f5$GY53XNa{&Ug$x6Z>e zj>h$FJMlr}Y(D2#Z~H^O`Puljm3x@ntv~4n;<;|ufu5ThNBO(_h3m?%ZhY!t=gp(d z)86MY2lYSRFF&Kd{M?J<>@gX7Tjl>GT)xhwmhBzYjuw-lwPk=36}9`Mv4Q6Fhl?>OJ{@ z@y&QY<0q%>Z}B0yeRA=B)5Q1j=(X}E(;wG=H1**DU(fyp-pZ@XzyH;R&*%M|%JMDQ z)i(#N6XX{E2&=C=wZogmo2Z}t$RG56z4ISFd^*_k?&`-6Y8TRfyjpze@~QDW3dAz5H z&->bC2kLR3dY8A0pL5>)zr~&dIL^Nu+~ew%FI7JI;r~33z@y}+$cLZCBYu2cZ+$NB z$^NkT5g)~FmjBzh5&x7u#TS&9#m{#<{t%BE4;YV#_l?IY9~NI1|JV2%PkuHzmRH7K zAKr@nsyBO5fBfMs;!j(r52i2WcriR0ey4qNpH)Wb$h-0>fdQ6c~<|%an{rO`|8KafAt~W zPi}|*tiIaC>nJb3qd(%k<#{@em%*FV@8ZJy_sh!f!{3&tW!)EN9A0U8m+CJsD_($o z;gR(t9#4N7k9gW~`@#C%JYW8GdAZ}@5Ng?a@_s5 zxOUF29N+n{d|>75g`W7O^!IuEpYxuh;U||j^i(yz^7Zudww|Z?f6wN96z89R_8#!h zFF6=r`i&Pbf0UO8SbWOoxGw#M?7Oo3F!#%!Ir!qT4{}($xaZsM`7ZaZ-j}z^evba* z|H!jA^(pRqy5aJG##6uU>tEil{2ltx9(%~nmgh20k3HSn75Q%dZsav^??hekZTYebzG=@6@`2XGyO1ZTX|{@MiIB^r1iPSNUc6naMl9 z+&aO&c3tW@l6IT7?XSqI`PlOndRHdD=0`jqIVvxbpLRX(f$@Ed?oVF#c+P7ld8Nnn z*M4{9a&Y;+rzjtZA532SZM=H@a({X*K2uKa%m0P?@$9neE!)TAr|s9`yRFOChw$jl zb0+QHzn{C~*yE7>7H__Lef);w<Zg6`iobL@6axOav)YU_xfn%!_H9N=jF==$tZ+@I?&U*ml5YW}Yr=9%IGyeLcR%UU(ngc~|eR#tFqixgHJ@C-glN<;I!QkNl4x{JV>n zH9o`DzP|X4b+0X&!ll?{O{Y#8ozt#zqoSw|GapgxM=*( zJgE3T>x8Q(yazwQxx_=A?+h3J^O1jD-`IZfogZEI6Te2S5522+u^(UgihGIw!M)P% zhjXbX978;3JjOb_;;vg~>%9Cb&h@KT+H-Gw38&&G@k^ZYufF=ltNs7VO}n0QiR;Eg zJvZ6Ge9(7ZjMESQs~yR+VwgGYOw;CkAr?dm!1hHF$GN6p*D*T%b^;zml}RXH2?Pd86bm0SGW zbauj}+0l4!TrJL3+??zF^kpA*S03#;Kh=)-?YLXzTKUW)D`)n@S(MATqwU?tyh@t? z-&OxxeT`?0H@5xDD_{0g`6!>BGvy0^$nMklU)TMOs}%qD>wd+hUXQw~-pZGHa6Rqe zuI{UU!&T!C`4OV?XKH%CVyYt;W*j!$v5#v z_Bq@UpJD&sy3})aykv1x<8;#Ff9~6M^UCIfbn|}wX&ebRGEcyP=y=XF9?(2rKEAp5 zh)Hy!VzwVV9eee!GV=2x$$!~gxMUiDY`k$&x) zmtUsx^UkNWC)=mW-EnRI{-?C~;Ev0$4+j+AD8JLz2ao@$xArf7^quF7>!e%vdg?_z zqK#(l>XQ+DPb)5Fc;g5zd~Q;wq@zbl{PSZfz)>rA!d zc*4EB`iE~m^$YkNyRAN^_x5i8=@-WT^4s!Vf11C?|M+R;Te;uuQ~QhesMpHnIqN+A z>$Gxyj+Z+w&V@%*|CN97VdE{+ZRan~>y86vukjhzKmAMh!#Qf7#!X$P<4^y?KddjX zo{7Et9#re3$V*yEZ>LYH4nr8)MMYzSezLSSiOGK<|E<<%}cJImt9Naf^p}g?t5QP zoZlTjSiAxLB<|pF!0Z^$DsEA~SbnXGJ#l{gq3`}u-@RR0`G4~A58I2^8`m56`^nYs zioe@-et6dVTKA487N4rWYQOJKt0(WPjPG{7)@hijkw zQhR;(uW`oW0PpXGG@qBA#+OR71Ha)1<9^ehT;;RlesKNo`sY`HJ^2 zwinNO;sf*R!~ewl;)SmJtCzZ;xW49}@9~LoKkGE)Ikf6$j_J`rog#@;Xkx`QIhdpK2R9SndDQi-zvZWRWA$#o_+)&DAL0_`-*H0mbp>-gf7oQDtLdN_%Eic|Zm z%in$1NBrLpul`2Z@6FAReoI<`!~LAyYlJZaNF!4E>1rj*TNwhx5cq=p2K^@ zl}T$yt#iIBUdOKdxOK+rUq193Dc&djYu9ng|LZR`j+Hi^k-xZLe(iqzJI;jT=|2wF zlh5MYDBd{jIe2&?d);}5>q_^0Dt-?aslMW#c!~N?<2w1->}6i(|7`i_eR0)?wD;D> zC-(ny^ZUgC6(=%YaCnRMY2MiS;QEoqv(9fmAOGvRaW(#kSJn@=ewF>4*T&hLIt z9T!d6@y-Fq%lK)0kH3`9Y5BtuY~THk;=r~~wP)${-agA8yWIUzoRoU}7*}`SzWw<# zdykhYFF$r&&ojIZU$wqkeNo5HzWL3mpX{Zd_?-Qeo1cs0lOO9GKc`=P;&6-qli%i* zPcAsV*1X>JaF^`i_{H@cjmwPxjSJB1lh&S{A4e6Z78i<@Tk1DTuR^x}}J6qS6HeYpI+(Nk=r@Ws#e!N1t>|c8N z)s>IVPw)IiIb6T;Y<*?ra{snB&((gU$7$?WU;2e1r#Pb~eLpSDj= zJYaq^UYzbaD;K}39F>#bDgV3TY1t*-x_)5wF;1)g95-D(F1>zXae#QO`&0RK+*9BA z-{F>(|IYh*?wem1f1AH|y|ssXyC3&gZ_ja z>$v*C_}}9H;-sFFwa?G-zs66>H6CbQQaOveR8AZu)xP*|ac4){Zhq-4nWwd3hK|BL%6pZS=4-+A1g3-XDFp88|=+VkSf)A6#Y`HOm=HcoE+ z_jq3Z+Ve@d{l6x^-dD;L!v&+KbmY#hP$^t0o1m8bVODi6Pz@^k6beYBhGk6RkI zb$|BQ^YN6|dz!M-baw0b;^;kJ@A+vS(tY`{`>s9aXY6GEoilg*zE9P6sBlgBO2< z>ig2JgRA36=5@vWjY}1GSlpTN+1|Y7#FvRDv+h;7#|6iS?mVb`c76BBFI^8OJzD+X zqvknN@r3H}Xq@!K7ryTwcbvv0`aZO{J=`z;h_fCpS^Mz)81;G-|B#<)`%fDGW1p!w zKxyAswSILRaQrWRQv9C!D;@X4=^SVKFI@RlKlq{NboV{=zWQ&TYyXd4{Z-{t&vC=- zpkGq1<3IBw{^P!B>yYK&I$pfZ`{mTrG!Aq8rTZ0Mh@bX8u47l<*>=5OxXOWRE5}c6 zsvQ6LN~iKsobq(#oO4%LGw`msnz%R5(bfU~i<{!ZjJg`MoOyI{3`g-poF{F) zH~Zp%l`DQKu96*#1FfCLO^QGC9Ew|5ms~r*4{?p7+b*BDVB@Q)^YzbNM?B%`z5iEE zdfVp*^NXJQ#lcx8eK=j*uIFg{Ok7v}($@P@>#Om=IAG&2X`HV3CffL%J^i1JbF}WX z_=x6#`yU%usUNt$}gclbR1zAEn3L z4)1&3Z=7pdeP+kjPs>;BLc0@xa#VSX1DtBFm(TIO z>G!Vv@;hGq-q`Ddu~$C7rOc%pLD+bjsLM@`CmNhlT+hM`P;TX z71y+Xdgq^A7Z>e0TYB*}wDDthzi)T^=IQC|KK?h|_HjVvcD>Z~J0G{X*ZZme-}&S( z=?|~}+w-5_{&YM)%Un)TI?kg#=`W^^U))<6<9^2uxJUNM&x?Qk z@+!aWTQ_PxIKRas^i!Qj<59&4I&bk@({r6&k7nP0SmVI_rRyAJ*Tp|pU&fd97sZjT z-o~xebM=^=%-h5l`d^%%;=ugT`?>z^8n=5-mHx(jGe2nEynZHoXhwESJQvv9P;(MpN8BT|d8xi{WsM!|wcrAK)j(|9HyxuX(onrtu~BHNK_Bf0dUV#&vo=#bM%q z`t|sX^BQ-{r~b=%anSg5aa?gZ92gf!)qC-KY2UxK9@{!xc8vQijmL}2)V{^%K8}{JaYlA?y>YJ|9L<2{5DM)bae)_EbL9?@|54 z;{3+@w(fWFf#p~EoOj|nTZdlUU*nqg$6-(YpSb&G;6D7|u8xz|uBm#xr?-8oecR9f>DHg#^V|0BJ8ramQS&I} zeCm_qc)mB^Djs9;QroWovH#2$T8}9oahcNY-#lXcWt{LC-=ut-ua(;wEbutOn=sW?%dCHOOFd_hx}n2 zYyNfot^L{GbJlg!_#%H=x_soHacR6y`dz=e{)fm9^9%MVJ%4t->xw^|-pg6J$CLDT z${Qck9-G(C?zH+|ylDO6+A%xWe^0w!^)df!-M@UEIKaxO9oUYmRUfmHe98av+y2GD zE#K4KfBlVlzI;v9Tjj_fdk<;X=a=l&{`?Xz%@3x_-{C*JkVtbs%_{ni; z_Q6ZEuU+qXef>`MNZG0UWDnz@%9oD&O^sLV$5ATR&*y*gIsVsqosVxwoA>ws>`7OS z#i5ORzS{vm@q80MGtDlo!xZ1bj=%m;|4Z4f-8wI>*SyC3n!g;~{^^b@UH#y9Z9iPF zG#+Q3q(0myJJb0ejsMk-<-dCIoN#>cq|RSGzVko)s_~=ijsqKSe~$m@fAgPd@7st2 zx?geR>HGCge^tMA+Tr@ixOnZO{LioImy{zr(ec0ODQD$g`PJ9#agWz){t*9Um-5?v z*`@N_HLlwDo!!J6v_4)wo42u>`F^T?^7ria{6Ee3!Si-{p5r}-^$+KNl;%PBjQaV= zKjJiJyZQ1sPTWuY0lUTj;%ImvPJ^r9W#y;#fma=F^t|5TM8%JZ-z%*+)te1 z(&KdJyB)>#ZTob5PkbIeHvZ>3Ah=%d!#f;p=S|=FUU7x3^JN#;#l05y7x(j>?EFoB z_2;hV|DQOX`WClkd-Y%aUtA6xX zc%bJb4yV65>N!^0cqlGsy>eU&pA+{HzxxlDir;b_<^MOY`)Jqh%Wv$*(@(r#evNaA zFFgG3&H-^!`M?3YuJdum_-Gt1j?(jVTrMusx>x1I!@j)ifAZaPy6eaB{GWzz;fyEl zum0Ng;(qG!#Ao4t#(8)TJGl>zDIe+ypW`P~eH_itN?W(v`f1#(I7#j19yiI4tSe@> zecxCdV&%rAw1@GG%0JE*Co-P3{V4k>m-5KZo&P;~U-pP^dd_?|_Zt`Ve8SnJ$Jtsp zt$oQS|1bY1Zqau2)%?#qkp1Eh#u>Ix%`2p7bRT};`q?KQ zqFs7lTKU-iwTs#5Y47FxyY)9;*NYcdp5}dVp3Up2ak+fom3^gMpT2XMaf73qU(Y^I z{xc3Z-uJHKe@CD5`{h?Y>tDvHmd|~kr1hXHS6V+Mjf=9+?|iaTdbr-y{Q==1-8?{5G2RWHVW)%*MP#;McR_kNc@mjC=zd%vgWZ~Ce7 z9k0@^q$#_wbM|T8Ydj@A-MrcJLVb)=sYhw$zw7*A{7*jY_rB7uyZdy$``AD2dex8Z zKfM08q57M&^x=QU@9fVndoG%{zxxwjBp=gwQpcH(@4MQ#Sou9X{cc}=Cw6|CjFk&v?dp zH2#x4#u=x^vE_T({|CmMao59(#{F!!{e_eT|alg2Xa{1r0 zdV2CdyePYTPIta>z}5@zeJy>b&HrXy*Lq-n@Ol1MToyYn-f#TRyp*4ggP6BAPK&?% z#x)=1r>%3hE~|cX|Buvf;!|&?$zUCFUlyR!;R1k8Qrs-|$fPOKZQ?f9>bXYsM=*-Sd{#j_&_c#gT2t zd+D?Pvfp!W>bUwr?Zthp=gkhDJJ~7w?KwDZcj813FRq;BcRcT|mHU5O^GELs&p&6k z`B&U9?#JHQCq7>J4*&b%#R00H#R;m1+GDEy_dKTZ*K>LNPrJGMRsPd_8Bfv9kAD^S zfPcsjPSpBc^FF+1+Wgt~jd8QKYaiAv#*4oB)NkO0<@azx{@?oI_#K`Te>0!Nai-hf z@rN^xJK-7bH*H?*xYn;%57PaAF|B;+9}g^l%Heq#*Vo>&oAu88tnV+Ik7n-_?-N(J z__WgUZC!Kk)w^r!dvQ6}iwAzx_#L}=Um89qu1$Ru*Va15!~ezsseDg&o%?<8*N#7G z|1ZDn80YIfZtPmR?-Gye#r@c6^)Q`Z#N$rA#8dw66K}y6`<_qy<jw}_J#=heDl-$996Y&|)@uYSk<#sSrr_A=Ez|Kr8sJiqWi zDy_f5|FqYiT`FF=wDHBCUH1J)SHE`lyNGtoNn( zUaBA4cZlP6`Z-+fsXxB#hPzF1EPPJ?|2r?$U&P~Z!}?Qv(D*2BhnqEi`OBC6OM8B_ zju^jVU)NC|i!XG2?ZW+V7u-=C;_toE#UbL)cpzSD9kO-op>c@8km60E_xCR9Ps9O=%j~^>`t8c+IM-3m?1d*OkNw8s9oKqP^P=t( z|C8_R6R#Y<@*Z6G!}rd8#;tmfG_L9YiuU7F`ES>ApYbt%h@UhbzVjX9W$AIzG<)DE z?2_USJ!fh0XH)guyzsma?VVr5H}I?Glkpw)IQP-sq{~lsn%&09ygzdLkFs0!yLdl- zcKpNqts%Y7a1zIR=Iruu99 zsrojbbzk$KdwM*OUF=s6Cq;}q|9TKZ`G)c9RKr}~T1*_nUb(>ve)Yuf48S3id@etX4- zyZkIi>de%pK{9e)^)`7ZwFe#XP<>8{Fa{L5dB$Mo;g%F{S`^VjL(|C-OnYw~l~ zJ)9|C#D3*>+-mDESFY95)N%17=gqF#OZLs5$M>{wyZKIC8d zo&KTp=?}VJJi@%HboE!g)h~8``NIEdA8Sw3ad!4DU-O5jjuS6lbZYzEF5{--I&miT zkp0r^$BuEc`eEt$gLb9fv^U%D{xAJre@i>R>pt`K-mboU&EH+;SB{P=zvGm(zuIg0X6M=S=yx4AKb;@urz@}bYiEyfzGwT>?yA@PMSIL&+8$>q z-?q=6*KbajfA=f@&v?0Uvv)O~>HhQ6&d)#CbA0oeZ|xvEQsXJdH9x>rtk*fpKUV(l z;(mAjdD^k|lKtMxgQqkP^nEY!Qg;qGPBlKYI6>nW?alb~uEsyoDL?P~Wa62skJ9Fg z@*~b<8b64)6+dNvaU-eg;(>97xL>>l4~_rz{!8^4zv+Jz^{GGQ7xk;-IHlWOdB(BS zgYsp!@ztl|W%eIc?~ON=cm38>KViTAA$wFG^Vg?c$N%~tx$oo^Zz&Ede^al`qvSVU zCqH}M&hKjHPu^wRzUN9@wEr#gKka}06Rn(Gcm37j?(9&#^H=rP`ei(B<*5GhkK#nt zt8(BXm8Z1rT}Qe&1^dO5(Z!bs}pZ%}0=jD66U(aLx7r)W& z^P}wcEp2l+)Uv;?8IADBETq2%F#e*DGF6pV`@SXVBQM~9L7dSqH z>lMG}y?`HiQ}e=jpLRIzHx4+?_vLk8ylR?%N^74-@R?f;JaRX>Q=*x&lg@xQ)v!j9w0`RU<)^RM|ie~2Sje(zn||61dI)3}{=!1$f{ z1^xatuB66oxSw&Iv~^{z2X;Je@yC~H*Z=92wqDh`;FKTz^u_ z54=*j@Rq6iES`;DEq)JA6i*rdbHDM!z88GBpM2tWHXX1kXAH)0j^|;l}OU+L@&;7E)M|HnA zrF!hXDL<5EmpCMTRlUby;x+Lb`7e!sm>;T_`@HdRzr`gj-mUXIuU&V#{B-}z?3ex8 zzwgInKldr$@jd=gJ*LKc(){Oa=ht}Q{437PK3`ntyB^*g&t;FsZBP5e=j5yH<%|D) zOxOR!q52N?vHScWyR)P7@B8oewmmy!5BF>T=T(2ueTy6X>gumLK7OWumA>1zo+} zc|T8|=PU2{de`+_cK#GElO8t{-&lUfSt{@H=Q-B+J9Qmt&wc8-N%@cK#Ch)8{Ce~E z_|%!#@A&aj^_qRMuXZgxUEGiU#`eQ8pYt5g!SZ$Dy}It<4fbz7q`xrkb^p7vzw}f- z8Xxzb!FQhLIo1Bfqb$Ao%Hk}#-&fatv*S2JTxIrHIkl(kke!W#Di3@0J_%d^x3JxH z>G8WKhn|0#-|~m~|G0tYb=NubUB|J{=hSn;c3kDI>Q`EO?s~-=@*C-Q-Z$sUm#^vk`@3}QZ2iK% z!*Vn~H{R-g%g6jAztO(hpK51ISMK=M{AxP89j*PX9sWFZefECpxYhD^+MnaJH~E>4 zPfhc?=Kc9|e!u=>e!G58zVH7>`rq*Ge|ug{#Xoso?SGti4wxP5pJqRL{GoEOOXa@D z4>q2NLsc*18`HC{`PuH{(aoQnZ~nCV=U27ExahHuaeMopTxNV`cKt3L&pA3ym5$qt z`-%Ul+~&i^f#T58GcQ%YaXR^EdnzBL`yM(wmR|hUxXu1g>3Cx?kz|l73$L$^YuN*wOZQpy$^5)5HIqpS{!gU-P5Cy~g9>#+;A0P;pMKBksw0 z_xJDNW!{4z-@V`Auvx1qO^Lz{fbLa?j2uzq;kw(i%;EiXWJJaxOStw<^TTtmB0Rv z@tn&)=0A(e?)hu{n4j!D1bZIuxliLEcnq$R;v%z4^FZ7m2Vy5YZ+f_&`o?vp{NR6i zT~GXo{`LNSW?bvUtu1~HN5c>CF?_T2yhr=~0baNFy*pq;f;6x$4_ua_2&JAxHcZx_d|-)^M1U_7r(G>Sbozd{~ITaOR@tlc~t(Cb2<*# z^UFGBes*|Q@u7HE+{E>N_TnW|9I|}jY4SB5h+Fo2ii5zJL7 zQ##-NuGe=~`kzku_2+5zWjt8@u%G)*XQ$cicdzT(uN?8{(s4l7tsL=5{bTn3oYo#Y zKVIZ{jJFxDP<-@oBfQmn|BBx{e5dEX^tg}lxwJS~{G#s{8;2Bs_@k>ojsxO;xC7n& zlrN6N&%00j&vztF`hMTVnZ3uKmF{|u$C2V3ag{ifaR)AF9Amrj1~pzUJx)`+nfQkG zkK;{0e}Cgd<QFnTRxs@9&qY+{xvP$)_okuPR2>@V_r{JuWA0? zapQG&dslw@`6n&^{DvRY&pp+3^jD6bI{uvtu72%*Vr zKR?>_zPjqG>!;R@NYgk(I{p{;IOF^0`~33b#;@k#`FFf!@qqY3^>nm$;ymTPtMW^4 zzW;GP8}Hk8^&sExs-A3rYV}z?ExvZ&jfn#m&lorBxLqgCpg!bp`ivK2$0z@@ezEc5 z*4@TUw3n{aJgIqA{*gV#SKfKUllP5FjO!e(@{xzh$L2ZbxO+Y}PiwwdJ)AhC<`>WT zz55&Q-nHYJPsI!L)1Alvvd89G@jlN_*V#N~x_Li8?7Z>2^xa<$7rOJ-`JZ|nw`=|t zKl9uf*PY$sCjRHm4?1u2F!`&VPCQn}J^9}Hg(*(rxT)t^{|kJVe?9r!xZm_2;(y04 zPPwYr`O%XntFQUrG`k;vtbXSQn>UZUrP_7p9d*5TUOVnN9d}FXzskpx>yGc{|2^m2 z@A%pBJ8oS1qd(4%-rL#I*=crMdwbW>UqWe>io#>#$#3X8e!J z=eU~ts_$_(S{$A@tLzYuY2GRyrN;$R+)N9>pTBdzZFk(xPmQbRPZS@X z=3jB0I}h7)r03G}|E1dF=`T(@Tz`h6t=`P@UEe%Z{Z8ASAMl68^J(94;ocL;Zl#ar zkNKr`Q90w*%Kzkjwe$IN^Frkx2lW4Yew+REOZnmS@W1S`_YZ7;?Mgf9Jls$D#{=0< zI=%Dk!$tU6_KE+D|55zs%J7Q=_MRyG1m|JT_|MXJ&Ufd5+fIMwbsi4pd>nFWeA)N4 zPJP6i`OWNlZ|D4=exdrQ9OHgR#{-KCvt7KQ^5b&uA1_khSV>H^={aKi&Pkd#)cB6u;Md0ZaelmBt63-0#W%#uxc54te+=Kg9p~&TZcnu;2Ts za5C{wNAW-$xOh5ofc{@u93YO@{~+$eF7(d-+(*4{JD#FG@jdp4hyL9a@74P7;w1m> z#a;ZLVw|R*tlsp0>h-SU|5No^KS{TqI6taBaNO##{?dKs&(ra3<>PPij|1WqfAZpT z-+%Ex-0#19;(34a;&|V@_?~`Y>v|XWNA-K+1^ELGh__Jv!XLfT)(zu};^Xi>-vJTt z_w_YD^}XM3UTOUSj#m5}?uR=a{-@s`_rueCCjtL4E{^*cm*D~9e#X_(=2^uBy8hQ+ z{Ni;#T+jQS@H-sxuI5|PPn93X#V5*N=aui}U;Dua*}=MC_7?}Jo#TSIu>9&*nD0eTlUXY2(5vj@i0melqU4^{4FB zcUhH(Kb2;u_#X~s9&xwRN6ypwV*L#}{_yHw*zwz|Kf$Al`_oQZUw!9cjyGODTD_FU zmsUShem&kw^+QKHKHjFh_w@3uJY7E?_Pl@f(taFLe(>XX)Uk)-?)i|;PTE<1=e+z} zK8ur;|9Ib&-)iSm_2)kMbAA;MRBz*ctvi=b{S0`|9BYxEFFhc&aT(EfBbLp8qMeO)6QEQ$L3?p@8(I<_jrTN zD|VmCvH6AjRGz7Maq}Dh9|zQ4^0)E7C;!F?%YRyb(swF8 z@286^j`!#<9OwB!@99(C`mej4PP<(@pC8mNUB~fvz5CZ`{~fpVyY4=#pF2M)Km53U z_oR=X@BYeXzkapjmfyp#+dfW_f8!>$zu)(yKbEuOw|(`MzW0AC@3tEkIDh4Swm;+7 zGfx$VXMPp0+y64+^Z4sH^Yi~A#H@&4Rd`uRN54|Sd5VCRqTcHZ`5 zwJA2{>=+53N1AC6<5YFu{L_+R}~^VmBNZ2Z}EcD?wY`!=+PPO;a{q4o&zWHQl z+|P0GKlL7uEI;E&@onQ8-!nNH5AFSS))n{Nj&VPntMdQi<>xq5@qb5)1MK+hVZE>P z_rCZim*Qpr{(ps;zjEh*?Hwpk3Y|^k3aant@fz@%#Uz7&x3ef{7$;{zt8o(+WGx^ANskz3t}D- z4|JY>1uyg*6!+)*y}egZJVD?8{jFErUp&w}HQpCz8*kIU;&@YjKCbukG)@;6z}dtx zy8aI@{`W^OZd4qf`^J-|-qRXaqVnN9_iej*SN!QWUmO$PP@Zu>@88A=e|VL*ctJX@ zIW9Ll<_YbPa zIG{K>@1Mi}_@j8b>i=EiJop#C>HEj2{tE9K53`O5AFDpvZol*5a(LpYH~nAsU;RwC zeH>66i+b61$GML90$RMN^uKx?m)4)MzvlrpkD69a+)}wy&n4;9d2uZHKRj*w^H2`()>xfc-pvn@sabZ{C?}zkMGG|emjC$0=INWiZhku*S6X`W-E&^^a{2ZA+`Mt~N$0zt^Skf3-t_Ee7k(7)jFWl} zwtd{TwC@Ex?f6X3&UjttKi3;;|JkScw0e@prIo{d8xM>JwC+*<%q#er{oh>nH2(kg zs&BgS|M}m4e4_FA^Zaw2+1Y;AoyzAuANmpL;uQJ+=2LX@k#Dc(yYqhO8qNOUrL|+{ zssEp+<1W+Z^|hCAn96m^+4yPm^|W!E`<-!n=WSi8_E~yFpY&(n~jI-9N|4*~Nb2 zzK+wb8c(MICbA8VvcDmbb?Pz^;c;;$MZDK zbHBd%(bi{<*U+|~IJfe}o~w^zPyTtH2lLnQy{A^*{H6X<{Ec+ld>Yp_Zcp{6G`{=0fQ_4bVaTmEVPE8(Jzlg0t>ely;wT$O)3k>WMQF%{QT{LnZ>?RM{h zOvO9pXTSVOdq1SOuzR`Gr{jv>%MYaUtE2qibE@w~eHZ^b$18XF%5M5A<s4S`xh7Zqifux z9=^TCP40)|NUxp8B~QEOZ{zd+H>sWe&6R)e1Lcp#7w7*K<<{SRdEHlkiwk(}$Ni?` zen;^?^*qJ@l;^IMCr-#N%EgboC!p_8C{OE~i~o!F#leazw7odF;tiMXeSbI^{^xpM z|NZslW7nO={qVDK*0|sJ*LYug`Un44@Qc}d>N@(@sr!uk;o#yFwTEfzd;j)Te(i-l zvmQ?I?R5to#9-D&m0u5sGa561IKdp@jx z%8&RBzvma?pZLvJuQb0AuXoqJ`@8S=;#uuajSJ$1zj>+t4i9ACeGjDf1nxLI#`iwF zpPb?{c$xHHT=}pb7-#doqPUv%x9SH6Qy;~>`JWue8UOSAFD;%9Cn(O&`b!+_>(_aW z+@9w|-*5iGi=%1> z?5-b-*N*q4#rui7#G4(LUHbkY`-;2D&cAl;Z@ikn#REM*OXHB*&2+qJ+IHhZ`SzWf zY1i*K`%71^>Nl>Gju(yROvm}g1N~p)>?xkMyp;>mH64S2ORBPh3L2jHk=r zdB0-&I&J6gI@JB>?$^3&+qVu|eOGUe!(pYrx$Kc&iaTI$Qmzg&hKgFTqZl#qc{%1V0D`DdTN>`ko5wD_d3y8X_(JpEc)^+XkNbU>#vxqaI4yf*_w2NJ z>vZ{T{q%_w%|7{${PH7qfAV$yWc$wBdmpFj`*Zi@57}w&>1@57{5Joo+>UEJUK~^0 z?|T<-iwk^n`9t<>ysAE=&phV5r@ZZlFP4s5j9)x?MCI+c#Q~1%q~i{$^$W}I<`2*7 z^B>nc`s5>L`|~*d)_KJ_Y~C2>YkY41;%OR3s{h$%b{RKGwLj-gkDrzAkDNk2>d%hW zuNnX2>G|E__YS|WUYpN0f0e&qc^&WnfBUuT&TpQf9^0PkH`_mr18T>%f8<%u>nM-o zrt`PyxZjjry6$Pe-CsL997(&keH`xHj@y3P`RaZCl)c3@nO_#qYdm55H2cOA<{#DT z{C>K5?Cy8^nf!C@YUMmSJFfqF+Mj=BkLk)i{<$=5{CJdovYYXBcI>?Y`jxI*Kj8fx z`TKa~IN{3uY!CdV{czaoV{!3Eac3d2{hOty_z;na7{?zi}`3<$r5;r#{#3&d&4G#rKu={LoH}x7m4o z1+Oq)o*wR}A1w~@Z?1WuI5X$tp3Sed&+Jyc?Y`r$pV#G|zbdEx{AlG<4~{e6|LQ8Y z{c&2`#rbLXI8*U`((#w;#1~&l`PbLi@%3kMzBoqlM)4^A(e-NI$N!|?`QQ9z{|olM zitk_ZWc`KqogMZbi#V6-k7KK+#_f*Z|Bf54?fJatG45AB)(<wV3a@v7qC;(gYI@{_Hr9XG?v#{1OA_TyXC*WJGAPkSp4ZT=WH z{mB2cx6{A!zxdzyPjO%4f#?5(j&on}eeasT$ais}$B*P6e^MTP7MGizIKVg{t|x!u zPrXmDcvR)ju7~^e{f`qzw{^9S^FGCC98MhN)+K9?Cl0Q5u(-e4#o|K`ALkeOU0hE6 z<8wG(Jn-m8KZplkpXo=W*B`M{{hjar#`jv^d$?a5@IC&|_}ua1dwAU8fVLMO zI4%B9+<-X1=D+wKjukhH`{6;zt(8 z<#_#N+$ZiQ|J|qi$B|s$cKvyr30H9(m0$etFJ9ws{15l~gHPqaGu@|h#R>Iee|Vj5 zye&wsKnfTDQ<8An1@iE5^*`;-<%IkP`DJ~E16sK1_;C@NSlOYQveJaLry6Wu!0qdRVT_+R$8^DX&_FKLf)5xlSd-uFMux2-EqJ-_a8d-;v) z^3S`yvwP*|FYF+{#?#q5{-@q6&v=^c_jUChKi>B7{Chi;5AmpJc0BD%K8)|}Up%IH zQ1_p{UvJ!R@xJ9#J$0XzW9RSqxMduWf3TZ&G~V^(R_eET#p)w94{W{?FMQ{1M6 zZ{Bj}H+TM*|Bru<`%T@i_OZCd_@DmVcJqk#$0yZC_ZyFV@;>&ppa0YGzR#(08aFqO z+V`O2eR#)x|BjpLU)vvVa$o7s^S{OawZ2il4hLL4ocA9-%lAI-E5FU}^4spa`S6qf zZQgzK$z#R|)Q9J7^Ss)faRWcP>yAGpMq&=Y8+~HU2l% zkGkH}_p79*yYK3UnxA}5mD6+guJ1gmaVlPNAHUZ>HeT6#0~b&9FHjWgq`vwLN>D z??J?Mj{m&#fpLQL&X>D?JTqQUe`&jZ@UF8*yp121U+vFv@9k~dwS%tnUHbH&D=JUpTwfFkBkL_(-&;Nw^(WwvVxR!j4C$8VdbzC18o4Wqt zJ^J%;yy=%$`JOy5&Ug0T~+s_xQH@JNa5W-Se4$ zvAcSv>Yc{**`epiy}tAtKcD}_2|QQK;~lRY&8y9?rPa^W{hNo6ld+3@yzA^dj;=f_ zSI^PIIi+2w2$Q{EvNo$05ZT;(yfhz3aPP^_N}q zi}Zp0q(KIO!_<>SdCTYt(vzE5)O zG<(JUT0e^`w(k6?xLNPX``cH%A3L;;mc6}K(RIK7io1*ZoqAXtUdlg}_h|lk{PgYz z>j&c9tN+^Z+OzxVH>KJ2*lq2-@BPHn*(blNz2|RnZvB9I@BNPBfZeD6HE_VCIcS`Z zf9en8__X&g$XD&Vc3=N6-WUH{J5sN`cfAN7lL-6O<@z$#r|K~fvhyR(c#9#W}hI#e*&aQTYZ}A^IKwKs6XWi_7 zy43zZzEu0bz2a-7ahLu-aJ_G?egaQ2E{@|o-|uIfb2x>1j6=HLcwPJ`{`bRA@qS0~ zKhKpr7u0{^SmS@?v-_O&!_woBX`H6*aZuwl>8bq2bHoASe*f`R{^I3&UtgTC_urZK zIo|uz;(+(KzqZE#i|Z|BDAzFXMdiKjX^m z?mN)zKb{x=Gp>j~J>N$s9x!_^PVn>m&$v4~-1&|AG;S@<+xo|EulwLuKf1QZf8u}f zto*`u{z0>|dg%J*72n0lYWqQrB<1H4fN(PCgn(P~*kL z!);#iocHmU#!KT(>EiGXkK1=x&N?>bTYdQdMS7}Tm0nyazFfa)`?%kCYv*kpI6q*Y zaX@@8do3Pt`QChgb{mfy|6~t#Y#y-j{_H@rU;GcxYy46?pnR~`=4sylKHRD}xym;_9nX(L@t5L-HKr;+{R5KfYc5yFa_#d0*oj$Ggvze|+_+{ZiLeUtM=xAnu1(+HRcr z)c3gGXL;{@vGd;Tw{|+Mz0U3{|Lme2xX!!kw`$Mhe&c(e}kLLxAUG{kX>z`dTw>x z+Iew+`W@|V9Nu%nal8I>`O|*7ZrsUyo4=XYj|1{Y+=b#WRK4HTbvv$pf6tL^-|^dy zt2$o!yUvsU`ClM^8V_&&v-;7FDu45&l|#Aecbd;>@0;J%uZ=sj9nW_BxDsC9`A_~g zE;#P=k^e0&ZQO0`)O^(c_Ut@W?k6XH=YQ*m#{H(-&c7?aeAbW1_u9jkSHB@W&ZAzH ze_A}Be2nvnYmuIAJB>R`dmfm-$7AA6=DYb#cAg#Xs-I^k{X6@opKI@{2mZ!xt$%AA zrQGV{uG#0rTUo!zfANsRRmNGAbKH+#tzLQ#x$bj+>34gU9)}%Ad-A{L`^9aD$5NiB zoyOfC2JeGRL3Hfj5PmAA@@4gFtI9l~_{35^IIDmgC7kl2v3Hx8H z_fGUYy2rKcIeD~pxbXphcis8D`4&4*v$u49%`dA58sD1YO6*Oa|HbvxTd7rL{x$&)>AWao@WxPIv2~JN_fz zn_Z^krBn8f`^OL2MZZ7gm-_wMfBX+W?|#KS7WY>i;P~J4%gg`pzv{34ah!krf9<~Y z?Df;tYyO#^*RPka{J(ZmyHbDpJsSV}uJ`@nL2*5*y*~LLzWHZg{lWG1kpJ&>+!xn% z9cTQC_nG(I)p$NmlX{NhJ@`IehSN;(s^-<=8O`gxkL*8R>UjK*z2jWoTNnp0pDqrt zxH}xDc|e>e-e|lK-y7%KdfyZ87x%&aT3>6u^4FKWqpD1K^%dWYf8t)s-MU|X*Sg>DU-xG}p<;ebbWmjp+AE*54 zd!P8Sb;8o>fwD(_=R4Ep%XoC_!~Xp0KYV}0dnv_>cAcNTlwWlHyJjc#U|d*z;DSBx zOXJJ>fBTO#@5|Y4d*RUH|ZK{#-k$ z-0{lzVE$0Ki#v2ayB>dy`x!4}@8^8sBmcsu*c~_Nd*MgRfAf=FXS^>R|D)yWSwH&U z%Ar2lyLvPakT!2^dtA^sPkOrJY2~av>Mx|HAKU5j`H=%UPe0TANnFN>la$}Kj{`0} z{&)D>-7bsY_@Cu}algvxI?CJin%9jFzU$7j-8e`+-*xls&uh;q&uh=C#=mht*X{Xx z;s6_WHqX;fd@j9t@tJ==d7FAEf8!ia{yOgWdF7X__vQcWqrGM)>B9x}vu)oxy2JO} zpFQq6F6g?(3se1Vkd zzj0aDSv|zf`Mv8+jc28g-Z^07xbm^><9mB=?A{mJ_RSkk{#p+_{uj4VZR)Vua-XkReqFL{{CUjzlx7M<9FkZ%9o$Gj{Lmqc-&NdblmiL-nbsl*Ku11JPtT6 zm};L-JLj)!C-_t4EZ)z&Q$I9im!89Wel`A4j-F>n>))O{@ZSG-{PX$V_*VV(eEP`$ zKK2jF?f9eG6?@gb+P?Oye{0-V|JDBy%2oe#`oGfgocYr`Z}J@P`t=jqm-JEgG_E)Q z-~SoKH`u;7+QrwdeXbtf+xxiR^l%pUUwPBYS^gKFHvTiU9k=`HYA+x8UGwq!fBVgE z@uexd-#LhK$3KpKj{9YglV8u3@!kA!eqX)b>oZ=re%rbV{_6dVDXvny8jd1Z z+f(WN|DxUH2ij})sr}sJ+bVy2$$k6o!--!T_j~H$QsaN-&;RHu&s}jrX*&KljT_tF z_f=Xqd*T84tvEaL()@h!f7!?WI3K&#{`Ft{d4Ah-y8YeHaqjom*L8cYPuZckY|2jB z@$7|%`aXdC_&$bwdT-p(#r8G>D zcqzN(f9dJ(&;JtD`}_ds#L=g%Gq!%Z_8X@iCp_14ef6S!8Xw0a@;m;||EPS+XL^4= zY+R;a(4XPGRGeCIe7GLJD$XxuC;R!6?Qt;2iIa1lc;2J>&At!({cF4uSHWH6J2fwf z7Zgv2KZ(=xzP|tVYL|51$;JJObNl`^53#QI+l&9<0poq~Klv61hx0ma>vwxT;xV3+ zM;G_?k-v>+OpT9l4dpH0t?!L!xVcKO-2m*07BrT4=* z&NzV@hr0f|YIphZ{Q9S_dcynE*U^9XDV^efI3XTYea6`iA1YpufAU}N1DhG~UdB*+p6Usf#H9hl*%`cjd#FaKL zo$}W>iny!RD?5JclHR}H`+h&yS$is<+Mj-b{rTI{@jr0@9as8uoX`HVJx<79-G?2i zd0D!0FCR}{zx;hpvkUH4f7$oErF)*)t{lzF79ZGqDEY7L<9^3pPfmp!b)RY1-|@<6 zzxj6e**f4f-WPwde{qlT)H2yd4@I&aI}{JOH2-dUb`#$!z3tj#`^WX}{4b7g|F|IkydR%`E9cHHf7)qw zd(QXo{IBs&<(gfM)7fLnFSE}yzNbIxxWx^&9+=&1kNbVp_j+Uh>T&fv{ubvlFR8qH zf9KZ8_kIQcduE?FwtlhWr;8&RcPKs1%nuwtRqoCoXNz|<9@k#VU;p2;)6ReT^{zL+ zpMG_n@A~=)iXYt5t}8t?|CgScKS+CyRKMxw74O@}4|e_(Pq^Rb-0xX__1yi_`St&t z?td5MsUMDaAMQQBHJ&*AbpBlVYF}IL{;@x}^ELMwUu~W~9c1t@!#+L4}Y(` z&;Lct3uXuTVwdT*e_rQ@M>}s^<6K8O*tq`a;$EJ*@;GkiQT1|H&tK&={g=~PrkGJ(x+S`{W?Eb{~n)^Kjpe>d!V|F<~5sdBo$=LJ=c>i=_E+$1g$kI}BGzdP4*e(`PN ze^d2RJ*D-#c!qU2&g1V>_NzVheUD>L$Hh4ox0zOc@o@N*_u`3vJp3vCchdK`H1THR zeBx)Mr`ygzizlS>>nXq9c05b}!T*a39p_3{LL$l4^Ld2pXUld`I-7v?zHzH#sSZJ2J7d19~oEey@_$l zIBd@o{v*DhKY4DC`|(5lU8XFX4}O{`cc6PU?>@E`qO$6J#gf z_n7wFbiU^&F6jMU(&mAO`)S{c$J)AIynx@C_fOdg7ZC4>WAHQcfA_-xnPI!=5RuIaw`Tf9mB;u$Bt?9S`P1K)Wb-sZTpa>nn91H|X-pW+tM zsdnam+Hc$Ow&D$Ozc}7eUoP{uBrN9RK_B zx=!(%+Hd@9d~W;)*J<38J^uHXUGxjj^cgSPE`N7Dae!Ta@ru*h7rWp2pLF?CKk}!( zsQFg@I*wNyrh3b-pY7%8-`Tz6df%e^NWZIkvVB}}I{tX{$^VLbRAJKyIg*=_SH^H}o(^RVVS?6mou z951_hpJ(4ao;~Hm@l)kGys`0K{Y3Xa^Spf@g}v*~m1q2K>$1mZ7Z>3^jo*t~k>8%z z)5eqIedbZdxs5aV4{kNpAGHqk<8^ku?&JA#zwgTXuG%kqsE6!Q{59@ZedW*Vr?rEQ zdvZViZu_|3QQP~U%l_2^-q-QZ`g48%8|u&5$@8@F!t}X*nY}u0^H}!GPmI&Y_msPF z`;(i_j`nw*?8rY$Ke?^#<)?g`Cn(1_ocT%V=XUe={5M{6&KqZ#=AZhB?DOPw{G{zq z?!yk<_wWz-yz{j3z57qQzINw)e%E!zlb-z2`_q*pW#8`Ce6;)B^Rex;`=^^%j1wG< zSI$1~b{qFQy8i)|@2CCV{oDUX%WxiJ-+qb-{XSybFLEy%&(R2aH@EfdaNF% zhYw_r;(l<7{Ozgg+jiRV^ONzt)%)se^?K~_y#Lca^RsDwaN@6x>z#k%4bT4x@}>Xm z`qS}_r#7GFU#%y0p7YhuUD;du=vkj!`S1Pdor`Y1as2=8hx|o{rsc*>ff5DBYM}{cpT}{Z1Uj zdE+bq#eh`N`^IP+J&%e0e&*O38R>TjTI6&o#8&P({|IBO6%ZrP`Kg{dK0plWZ z68S#yfZ6G+hkn{6?rHs9+o#)}ZvN}K`IC0)J?HD^_x#9@@ju5|$9cHl_@DW<^Ub%_ zLy9|man*b3zS6t@GybOcbYaS{#{IB-t zx*Koof4}+lo^SXDdrF({|MJWJ;v3^j6koW>ZId@xXcefah&*{`o72i zshB(ei^q-oi~}A1h5N~exE@?AKXc!&FFW!Z{$c!<##R67YG=JC3U4VwaBs)=9SnAi1L}YHpR|0& z36J6e>@ckz<)^MYzu*4ar|UINC_d8l7Vp`2LfGAVCFK)m&;NYyL_6?4#PlcEdD_{u zenWq`c*gi2zcxPRZ=NS{Gk#^hq}*xw>N&z5{ER;wjq7Pw#Y-9Q7Z>Hb!2j!2EC26{ zlUQGAd+UVd$8qtX^Zj4Xzj%vzSnDpm|4%#K_dm8icJFZ;hoH)V%dwC6qH(|Jb=y~b zUmOq@`|8Sxj`4!Z%U*}O^b?6u*Jm1!8{e5{(xuHerEvi~7f0#1_@MVZRxZ5M{Qj)3 zj`z)f{_w@+zJ7hT#(cc**WiCR9}e`VmwGSYpT5fVTdy>KlE(jz#zFt|vcK`8?fe1{ zOkD>jEG-|#&wqZ^PkehkQ2lKEFuqm&#Rd6s?KQox5B9v>I$r8N;{K-WSR9~!fxYtI z^7ZtCeSf+*I`b**Lwk(3iBs(S(l}-9;;!mVdb;?%()n%NwRQctwlrmb{&d$nf6adJ z)$u-D-~FbzU+MTF?xCDh?TH<=Vy~@($Km-ke`Du2^z2UBD^@H#A|GNI{tLu4fyKxkMFg~k%|N5ne6OI=aC%OI$C#n47 z$MN5H{&&)q+j-^pKEIOB%Eiw=?pLnoyf*Gv|6v~Hx_2Fai~so!PwQ3BJbk=r=WU+c zeaxTaWAi)nUupB-w0y2UpSAwc$VuL z7f92k+2ek{bKlCndH&Hm|ET>`4|o0-7qQ)Qq51FPpW>_Aez;$JCA%9x7gsoY@zd&U z?O+<;)7~2Y{r0Ooc%*V^pLZQcn2wvCxR||1Ywz(n>leEIxZgCpvXA}a6P`OAfB1*| z&p-bmZJzez2bDjbv-rC>gX?CW;*In#)f4}8-t?R|F4X*yKXv`$=FYtQ*`5yfYyQcO z&aTme9daeDI-u7|d z`C0xXKh@K8+o$uRcb%U-wf~Rsh#$TGOXVKVH4L@A+S- zcI-LpyJ*h)=F@XxJP^-ye*CZTZ~pM~U-@RA_j=!U`DBl&=eBfO`)I!2bH#PCUz~#f zNYC!d+5Xj6%CF>O?S0%G|H*IH-uApq$2X^^pLufF)rWkm5B53gzV!$8mybA9^M3me zcQX$z&ZT;d4|!h36Amvr$925x#D9Db)OGNgqg$8P{Mq*BeEsA@e&locoqqYr|BqI# zmG7PZ;UBfD{B?H9j>?DosXrVrI~|>0O~?PH<9?Hel{OFdK05P9e8=?{=aqWTo9(IjBEO%XkNdHY`zWWl#Qcqat55!^ z{qVc}-6vM)ib|{ zx2czLxH#ZnU-rWP{`&9pwfuSSpLRJux%`d$^$!e>@9@9c+sExYuKzC_-}>0>zj`=2J2anDpZLM4*R7Lg2Y#SjxNsW( z^WIJCnaBUEoBsAHmH$De@l5Nny{Djfz~cPGJsjT0KIS>=ceHckm~Sr*WV`jA)b{*SO z{Z5=o{^A(O-^Z!L~*>nY=Q?C1R6XP3%{?RQoG z@+02Teer5`-tzOxQ=>wf3IJ>`lJ8G{W|_nFTekV>wG-W zJecBbN7>_Fz0$_5e|qK1{FtBP7ySC`t9(;DoBi%8ZcIA8%=7X)e(61Uu7h7Sp6~lM z>}7wPuJ467uW_&ED|<~nzok8|)7rt}RlonmpS9A7A3-G3agawvc6jvb#r zjT`5u{DJ@CAawD6>Lvd!K2Eu%H$T14%WP*4%1BIKgT?E_k6d^0UE^-kXWZuM z(L7vv_!U*}6o;=|i{Fc@jQcsx{^@w%bbNOF@9zK3bHANmdEWV79MC#J`<;K+y@!gj z6Tf-t=Q*G2bX;6R`*hu@=Zy5--sKm^x%=(nfX0oB6XI9wryjE7c=%J-uHDCR?Do`- z=U=w3T^&7sEPu`8*F@LVqo>`u{>k^=oA%FN_cbr;{-w|VM0;MuS&Yx`$H_dCFvp*Mv-Z3=Kk-eD$NlIJ|Ni+AXB-DS?Jj>m`6}%=yukJ9U*d51SoRy= zh&$kH^;2zE@8-?o_bRie;yS%=%lxwEC~m~hooD>p^>C%^k$!Q_kK=#1hj|?? z^z~IAxR80JP0@M%U}GV{vdxmymWpuUA@q_U3`GuyWSMn8|UM1 z=er?zh4{ekdw(AzJI4Rwf&6CiuIjaP`Z@pLhw|k;Hx!q0TybH}i~Ai_j{LCW;^vLZ zPWvg{`Y8SopP64M$Kw6)zBrpWx8C1q9?f6kFU7xESGx75M~gq(dei6e?kkS)sOw9| z1@V|4zBm*=jxSd3@u|4m@%Qn+wEkdz9d};4Jvu*c{dsYL-&~x>bEfy;@mKAmctG}u zOP=<_|N7n+e|KO0&i?V*xZ=IuR*pE=;@?&ut^3EHp1id`8GzrcMDRQ>6r%LlGmJDSdqPkYJ#;>Gx0`P2?^;{S2kp*ZL1xZkw6T|DsXYrN??`hWeTen$I} zj*sGd=YNLcjpLK-A+9kFtbg}C-To)UTg=b#mUQX(pZCn+eP6%$-?-mV^K_gr4#;l5 z@w$$AW%K^S&&Jct^W$jR!+pIZdzt@hN4Ux2;P6YFsCB1jJ1!{hiNE87{5n2D#gUo+ zAJw1W3~>zkIPWRz{bk~YDnjiD4qs5&$esO>Q^>yE$eeqwfcJqtZ_Wyd_50A86x!eEiukHS4a-Qc)`qP)1 z7l;QGcaC$XaRT>uJnpx3?ffDC{y!i39!F;$!Y_=Uv)lQ;u=L?T<3aHw`Rw@kHoxrn zKYG*bYW$wR_C7=NS@!I^-0~lfQ%}mlKJvfq{JHYseEgyEv3u=eT6L0$i&X-^Fw!6wlb=-K> z@oWBFJ1#$K57no7F5YkTrXCx&9L9$J)N{qtt(B zk8OXZt!uHJx}W2^@A|uR+s{0H@l2kF&6hpDzrNbp(fGeK{%D+}|GMku!PCu$cOT3Q98h$}EZ?|wP|r1$%j&L6Cckv?&h>!;Rltv<%(x4-kx{o23wvi6QRj(5Mt0Y~$D*O@&%?;L;DMaNZJzu&mT@uz=@|HM07=N{K2pZkBJ|3TRAw6pFb z-F@%*sDJtS{Ll3pS04W!_uD##_3w-O>v^R8)DJGMJ)K{wkNW>T7gFDCuzl*j()+&@ z_uzl!r*SZQd*5AltG>)@r5#7_+%S8b_`LeHalrA4XPlqRi3qf?Y#2s|A6d0-a6g!@A}RG-{axN!{RIQ7jKIj|uZD zts6AY*T0X`#T~@|<#*=!>?0kQGf%ayalGR2jCfZ(&wPH|Ebiqv^IqGlzmNOlC2@<{ zyZTgycTXBHnfN^Dhh0n#Q ztP94cymxNAkKcIz+|+gKPY?H#Ufinn!sC84UL7YK_ftT8yL{dC2e0+U`d#>&fBuVe;(_98)r0lF;{P0nXNv#h$9Nxq!vFNE(yPxY z?#JKq3--VRkIpWq9}$12zwp0<=PbX`PQ__DZ|ksUxAkM=fxT})`_SJzulEI654it7 zv_JO2>G_BC_+MZ7Z2hnJK>H=EsfJ@M@w5Z zt$lrSl@~YEuZiblPrT23C*Jq%6;Jf1SK4qUU+WiR~iFRpmWUwA2h z$2V{?$F&|6Kl|dEuN>WW{@A)hP0m zeMx%Od1gARDzmC=Y>ex1Yb-1y1OnMYwv0-NKnR4~ zLOri%efIZU6>IO`$+G*rxfJUmR>U25#ESTyJJybyq}GAb%16be$k*?p&~cVKk5OLs z!#$KU4j8|&{_6O+PWxp0orG~D{)LY;ufgxkZ{mK|$I`8@U)S5MKewMZ&V#Rh^{O|0 zj$g~a@e6()mx)tocgKAnD}FH!SR4~O;TdtiRK4~)Dqp?)jz8GX$!_BKvTMKJVV%IA z_zm^^c-`N6=zZVs;eXj%n!RyA^WXRQpMLTo|8t-H!k*jr0sVig=lk7j<%nzLSFZnu zk8-Ex=lk88+EY2SFF#O!>(F?hw00^UPdo8%+!hbVab52@-8a8D- zlYjHy{4M+Dr`8+Yf7kKCJO7hUyl6bJb}zm3N$Q+^^%~ zF3VqiJuj_&Donhi5(@y||OJ zzH{BydHQGVl8y&XjTg>qr}ym1Kjn86zu0ieBwFnIn^WOUzPX${hP*R zcEKYk``=alq`yej)4bC-!Jcuy#+#Ft@8OHegX`o^+PVIged_1)`}xCEIlAv|&&FfN zy}$4J%CFWA`k(7oj;Z!{eEvAy@o|Z%eqZ}epZ&Z3ss8hmc!zb8`>X@>AM4EW`R?2C z?>y9ZfgCsgtX`F`I4b3=zN=4uxqdJIuK!{k*ZbMJan$=udyQv}|M4H?n|+VgkJo

q2sn|zLDSN|_(2kk_69+$gczxTj&`5tYZuigB=RGf?P(EO@?^Q`f|{PS=p z_U$@$Jv^}bm(RHD;(Ln&EPl7~$N1~J_^vlTQsdTL@gC{J0gE^DT>Vl#>!12p{jcjA z*AIsrm#yEdpUl6f#!>e4Ja&Fne&;> z;U~{rvi4)|!{gOky84gj#v>eOAMM6orRyK1dp~Ua++q*NfYu;{D`<1D^DbyZ=|N z~zRqkiE1Azl0*KgF5qcgkseDBiFBxpeKIT>6*$ z`u^YUpDLGpR-W;!;#!qUe{Xz>(~aZFuj6rA{O?>RPRMw;-y!inir0SmjbEmJ=_*}3 z@YBl@)n9zy?1o!^<0{{D`+TS4epB-_ae&qxKY!_I$J#UgCytQ4{_NsX_0Kq({)xBi zuQ)Zu{k+HdN6KD)C)l{bPT4m;XSpj}H&D|G{f ze4om5<20#q9^TaNov?@F<9g;{)#Ep=|^3;6%h;#H-Ut9kHvK^kx22gP5i@8KHW8{(7X z6aUi=@5L#Zx0%;X&EJ~$b-neo`hN8hC;4-49G3mtPr5iv_p_(xq@~RpaXEfboF2dQ zyuba%_r(2~PyFUXzOhiTi(mb)Mtnr0;P*`4$gM$3?5(_@8|9*Q4fRtt<1_ z=DDpSJMR4RdT{GV?c03rdEZ&<)5?3#Py2d)>yUVX^sE2355IAzecy3;>m~kgope{_ zsh_0fw|skE=k=$aD_uFNzj9Q*c%1%y=aQ8>{^xmJKb|&@8An{c%7M39U$TSoi?+_w zPvajQKk3%zJ->C!c+A$_t5S?(aRhIH0&1`(&5uXIzxtI&=0iPB?znt1D;q#}(9H|Eyio<7fH% z+RgEv^Q`)3^To<@ct!QyzRi1iR<711_fGTG@q+P~Q=al4 zPkiQq&-{V?y*)p!-x{y-kMWIZoX`Bce(|i~cxs%uUw^kp*R5Y2J2}4V zy8q5G%GbE)y8HMht^JH=Q}rsnc;BAm{n`EL>Hp8|bjFp9r_bY^=V$-%>5bRZXa4v6 z{^4JT|H_A*sdY~I#{I05PrCKi=DF|jzqQ}ppVgON-&H?t{4f4b|0%urr04&4+}{`3 z_4)kn$DjDkDM#E-T0PGDvGnR~eeS&VxqgkqnOExPtrvdyQ29vT)%Dt=abo|6{N9z; zA4|)x^Uqw>db#Ju#acg?pL!ggSp1ywPGwxJZ1Zc&GN?iSzItI$UFX zBUP_B$+%_wFRmrO_}pLXCU z)A6n}E)%bF{W#yN%HSTiHLjDr*q0st>@DsJ7s6lsj-~yk#f$#sch&d(_~9oHPN-gZ z6+iL3DZf6P&2fD2#Ff>qr`;-#e7lcd;gLss&T0RhIdu|0VP@<6eFs-MCOc`^J^lKHq#C7oS+W z-P?KXq~48d#kG3=#`pN2c}4wZdVar1f5VggK2m!2{l@=L(&7Y_S3mWC`}(Q;U*rAS z?`^+yJT||I|HUnz`CoB>aqhjpwr-DGnV-e~`uzmFA+9&x_cyNe&%bdOzsLMrSNgN7 z-2abDwKtCP^($%<7x?+hs=xYJ|9|$;FFut2SnsFtBs>Byr18HgzuCUQ_jPejUDv$6 z{O;VZIJU(r#WCWB$}f%gjR)ct zbbsrdaX_3>JmbpW`@H?di-)?$1D^BMdmK>Q9xl6hz-Jwo+rGr5@wvFgiAT%7v)7Lw z}J{yP2F4>bmbRTZi`bv4-H+3BUJNhAy#WC)D^>DfE)9t%{%7N#J1N{6_ zafQ_SjhfF=^S#pXKkGAmZ@T==;~dxj;(trGPuRTIaq9%_s(onRzY`zzKV9kgpX0dS zYnpwI9cRxt8;;_7{N-rv%pQxY69?M!)0Jmx-Q@b>a;NODf0r&loS@^2OB|YJ6Ak=3lKN zI^O>gjQiq>o7ZkX@vDxDEebn}* z({=37JZ=2A^>BXWx_F85_1x!m-G}wR+uQx`r{gsFk$kmx`Om+{K@Rt*es^x8-jz>1 zogXJST0ZQSU6#Lk?)g*q|3&zpemI`+KL68i*x5L0UT1ux`mgzl_;&L$|FiNv4*wgXpuG6179`7`+@T2v!alfPWhxwi7;|_~w9rv3azdZe>{uU?H z4yDHv_2bh&$M1HX^<#b>_p?qgj#wYmf8qpNziaodUw>J@o<8%x?H5@6rg4+TF@7PQ z{V!(c`R#b}Gf!H3Ob@49{~gDD_4D`BEC1|%=YQ;Q+OhicL-m-xK7U-`RqIdMeLQdR zc;iXqfY0A+Tfft;t#9fl8)xqEk&QcXbmPr^96ICN_+rmfuKMx${-iW}r15_9fv(#) zQva~;pFQ^d#`Tl6&*ENZr*T@EeV@mDoG8DXp7GuFukWqBcXs^C*LdA^`M00ZTj!4ljK|4u@qN9g zwYU4UbI%{gzL&#!e9rT~^>+Q82WB_tsIYI-M&-# z;78+pQ{UgJ9pZrM9S`(-y~_K{?Z$1_KBu1B&-=`)<%ct=zvoZg7tf6A)qZ&Ir&s$Z zXUENp#G_5esiyKN|M*yb={fwf=b8VyZak>}gBw@0(`$U7c4$7F8lR*O|8sx8Ps|T} z|Izt)S?x1FKKw8HAMQ8)r~Qie`}m3wQr=IlxW8xBAL^I-#WVja-Yw2+-uvmbF4xc3 z|FbiHz)RzRzw$UQ-m~{X?GUGBkN9cYe6;7=FD<_xKl+bxL_gyH_&UG0{}*pQI{r8H zt0wy2r#D(2a-MLEOUP z_3ZbxzYfRy?Am|XadCZpcTe1(?||La{QvMj-@R*JrhQc2BVW0=x%bp(SG|2lkU#vV zt3Ki=sdZkzCxR#N4?IHuTwKwv0yxv(t%_T)ZT|9mmm5#<#dps$XZH z>A0!(Yo0JpI=*#JtAFjf`^@vIe_YCZh##4EQS+H+6@RK<{>{fc$A0$DAJ_lghbose zj-CFshnkzYSRcRc=Ry{bIZ+IN1$AF^Lu_@u34*=PKD zs=qr)Uo2n$xA;$2zy9jOAN}8```E?(=J(}O zyIKEMuDIVgpn22DPkrVu%cpXU&;NP9uY(twN4oy5+vlo&&F5Q}-`D5nSK6)lSL>Ip zOQy^!MWX zmjB`+&ibh5kN>s4G9Fd#xY5>0{I=t}&ieL4F46kxL(aGRUv=vi>zLR4y)S*|AiMTl z^U1CocWC{!b-DVh*Hk;*>v=d|yw5o5{Emx%@BS2@C_R2SJ0884+jye9uX@%4<9J=C z{;oed4w%M&Dxc?AZ_!uo=Xm8j<&xI#I-XsYrrHljX6Mwn7_ShIUOmQ1#zR`qRG;Q2 zT^IjTUg@n%Uv=$2zdD@raGT~o+pjo&IF2xm_^jg%`m_6|#=W?o#wPI~`qre15-<`+2{q$KIRshokEU^TYLz58o&G)sBzb#gD{GX~*$DJV{!7 zR_)t$?->?7p@(=0O z%^&J%|1)mH1@RC0jq~AI`9=J1>1o_9E)!qqx$N(`sq+0S{%3t99tl6f7jYb1B7T7L z;0VQyiQgLUnp*!Y?ibIgJU9V9gCEE*PJ!RW$9%s|dpU2P?a}PYkJ*)OA1~Dp4%fm- zPMSURpE#D|ai|Y94#l6{?>TqXugkak#{I_grq!eNjpMk^|F6^dq5X0E*zw}MDBi=~ z?9P6F`BLThrAxINweEJ@y1VNS54_iF{LgcgcifU6o;c3K?~c8m?Z|GfAJ=o8{C2!{ zJo)Gc>^AN%ZBv^6dZL#*ggY|HDhS&lgwo`@qh}VU?$L^8cLj@BH3t(_NpQ za*kidJ;z~v_w5%iKV!GQbmeQ^TD%{kQu*xHRt~(haYkA^nfBtp^*?FtiQ`Y%v;Nq1 z*1g5wic@s|t3NDGIc+>tuEkN}rj-Zhw7xD5uX{l)!$`AO|N*Z-#M{(n7w zw^=@Yuk*y;<`3)7{eFt}V!y@(^@U<0{LU(lgB$w2;jZsJqyKwv_|D_uf8&74C2mN+y7RxDgI9d|_&%RVZKvtI8#*Y^zLf9x~Pg@eQoid)00`W-Um z{rXjZX?{>X&l;zR-}#-{uRr3%yzg;9<>>x6W8BjF);?xj52wKKv_l-B_#^RKrNzc)`Z zU%&G}^H=jH>xHT3T0h>^`ReiP2l+#MME!7*+WW-E-S0c`c>0BQf986g>-urOqvLjQ zc=OBbQ$P3riPDanPw20oUi~&6UA!fG=GV%hz0`}E=U2{j*ICCpzH-iw@A0$U|NOh! z>&M#{ERM7JZ+v?k5dSm3#3AX{7oKPS=y}Z}w=Um$^USlI*Zw$)^;FlVyMJ*$);pdv z^}L>2Kl5Du$9?sqzT4>f5Bp)fM!j%q=g&Upeebb+jDzL7brH=^J%3!lb??RJSzlDn z!^_mO>p#rro}ce``agmDyT1OIowDPOKWq8+oH&BtN0rZb!_jA+Fnh6kc9|Ws2mi_* zseUOvHP7h$4<2e_3GRC_mw|a-_$%$da6A-KOVDwpRSxo>+hcHK6bsU@kaXS zGygLlI=}nXuj{juc9uTvJRK8 z!2Dj^o$J_rT06y=HvUxq*`ao1hkHG1&$V;y`P$C&%lRMm+;ODo)x`_JsNezmy1_qm^P_x$JU*v0YJ{Jr-oN4%Duq>ny7-}{^W%(wE(jgRTt zVR|1=Yp?A6YG2paF7NX{+^FX*?llfL?mfM?SI>)6IbS`W+tE1g_|!a;zj=>4Zv8{e z%exNGZl3%4|F-;W-1A3o^Qj*_=1u&?yby=!|Jm_8ysi1_cOJ@5r0GvC#gG5}!~cJL zX}=fpr`K`)f_`%O-Jd?*>%VcSe$sJqGS2hAyW%$Tv)(-_pKrfC?_1aNuJInSbCV+Tr;- zeCit~r1BdVo{k@OT|7rV_T$El@S~+Y@0*W&rZ|rC;|0&W@0CL??oUB*h&|8x4v(mw zN8^7uMO<*#O|9#S^YvVOWL$`y7I%jWy8pysb-y%Tc2xbIc^vyTPTaM2Xk1xbWaYR1 z*Dr9M_q2A>F4`-$*v}>ouzhjH1NHporR@BTH~lL& zRnA{}v>y(r9e?iPQOa`^2b4}1CzfVMyhZ!Hr{iA5?bWYlxA!!Ty6f_*IN!MF;?v@z z#U*NA@rka-|CVOo+Ee_d=NWhIYMiYchil#WUc67c#0$M|oiFa)xU>5@|33elU)rax ze2c%tw|?pJzf`%u^x%N59|w#xXP5EG`OEs($5(&C-(OYx7SFr!fqh(;jssh7YE??uA%z&9ZB}99g1(P9O7fu8%MWqyzgz&xF!zx<*T0mzqj8xiU0lO2k$Gc_P&1~ z4=mnqzl+}Qp6JiGq38EIK)!pJ{kvW{8xO|+;{0*Ic)s_n_l@~rTp;deol!cT=l@*N z#W~?uc;Dgzmu?;CI`2!`|C5gTf71TH6nDfSlrt5t_aCqN;$7|^KX_Jl?srCi?(usi zuJgMk*018|l%wzU6;~#WQ{jo@SojP6H|{nLv-m)&T=-^jca>+{ix%%!J>yaOgY+j? zKX|rl`$)~3mXCakr(C(z8`t6gm5<%WfABf;Z2ZyjcnUtFe-xj!r}|O$Y@Y&u&R@m_^HcsBm;2j~`O(K$`+xrMpWk|@d8{;l?>N2}um2C1UB#8S z-?&DNbIoh^-N42Dl~&%K_o~%byg=o~+tx4qiVtvc;J02f+U8nIQ^Sr5YHjmu;bnCq5b+CGv zuTJ$RY4y6R^OduHSln*^cj)-x+xPk%{23OIt4-{+C_LujkCJ%g^=Bzdrwb=Wy|BTkmWge)xgs@^kj&w^aMw z6>q+$XP;^D66$|AhwF`VY5Z>-aJ=ql?XO+c=hZ)OlT;Fp#Aw4eF3@$atcD}A)`t-ZfU*Pj*#x%Khk z6wkayKF#N!`QzaT;|kB^nZ3^X|2dwd^?dy!d#v8;-?R7Z@ZA5|)qO|fs*C^I{{xOb z^TWHpXixTd*7e8t`JZ;``u!gv|7S=3YaF=yv3^&2oO|3`JdSp3-95FRr2qGAKVkW5 zuku+x{USen?XM@zZrU$DTR(c{>4*DuTz~Gq+S&WY{98ZbAM+#q=skbwc=7t~v+l4? zOWhw2HXc;2*}wkAZ`pgQ{L)8H{W_li9Djf2(I4`pIFk88^(l?hN}JDAui}*OmwQ^d zrKg`<_38ZfBR=<|^;_?E*L_hxQ~vV#ko)a;_t!3q=QFSBcmGy)5v$Z>a>ix%l z_Bl-X+s0|!O4@vD>blb|8z1-H*n1>?WS!LY&&s}@j~{rSv7hVkkTn0$FYd?32lbnd zZ``kb$B+Nc!ybMwk$;IZxU2uWxS!U))=z!!T>avH#fiT$#5-^bLB0#>snJ)9jcY{x=RdE}Q<>M_iKrEKX_P!ARLBKm6q(xFSiLCjHmw|Y4jBJ?=B2eyT&w#%ul>c@ZQOV9YVo{Re~IH2 z7Z>+qN8dF(`syF%S3N&&H~x3m>figv^*y)ijo0Px|4KN<_+NfFK9;WD^-I@3e{auv zR(v0>R6V|O@z?Ti-|yWnmAmJ}>;LcazwDwues{S3#4r0j;ne%Oc1)eu57s`Xf2}<2 zx3^!uxKZEXR4<%Qe51HN@r_garKRuv(72<&>UW37H}3GS;!8ih?(_UOS+^yW&`%U*-3^v&Ch3j`vpkJ8``@6W*l#{4Vj-d$8Xv8UMq5a4qHg zPgi}O`Jemnz~T$z8hF-a_BSqLT_8O!^PFxT+VdAzm71sGJLa{WkGJgpX*@@NaGm)I zestIJ`}pct=l504@2o6;^XQ(3EBSToIH&)st5;flPn;A#YCmY@8?TCU$&cO5$M0Hs z?|im)__+uFW6wAizmc!!PER>pH*OS9GXHkoJoc`}8}*7$HJ{54vu~W(x>q@IVt)AX zn?Ks8ReJk=`J3m9^OLXr5#xaFkN@dE<%gF!UOXWF<$9dMar5uHnm4PjE`fc;Z6VKYbI^LqaOD~RU>-*;S`iu9s`kmjyksjyS z`sJwn)N^Y7E`3+^YrS%gSI+T2oV|WuJ&K=H-qnXL-i=?#Pk&1nm)m-sAND-!q^)aQ z-#TS{DXpJa|L8C3VO~%9b@e*y8|gS!>j>#M;5lwR*?sA_m-R;1r-yruhpnBq-mX65 zc~f?nJ<|5Y8wawN?~c}vcjdqAtQ>u}b-%yf{l+cVE7!A**LMADd&-x+r?damxY7C5 zCywGf7LJ=Y{Ve5=_x$-|*B^hnr}b-T%HE4hJN)m&+wk{S{x?3w-t~uP-T9->{BP^z zFH-fbT&=U~Z|v~QOuv4d{5y{0In}SYjpP44|C6h~D~J9x?fS+Aeo*~O z-=E)e8VAPxjz06j`}pBG8!sH!?-u{L{&2W+?at1%Z#w_$|8`EOoqd(N>yNgcI&pya^Zc{);&aFU zrqAuYaby0_@51%}&H6)j)Xw~G{BNp$^@rX|AGXilbJ{cRq}{|3Q0oe6ok7|AuH$~= zd&V*Cw(;!4^PV^EbiRv`U(5e*z1jWmy!rL>_-nq`^ViQ;zxt>5h<-}VyYLe8QT&AB zG5FsU=ZyD#@1g7^O%MMo?(dJTb;Dg_&!@t!|>l`anO9yi$c z{p36D*E;@ihVj1qp?TUi_bS5Etk?9{8-mzqIeg-SyLp!@7PP@Gr*y#sNQ6;{sl5T+qM2@~|h~)$f0> z-|SdF)qe5Z_q6x*_IcNTaXaGzp7(Q)ct(8hFJI}Ozvd~_?|k_EVv74sJ?E9j`@W+5 zal7hs_VIr8x*q?We&tHzets|5@qRz}XycCa#ec@djL+8Fc%JyVxLd!YDz2dO_+NbD zuD(}a960{hzQ)fV`Hla5|GKX@&GM1<-WJCme>vLkiGF@@(yw0}$9-SB_@3+ipN;x` zhd7ttBUbJ^|Kqp)4lMP4!J{Z1^q9 zko1m^_e|Nj>v14{61Pj0f4py6T;a#p`#e5`hqW&}JH(UXf9fgS?;EIh@r3P1u;2J= z4?AS%$~g{Iy{u!{d1^iuC&Rgv7x((gI_?!{YzO0r_9{KJ8?jbp6zLAZ;F#ea8W(?5TWf&y{n2%0BX+ zDmTBGx?g%KpL@FFmGf}F_Q!W!{8>9m?{{?YS@U4!Y(557x+!{ z>~XHGQ{w=e-@9MDoZk&^{jl%$J+E`sLwj@2`@9*~~0L-k8n z-|4v3;(m7(OaaXj|H?Uaulv?E>pJFgx3y>0W2?783HZl9F<_kRq2hr75=zwG+?@w5Hc z4o7?b%AuaM&-mlvDYfH$zgGRmapiU2^yD-CvN(|Ect-xiUSF*7Z~qTqe{rzpz2erb zGmHn+_YiE0?CyE(YiwMr{2PCsmH#Qn^v~me z^^?Z8`oa8h{O?)yhx~K?w(o)Er}}q(xZ}s48#l%sQ{%7WQ+BD}$HD6NwcCAM(NAZG z)@!w&dN<$SzVOnM8~Ki;$Z-gEIi>!bWL zUc}z=#R1dam(~~e^xm5rx2W^h!FOd>>AffUv-Ujv?{B=Njl-^MpR@nRc4rc+y3fD|N2T>*Z!-= z@$Wy>{zvIAU-tQzkK-x3N#haDPw|%0-H)@D-?ty?zJGgNKXsq-u5YetW7_ki#Jn=~S zXK`+K4%j|Z^KJP|s}DaA$Cy97$N%C|o`2_o^080U`^9seU%cWOAMWvq`bXmmp7P=I z_{TGUyQgs!`Qr%1p-JNf)9Mvxzz0<lzPxb$^w{}g(Dbv?+Y`kw==+txLWbs@p z_c+yi%5MD*czopS^R+%QUWl7(->=_qxch_W#tCsh@m^i;`+n|A<7e9Cng8KB;>E`Q z?8A&7ee}lR()m&4G0%znP5J9HAG>oh_UwG^?*8^2Yv;aC`1-v%JX3q7uRQSh$2h9@ zs(e%Jx%a@{$I{jny%)UqYUlg=M810u@jw0*Ut{;`v3R-r{$2IDf1fZOr~F@j)IFe+R@^8o4UpeK&zo)hLGylU?*Uq@Oc9w5kFnjeo zBja+#&BpCMzRKV4^Vrw?wW~gO-&e2u{m$`ckNO?{7k76(|99N)2H58-oZj`Y;};(k58G|n6)AZwu-}PRd#x3ptjC8gM zj(cwLYvTE(#~D9)@U6>DuKLO6uC9}&<0@10dDlSf(~)O=v&8qbT{ihrzJ{rGR~{rTlze*XlY_Fc2e z_00dwr>bvi-gkI(|Nrg2#Sw1*aD3bRw{mQMaP7~2j>qecF5Yiy->dfXeM$Df$FfU) z`^;P8emK4FKmLcS9lmt+51ib6cq|Thv^dSmw{lfp>mA39+nukS)W`FWu6^Qu^ZV)I z6pKS_9c%v9@7U-c-On$Z51;+@=5LGlOWi;ISA3R!)V!~Cs(hN~75^vy)&tYHz*)Ch z$JWofuJ8Kkm(uF_p5g?a^U7t^TY09=&u`PkMW$yRFb?$`-{^dHXq~UWNRJ!v$E`>1 z%5SSr>rUf_wEL+3mBwYP6S}_n@aD-|=X_Cqvk!Z?AD_JI;eK>&;3Wcf5LOm+CuR zz1hKgxU}oobNo;JO5>_=&eE;3W@rB5`20@!rH|g*>-d}Tq;j3_GF6_Hv*+U$_EK?*VGh?Cf~;-T2Xc+R<_OvJ-!zORrxjSAMqfEuH_lzVltT>yIwZZ~dYD zcGk!JA9H>xtskr(#j{U7Ka2luysSTFpX|JLp!w7J9hlYy<40RBjQ1|CbbM~>i`J{k z@BV4)M)RBQ-@abso9Fuf2sN%fYw@95_ggpCUi-ht`eCXb^{@GN{=9K?^_~B+U-_l^ zVe{Df<(~f>ZxnyfPrjJ{RjS!%EGzxWTo zslS!xKg-wgofq#{KJg^^>u*y$OM34|?Va6ckG>Cj{y(tsqj6#HLwfIz{G|ETGymfc z<9?K%-1(n!EglbFCP+kD%;XXA_SK^5QBy!XThHV$t8 z@M#y{LHg|SFXz{;cjYhA_zun`t$v5wjo*#GO<(z6ylyGY>M{&DxrsnsxH=Y{TGfw1RzL)QN zhxc(qIh+?i`CqR2r2f!%_3=N)#Ramvc)-$lqqx7jiu2h=+N<_I_MP4K-NE_6RmdD?OF@Y?k+!vEHu z>|Xrr`5l<}AHNlc+V3Z8C+YD&{kPxwz&RZkm&t#PM>t!*zfpgb&+LAU&YgA zfAhKhAK;nC_j}LU6aW2hkKf_YujTWNOXZ_J()?JQ9XsJ}IHdE%-%S_)N5$#ketwtZ zIkd#?hYle_p@G@RjR5J?{5sSHAxLSUJq2ivRO_$JKx8xwxfr z?Du<~`5umfmxwR;{IaY6Z&B~N6i=}Z`RfmEC!Wi=j`z{8UdJgONX?^ua;f>6w0TtD zmHqWg`<>{HfA4YLI->jj>RbA6zj498`_M0c^uIjv`_f1M@Gboh-pZ4TC=R zoMp$y|Mok(<8sgZ&%DU{9*?V>`#^cdS6NFujvmj)gIN?^SXZZj*qf)*K5zp=lOWp(fX0{pYQy|ot1Cx(|LaA zdi&Sar}O34cQ)I1Jb&UJtxJ!3K0Elo4?iq!MS14G^S`6}UAVs@P*oE zdT$^8A|5ub;yP*T(5ZGREgsi(`yS-t1fSQx*3HcWTd(R*&FlL;UHSE1FFx?Y^;tY) z$JwFzf4bknPUANFo$Q|b9PcMyQ~9UkOta5lRL4V)T~^OKf6|_dm#|)KomqVsr(k`R zzf%7Xa2}_l)(3Yrf0drLPU3H^%X*%4>o#_CJswj&J}TAf z^39&{G~J-~W8}%e#NNZsSeL{;p@I{4{@8&hpv! znHGP&+T$yZV-%pT`~f4f}oQpY!k3xL{t2_qWa|p4I;uI^H_e z{|BVwRmPR>+jY}@uaSEGxYc;oz5msYwfFo&J>54w+e|-Ia#(VahUH@Vl ze`bfqQT)&QMV!%;f9yM4~mlbz|$m_P@ICng6k0>)+}7JWIZ{4>hju{~vem_u+WC|8E#y z+&`V4&X49-drt9dzArOA7Z0#5sl1B|Y+a9IsrPi(X}9d0%3peFzEXbUe}|`b-C4Jl z&)V&M{`Z<6zwN%Y^WovyBY)>Vcl*pvLt``{4$j zLmOwFb@{Qs^RMr-xKRD#^?d#9i}|1PjYIjra+q&StH&9?>sP%m_?!2F^8Mse?RQ`2 zc;Alm72nr)_xJ&>cJzA>uBZP0>N<{#Q2gUxT*|J~KX|0S`_b=TDo%^~PSroZDK7DQ zkMy@5>N(O=@kamr(JtMO`<36f-ty}>4(Pe+S9w;hU%hx_^~D4A^QrF#vcvW-|H<2P zvdg#L)_dQ4%&YN%=JWe*RPmGAd3L2ZC%cP#q-%ew-}irjqtEO8@waCc?<0Q9xYc?& z#RdHS?os}$e@}}y>wNKsJ#Y8#Iesrwzdmt)UB{m5_i;t_tv{}x7x#xl)Zd@S8SS{^ zhxf!uj5oOL(fXgX=XCwX(x#tt$zLA0Qb^w*{S}E`>}g^uG?|H6XHCL|4k1EEFSRiKZa;ucKgUb zzS42e_w?{6<;o7P_NraI$KsFnsq!;%i1%`w?-1H2JPtUGgR;ANQvEmoJ^v5l5Bh1k z_jGC=pnv$?NcmeI=Qn%5dymhr;&u63?>lzR-{Md4KjrDWiMZS0eboHNYaR0MFME&sSw|Sp zeg8I&_ZyG*pLs>c<9f>9`5#`Izern$ON*cA_}{zk=eK|Vp zi@$eM_xT-I`Nsnn-?x3L)>FM_rt!`=D1Z9RM}CKw-1*%&-_(9(`=`a7;fx(uF6%97 zeL>BiD%ZFl)vv^njsF$DhVPg^DDWBpz@uJ$b{oC62 zCy)Go>(bV%(&oJ#UtH#IKGN)0y%zVkdd9)bn>|l^_uR^_9^T)M_dfrkb+z?*-`kr$ z*EjAL_qyEv&CXNnkjl5;{oTG_91u_0KJ~bu@vY)-b>KYDOk{U{zgd+=lBpPJuFt2aNh z-mX1xjpF#?dBt7w-_B3tecQjj_I%|k{J?tEbMLAjw2oce)^psP_A{?L+WJ*{cyH^c zz0XT8j>>a7{RW`TvFTDJMHjji1u5svI59Pt_+s9G`yXf8$Wa1F{!Br9In! z7Vq<1>-2NH>vp|z#0fp${FZvI|Kr`&I9>TpeVkX1$~n%L8c#Z(nn!ls;&Zl6KU}c+ zb?bljlAf}A=ildl`JZz4JniCn#-Z*TKb$Vk?|tPr-IrZv=h^+0``xdvo@>YKxp8ZD zoQ?y|KmI(O-<*Cmu2;N_bzS|YwDo!YWY;ZT#(38M!?M%(U*$fWYx}CRyLPZ%FwRYz z*N^|%@7wri{w@AH?YnX8;ClW+^|RIi&uTpDcDJAQ z`x!@?@{i^d#!LSf%nsFGIko>6srGyJt8uIBr5!ro_vyAy*B+I(_4)P-PR-BN6Zdpo z@k{D;kJs)!ApdcJ)!YAB?sk}6UbXe!xqshBo9Z|6(T~dSng4CvXnZ;SY<{!;IQ2aC zebtQ%JFY&pL*vBaxxSeD^}cey@yY$^j>q-nv-e&7BQA~)HE#D^I?s`I+&s*EY4dLW zV19JpM`PZkAGfX%|Db(-{1(sGclvM)+>7F1*7bjQT_@fuPWGLj>c6_qTj&3aC;i?> zfAC0u@4?@2kl(-j_LIxsaXNe)-}8R||6YoB{q9ZizTdgh*4^(Z4&ZpI{NK6K@st1K zI*$KQ@lljNcKlc0p7+ByzW9ST{n1-_fB4{n`n!73>ifgDxWQk$wCAyp=f?-X`LLhz z_Fcj6JXHT-XYJj(sd>Eli+19_^vsLm#QN2Ld2kB;6@T+y#M^Kj`x=X-tPweVB> z<>G)x@jv65c(S-j93c+qIIfbquKm5Q{BOsrw|+Jr^CACv=KYNm`HB1Pys!Rx;tv~- zt^13YlJ@*9Y?6}ZPAF79wDuFO8=X>pG75%-wi zX_x2sPJR-{TRf)rbR3sCTKp3K`pV<|UOVA~-rL9T8bA1z@q`*r@TX_~mwm;@iCe_G z*!yVh8Mku0cBAa3T*afl^1pFFcF{klwS%;A|G!-v?(2{F1P;g#$LH(+|Luc#y79JW zJ>TQ|g{vO;u|p>kN+93alfO@2c@kq zQolnlOnB&-pWnIv^2Gt^ryu>l zFU3!ALGu>8Q2yct>EC)g{&(Kef8$BxSNy;DK%C_{{_!^-@0<8%_4xeC*F2bx3yl+P z-}KaXnOt{tzmG!eH{*a^hd+5Q;!@2|rNt4X<7;=0c*brsR!HLzAAF@ka`ZcZG*+V{EFTT%psrj>Xn%&32sP9{PF8}sieq2487wRXacRbzk zalrAq@xb;go4*z3hYy#}xLm}?y0x?s(+Bhl7lV6vub?U+bg(U*3DadTpOg>nZcWj>rAR?ev@My?l%R z+HVtRCyWf>Q{7+gwRKDrPgYlm1ss8u#C;dFW*auO*)9zpUc;2&pN@vI3 zhj)A4ub+Q>sOCNW-{h75>Hn^uj{A)VvRBVrzZ}OOAB}gZFMI0`ui83cab)o~e$za@ zxIgm(Y5k?+`~KhJ$i|b#snT)9srq@|l-)}2J8Uaw<>o*06KWj1>xcgKv;D#Iw6A_m z?QfBv`6yMtXN~`{v*X1b)gE1U=XZ|B1*g`VuA8p>UzE?zPrV=TjPw1$t+Tg|e%{}E z*74TWjsNyFef4U0>!7b)p#~$^FRH9-L)t6eC@LK(yqOS z?s1~V&-_gN>Zf$;`)9S^Zv4;l@QhSG?co1`zwg<_G2@Hf-~Qm@m0rt}A2dG4|BRo~#;^MIv+jGDAHR)n{Lyo!c%5`= z9^H8S{`vene&_!)U%AE`@1gc{FQ3Y>|D!C9v*+UHuA|0@_U~Gke)CFOzy6h z%lUuTm#_1^2fzL1AK!YY{^s~pJ2YMuALzK}Xm7tKvN%B8O}X0-?6^3*xLZ6KU;Fs7 z6aQFz*?7}*$EQ8Vefd|stM-@Q;f&jd9RI6a#_>4e)P7I*eR`F{e%4*50dd3Xeb@d^ zW!&^0iL>&5-`P9duk{kXZM}4k=dZ;Fwoll&!@rC}`B{D!uhWj=B;BXKeC>MgNPqnr z*V?z-zS*x_=ly=ke*f5g_A}Gs36I|MA7`CzAMn(1@5fKC`k8l#yTZ{t2UpWB`hVBm z&i%AoX}rLB^MNV;=lesr z9gcD5eCC6V-_Pp3>A3l0*ZG8OFz5H`S&lr=lJ;F|MN=gA5=bg zAb)LN@Zo;(Ki>~jUcVbcaWLvTb!l8o+|}og2v#zo9P$ME7!BCZ+5HP z&s{UXdGl|_z><}y*oc180TG_)hE|`#d+)aX`Bczu^tf@sQ-*N z!~u;jy|?iZ_22IWKl6#L|BuEEv@_24(e?bJ`oZCW<$u=m)(`sIvp(0?dG*jg?y9`f z%0c-}y7V+VC|}oa-4aK;&u=T=I9;3t=X2cmve;#DdhG0Y>!PEt@qfF2svJEhexTi2 zkHr^pdg-I%4dZ`{1MGJ@#&yLhvSYmWsCj7h&Tq_rv(x^+U;kIG#(`H3fA?qeKk2D* zF8+7izw70vKd9fmU#x#?xB6k@k#X#v)^93Ly7rx)Pd%q~=yY7C{qNoz*(HD0&$It@ z{vVHi<$=qpDC^6=Nn8MibZRIcaa+THP~_UpdzQ#$N%!5 zt?%<6c9~zb4p{uzGw+jM*X?+U7d`vo@{9M3>#&FG^w08nJ^##q_Wy;&85@^-&h(iZ z;=S4b{=GfpWcJ08od440KiOsDT6X3)?8o2I`p@y3?8^?>d2xTmHR1Zk%g^50fn7X@ z-}k)3XIn>&+r(Y9qvQJJ+M)Hwz9)CS7uo!K-0xZ0*?D$$zjXP;0sUTf>yGij^7q`X zFU=3{_v;UpYub8q{B6HuWM1sL?LVEK_dxCb+JEwk`b&QD%Ka9HI{$p;r8q?8OULo1 z<9<`?%dSs%-PCyR{B+01|I#>@>#VofYwG&!m%hf=xZk?+)5|~TS1-Sd|2?-iyU1TV zR-W1Ax&G_N=1=vLKac;7@9n!3(yc$cf5&^zc^~lOFXDb3H{Rkn?FzQwP#pNSu~uXS;N?T^Jn{>3BT@4fAt{r+2= z+;@Jezki*_HGc1=_#w_lfA>=L|J`d|^yy{a|KqZg_`f*a4^#g zBmKQgivv6A{5K!xt;1bs-AS!Osr>HBE?xJlAN{k(bw7BNgT0l9jti=f{#Lzy<55rc z`h)8@|M-`W>%aBb-|YGS`tiJPJ@}yCW3?|@`6+*9Xa4#pkK^BeQ~SkSmnvWH;q5or z|3~6QaUAu-+pH_~i|xn7Tdd#JqwnS6H`286ZrrT>obtm7*xP!#-xJ8L#s68y$EWnG zcucAvt^YssKjqu^N>lZ!|A|M_F2;-Ujbj$i_{n9*j^jPb6NgIKuYI3W`8Gb_jGsMz zr&0bJPd~oe)BhLjkDxee=i_kvvGmIOJYKDS&nh3+)z6Qz+wx6c`J#P|>W6pWeK^)# zak1v}zjTcg?EF`5nqM0~_;>o<57hnpK2Ds`^~y7QPw_O|@2>2P1G2yC*jqW`zOOtG zXEyGpyWac_$9?vfKcD}_kCaD0KHP8oFMG*n{O>#`uH1e3zvt)Q_W9z(i|=bZD$dV) ze>{+#@H6c=t{ngK{&JijeAr)%XZqFGuJ@09%U`|bFZiDLO5ewu@|V72n0n6Q3F*pf zovR$5UHSH1yyEBB1=kY~Sbycu((%o4zv7<{_Z$D~JAb&Gej$J3dU1Ef-|5GF=TCjc z-S*wR+5!K=W8L3(9LEEd&vEUDgW{g@X+N;`jL+hM`t8qOeyZP&|NX+l?$Yi5^<4Iz zDv$9<{9of&{Ewe)e`g%fJoYD#_UiXIwy)QG*mye?Ulz~%n{V&QzxEiH&D)IA)^_3Gw+S_zVbi) z%JYm*uAjf`xN@z$aWV77*2k^W)mt2&IN{=Y;vM6G@uuwjysoy+_MENr`&|_M@AIo2 ziUaKb5dA(0?%8(rqIpZl?|iXxbU*I5=g2n>I4+ougHHKr zb{Q|gz13HI+r8f73$x=?dv+bp>;GMNuy|SDVdS@Wj?E9}Uu&QIb(~{rUZ!5>xhu~- zel0t;Pd%<#JXQNn7awI_y>{KcO8ute&+&oY7x_cn$9U$tXKkL_diQmGj7Q{$z0W`7 ze~xR<&Tkz|{Xfn6cv}5jXMTFW&;6|GSpcq~p79+%G$M zU-g{vzt{aviwjKScG*k$rLCjT5%{IzfEwXS!( z=V!;#{6zcooa`AF#Ob8{znMLz);-dc-|N43)h^OU$MeVWp8NZ2|DWH#>ggAU@7M44 z|A?Nu{&MtrA3Z;+eNVgAp4C_TmmXK{`;y)x*?Zh?I!+h=b3eP^)qTd}wCjxn(o_B@ zJx(}Xd8V$bos_Tfx%B$M;eC#eOHuhx*`R&wuN;#$J+JTnObKD<0_q^Hr@U?qB<;U;G|B4IsyzH5d|DCwe_#eAu z-{&D?y{mgoiHlH8&JG`%T^5Vyy z`5ily@7j0I>-f%3+1>Tye*9E=$}TG>9rxR~XC0!R#?f^CvHk0{tNdmU${uunG`;(0 z`OPmYhv!tD@yFJ&<9E;NVC8DPOnZL3OS|^`@v-#Oqx#7AejiTa`O`gjdViklUen_a zTi4GIrtDDu@jv~peD3XV{0om&zO~0|`Crq@-Sx$BS?}maQ{|I(A3v9-%3J!3N5)<2 zK#F5Ee%s$`p49JAxX=1Te$)MaE%jb#-)_IJA&pZ_jc>S=@y%bV{y%=Cy|;evk$?P7 z`~U7Eo#GJEQ|IwK>qtD!`t+YY(%*m6?>!U;``@qgIRALxKYd*Hy^sFMlYZxsWd|!{&k-I!Q;O8AN&2w$MJ7o z_GB*{@YCz7_&<2W1%BmP*WdY{@@MBCJle_g|K#!9;xCPxt>=p0JpQonpz2R?9sU|` zi}x+=2e+}m_wYaU!vEga!!tTB{mdh*m#pW-OW-l3r}d*d2h$$wM{%`R9;RK~R~%#c zibIn>4k-RDUgtY;)|?UQd`z3+c{+;3f8zpfnoymaGBJgoaF z&vSXtc=P=Kjo0yS_1pEY>0MuYeSGyP`K5R6Hx3y8>w9tk`C6Z;ulc?6@j&UgnsG$F zclA8u&(V#)@9{t1htsap*Z9A2z3JloibsnZ;(zXI-#9*VxZnImdBy9c>fi5^s26|e z{?z>|M?A@K_3wQ9mvJWThX2JiQ!zCXFH`|RR+%7JV7zuTu52a*2L6-QAy|Hp@p1L7ssFAg}4 zImMyuC&v5iFaGKy-Fnr1#^>(;(VPC-gNJ$F|Kw5MefKaOH=TC>^8574-|wXqmnGlr zt2Q5%epTi4oTJaYZ`|*w^Y{?H`RQdZ{BLRb#D%Q)%a9jjnho=F8jqlf8@LPojb3~zwZ3c{uI}b z11L}F=liX19M>Q2=g)odLhF>S>wfj=`qX*zP3u1P(2r=x^QVsAIjQHCmS5L*KmT01 z`s0A?@ErH4e^!oHuJ3oYwZpi`$~}FJR~(;8*`x1Mievor`gL>rjz7CbZSjfX82e73 zIG5UW?flC9;(gxx`N8x5<-ISuzxlg$UGx0b$?PYsou;h|T7UODtlC++^@#J@zxO>J z(R=G??cMq3b-a4_{116fr<}EUwZAf_B@)s^*h&_XFcowk9}Y7@au7d*YE3{ z>#E0DFG+h(smIn$)@Q|6&aQEWPael-zhjr#Z;Io{*Y#8RJHEJ0+z9tO>8{T{`GNbZ zckQm6{CwOm^}f$mI2`St1NufOke_6_MD>|Hfxa7R{)6e=21G}95 z?R@<@KhxjMpOwG<;yLsG`AIrInI9YP+3$<=aJ})S@xXNXe36bX?fmO=yuUr)`#V2* z?*F@QYCLouJ9hp0>C(^Vi%XS%d=Qs@<^zYPI4=LYdd_pY>-F=F$9J?_>BHxw^|SiH zINY6&RS)MqH+{D6xam~8cHR0x+)%qaK5ZOoym#C@AbVvW{wh74T|d<9yMAnb?LOn> z-Tpg&>aqUW|3_vY?cMrqab2zZ_;>5Q!~3iYwEMHh_t@2Oe$)D4@qUXFOW8}l?9p>m zeU;PmN^jro@@;*}F4}wQJ(EAoPo}T?=Huy}d%s>g=0DH=r@gwaa_~>( zI$C*NIoo^b@?SZh%YW*zxY<;@yKm>m{qT~?@%sG56HTAbZ{OZ@?R2zwAoE@MkGJZ_ zwa2(;cH-xiZydklctdtO`+2*r{dek7|9R$r?(4Ym#W>r0>-3Yo7x(|h=lF4UYW~#k zaY(n0`QAhIo7OG;j;;3fy*|&u{iLb(O@Gy3eWmZ}`X4=x%m4S@+UIw#e5}KM_exuL zQ}H(Ref}4(`e%>x-+kk4_+MNw?pM4Y|Nf_s>z?@^Kl{gz;&LYz4&Lk-x=Qj3%~Q$-r@k`4*cx!o%q!FQanNXeKGg@Kd<}k z*Tx;D@{4=i_aka=>wN3kah5op@1N-}>#yV9`@h)s(W-CparG-atA0ig2P*Dw{BLT0 z`(kkz@vHW# zzQ(g>JNmAl_&eYG^ZO9eA73ky>EV7V@IL?3ZpM?NjXU~{G;j|{}wO#$+eO! zKWe@Ii#N@W@lC&*f$J4FD4+AYBIAMbu^;zn{IB@PIAHsd`G@K6yZ$)wZbnD9UQ)6`o$jPv}QTEBF>cysHRpFE!5?|iBM;fKa| z@1xJIQL5iX#?#&J|8|reyZ$+@(!R~g)p6e;msSsPc>C_&;ec^L*Wq;bgNpO}(xY8{ zKT^F*AN3wkF4udWe$F0?|7)M9`dK$p@phhX-~aRRrN@!tS07*XY#pC&Jv_CZa9+H_ zf4KbfmoIMB{LJruDc7Cv*{>=8qssC5Te;Geqw;!=avsHN)#pcV8n-ona9nvhZ{44t z%GdQ&zdu^PIQxvdzv~wd7?)Um$N#40$LjmZo1Mn}rsGCO#N%BS>>}h&i`=vlkd>reqVcBU%#n7dAi2Prc{6J~eMF z-8|j6Te^8XyWvDr?G-l~2W(q7XH#Pr?AB_*i!`MN7`@i;-y(;Iknm6uv>!rT?XI|s@RKC*7Pq|9Zj^m51 zx9m5H6_-5_5_`dh~-{RBeKkVtg`Qv!h@vHeq{SG&1-n}@c@r-!E;Rc7V zSZ`?W)*Xv0ip%IZM`>M0|`ups?`}n2jP0f#be)drx^ZldabkkSf_nbCvwSL_3XCCPM zbN;O>4+m`BsQ#{d<$tGKE9c5}_@DOH-)i^x8GGE*>{Pn;SUcdA+2ffDpMEw@nC?0A z!>RI@|1-}r&N@DQUQgCv?&ZW2y1sR(a@T(QU5omS_I2IrIdwfduD&>)>;59@KJVqO zPu0)y>Dp=Pxt-rSzUQCv%r4VYe)ZzdceU=SJ-+kSA5!y##-)uT)5cTnVth5uO?$64 zfAAdRIlEBhYn|}@N1U1CfAlEN58i&KB4y`z)AR3K$S-~s_j8>;`QFufOq`x|G{ygp zD$h6GxY;)!iU-EgzI~~A+z%dH51)wdrR;H!^Yh%L<9%^IeizR>`oBHu`Mr-n; zzyG*?zhm4!Y4!Yr>$vyJzkJKD?+J<Y~( zagNmU;(zM@OOJkc4R&?IeBlc|6!SHf3kmYmf4I9tYUn@zuZhz2e^--}&jd z6aE@k-2LpP|A=E_KX&-^danB7TIxT=Z|wgq?(Jyz`yQaU%*L7izu@_eLwD70H$N$U z)PCN>%RCP!JG||czxADm@uYFODMPD|^=xsP#rajg>ObDwbg99 zo;X1M8vpZND$b3+sMl$a#w+D|j{hq@c5$*NF0l5+#q1Nt%kT~7wPXD6^eg=$&ThQK z@%VxI7w>nt-_phZ#T(D>A0PhLcM?y&d+zw(e&3_t&-jr4jr+yr+J9?5bo+ddY9|~J zm&E^`;{kEL&#w1R+|GAR?9;{9$M1^6`>&VZ7I)b`V0?J-fN{U}|5i>MQ2QO#zWG_d z^NT;*5C31U=i!}49T(^4I`$p^`}wO}>c_sgUL3G^xwx5mTk&-5<25f^9N*M9i<>>` zuf4rTr@#7^rpBcoU5elS_)^dPjYryh`;RWa!2MkJbB}!SX?(HtA7A%<_2L>wJ^$Ap z<)XdM|LUd1eJTGqB|cdF@Jsjk&S2#~8qX>1yM)gF@a?`IJ@l3Tl^z!?&Lw_WJo=Zf zap+G!`Gu=hva8>d#v#9YwU_*@SE%(QzPC8U@ju^pi_gUmJMVoPzZB;cCyZn6{*?c_ z@0I)M5AOGV7-y8v_+Q%h0L6t$x9=B^Gk=OB(ebxw>v8Sz`E}i$mo*=I=0e(i$3MS# z_qQ*!K*5~o7qo+LVsC?}Do|?xxK9zs*567kN14c zhdaM=KI`gvIKk@u%nM$x8#j8@@edq;efoWx+B3T?{;zt-xAM{K=Q_vl`bFID9FNzI zSB+ziXT2&vh=WYyBJAb3`P^O2C-R3BHxlplwX0qK<0tk}?{|pD{hs*=`~IiP-+foJ z_<%TvdN$u1cbIN{-uhd4TZfNtEzWQ}W!&#s)o1IDyJ|P-SGz2|_MY;~>@iM+`x%$Y z9~Y^7;|A|@zr$a)ZruMfpRXS$m}bBHqUVfD(72uB#y$GUi<;MWU%XN}dz5yc^tj;8 zr>CAc20J|SKYq(TAM!urbbkNJ|N36I`D*81wf^im`p3qF^=I!#$7%iKSvStD{n)W` zFMcuYxcap|^_={oec#?s(s2&pM9x>gV&5`ThLqtdBiMen;bf(#B7^a!rl* zT|YhXnvUzgwg2>)FKc(_r|e?ht-UG#p5hSNL3-*wX?~Q(v-BrvFRwn`;McHtF^y&`)>I`>$?5!ZE;`h5%=r+ea4N}dC$Dh_}BgCzSbGf98f>1Jg>a% za7yRd|E}y)x^-&n=y*i+Jv^y&?XCYw^N)_tA71s9|Gv+Am*4zZ`jUpemn>AW<1eX%~T_h;XuaYy;fhu=+W=jZsnm1F(; zwS4^aZio4;dR70!{~C|R`3@&<+}Zo)yqAr`^6P#2{kL)aJ3m$H1$K`6rR;+DP1#kN z;(f|R?`c;%?$3JPpSY6rI}e_RL*aVkd)9ApK>W|TCl0vt*6-thxS!)`{130d`##je z{cu3|g{4c+8)n9(%fBftZuJi0p*&F|(<9=zsBaD-@eoNWgyg~d8zhd9|Tl^27;>Ud# zi{Fg%edCSqedDA5ew|m&Dek9TsQl~~?0aLzpT2{p-tmp%>^$f2z{+30iJN(^;VypH z1?RH=&-pkK{nn$LQ#?<(-_yp~JNN6l`|;;^Lg)8?lKy|fPs(3^*WPy?R(m+F9r|u( zPi<^6&`>7}XrrvSC#pf*!P5Z`a^h2EXXnfW@ zSKOv@;eJ!~#_y(aROOldjU(D2^?Ye|!HZ|N_KUj?htq!Zr}{zt+V%QN?Vw&gSAE*Y z8b4OA^Sjsl`_pT^h6C=qn#CF7cX6(1oO)c(bE^0FbiV`adEz|TA^Yq;>pcBx<*47r z8}Hv+9RI`3#M9jspOk)I&3~Lv+kY7UGw+E5>ZjHp#eq_Bd*(NBKfKTQfVi}_jn&w1Q6zr^=&bo+U=ulPOwxbNHA zkIO$&^CfBeM~~yb_4qyp4)}*x+C1*A#t-R~9eqz@8vpylhyC!vc;6pg_5Je2`Pv68 zj~Yue9~nUCmde&6m^e z>wfEB@qPSk`=p=0Kl{lwemn2_uKO!*`TWX5<9~iv?z>modt&j4aX9;^-FH;npZ9?H zJ#l}|cVE|49_>~-9vBzYpKw0B^>5!)|0)i0yl}j+I7rWLU$J)o$yFZn?t9$d_#eA} zew}|+?c(^>$FzA^@oUaYn^)4U-}OWHP0e4*XL{#Y+OPHbwDKCi;(z0TQ}a*tF)yuN zxLsV~Lml_?y+qv8b;Wz~=kDKr+Ejfi|MV{&ACw)k)9f?8#^0R3>*0Rt^P6vWiu>{F z?3R6MKX!iRe`~kXUd1`#0^MKypZqJ|Gyl7n$N9sxs>j-W^;vscFLix<#=I`O-Q)k_ zLB$*9FWS+4c#L`fE5Fe0|MBv7zx#}v;nhc7A5YVceqV%raV=b_^~URZeVlE4?^*e6 z>yr2idq{tgU1pD0oqc8(c9M^BmS6dM-o2dcRywu*RUi9%95*j`Pj}yV;#4`hKJKX; z<)0eYI)9E=&Xu=ynEvIsb>Cgb|NMWu-acL{6={@{>*po$M4V6@1)lcKKZHN=kM(1yz#R8qP!eFV^S& zyn0X9|CToY>v`!H_3s^5?(C4Awr`o5_iJbKYIbRz@!L=O%K!LT^YHucb~NvD+<01k z+aH>0r~C1~C!ak#Ui_x=w%&{fiZd;}c+Tz19oHQ6z_l;{GzIVTF*UzulzUCG0`O|AZ+5N7U@07pvy^HmS)pO-+ zeeQa8eU0~1j_jT4-_o8>`Bmw~H5RXU_(bbT@1eULj$Jw~ALYbJTvwVuR{#0$)c9>Y zkM&|-}t=m`+fH@FSZ_!_kHK5YW>0v|N2t>mrDP^P4zcv`a72@2URXSPQFxq z@iuAtn%;4o!}+7X^2YH}>u~u^T_-)gKd*SdI3WAS1MSaseac_)x~cY!=cU?T`sgzk zw4VImu5k|E`$s?3_`pAYOZU9*yghg2$u8EZ)o1&J#Y3v!;sbyAVNdJR-+3JWD{tQu z{N+b{pmp=_KHi((dHY?Fqw(19K7LPyz5m6dp5J)mwZHNfmy+Tj)<^8fU)Z@$Sn1?)=a5cYgbv)A-Qp#?cw+qZng4mNeb3X{{Xbvj^?gme^s8698GmtaT00&;wEt9ni^nXV zxRHIN^@F4F!V~wm^W%l_NY^VDZrJxJ$NSpXD}VcY*;P3Y_q}d=aKP%(bK-pXaQ(J; zL%eys6(2NS)4sE~cuf1Ci_c3JA2>d!9QdDdZhwQgM(x;sXYqizXj=Y<`^twOr}&@v z%%fk#|6E@jXX6DwHcnK&!xwQz&*$Iznf=DNAik)-Exz!m?NSlBxHV{k})Dd+EL} zXr3yawhvUi-=~lJ^egb=$UA6@O`_obB^ zCpCY@IrZoB{QN5ZIsRC@pLtW|J{%C2!@1RqUsu29ctCbIJRmzXA89?U9Ma=R6I8OH!zo}f6`|#898~0nB)AliscRcHO$oPo$;m@k~=I3#e<`1s- z-swIZu=kJhSRXiU{BGVh4j2!`L$ceQQ?~!varJGz5En6@iAz{V)UHPxr<~t)TW=_@ za3y}AU7q#6A76i~ zUrw!q`1#R|D_^8tuf2^o{@*jr5C8A+KmJpDFAlJJ@t6E#zmqh+UfTa*ocDj2?%(ly zyx#He+xL>~W zuj%}YefY7s*ZgsuAYB~b;{J?_=CAB_*X{3|s*m&L0e64b&r0X_J-_k0=Rfm5_U!uc zyJzmlf1HnJG>*mPcirNf){me2+wAeG)>W0~eg4P(&QIC7`liOq(&K37_cg5F{2#D& z;BP3AS}IR47{^l$4?-~ViV7|+vg((b#f{Coa5;A_0!%Kgm$v{&_N z9b=v){i^KJb>m{=eDS}-{W?DXQm^hCe_q_^@)@_P-PitjcYc!UC$(R?cA6UBYQOid z+xhpj`Yx_<_86zE-0pMTRDY{p?<@bc9v-JF&938s+dnx@QF?Y)-}0Zv|CZ0I?tMlZ zzsCKhhyOJm9o}brW=HcqYMyPqNAa=NEB&6V^-*zsKYIJV+|l2A-1oz`eX0H4hJJ^y zsTcJ=jjMh4p{3cWeYDcJ+SK!1FAfkdn_3^1@3()d|MWWVIK^k~Y4?>LUwhpT{DVjS z?Cv@G1=Y^fc%mFffAp6A(HjSh|KUBZ!-M|O)&AxcM>~G_U*~&H-xn+{&~y4u;L&l) zRQ!wjOvS%Q(>S3x$?WjY9>>4=7Ek!ix8F(m)>}Mg>OSpiAD!<=;R65eO8-UqANyM0 zQ~XamO#k~ej^RJk_~7|YAkL>>-PJlqy7l|fXAXF{8vklMOg+Ex@MrPA^ZmQNhbJBh zFN%}I4RHtMzsHYNzs7gRm2dqyRZjQ$j@41~YyWQDvHRBNRX%+PU{jTnEpJ|J?bXd3yVOaX;Vx`_dH|^q(*8;rAi%E&GC{#igC!0b!5#_@8$B z=5<~6p!(go;NgAOiAQ@(aU|vTI}Pd`PdfbXnb)cp|6r#nf31DB5BtBjpL_MqZsNs0 zedM#azr`n3zsf5=54!We+8_7BBh=6D0NvF%uN=l@+V=ue?bm+gY56_J1s4COeD<4u z_45Ct@xPM~URJ!@cvrk{+)p|2RnKwVt5)B;e;9Z0L+c#c_xIeVUn{ro;dw63AGftX z_I#HQCyckn{p@onPNaU)cS=6K{9k$6ciZm+$3^*b9FQNVm-b>u{wSXFXmNN;pX+yD z-;2bR>wlkK^(wBg_~3pY1n=|SIo$7y_+QUI@qckY{Osdvelz`dSNY9@{^&B7c^}39 z@H_M8yP9uHTc_ZE;%)xzPqp>+zkS&6$Jgi_?F<9Gk- zrSkm;Z}SVkN8-M|Kggb?<9y~1@yFEs=FTJIfBNJ9^x%K{y%Jmw58Qrb_K}`ypVI9w z#$n8VrhZQZx5S11^kEObhs-Yf-R9yC_j@Uo!~OOX$0Oor_+Q^|?0E5w<`vGTUH_9u zI=d3?N-h>WaUvl@6|Y9S~;9op7MRp zZ}ENRD~AKV@<8PqAFO`LRsG@->izlk9P0+kPg8tMdAE*!jdObD1N`uH-7O!-)8Bkj z?d^E+f7KtqSUlu&e5CPHd}r!+gzdNQ{$~!z&m5o1r{_QG_}>&CEx*}CykGMj$GvCD zr})36r~1jx#}(M8exF^62UM=k-#K9XH-6Fg_{@vr4){dl(9!&^^ILDU4&jfEYu9Hz z>yeJ1bmbZMSvxUraG)(M{b#X25ZxqRQR^8f!S`?FqalJiW{j8KRSl2U4*L{cO*Q1h6XRh89s(CGd% z{UbA>0t+OHNFoUd1O*8agcO<(LLiZc{SVr&b?+z4*ZRJol>6k_=7YHnuTA%Q&3*o= z^Mfn@@}XQlTjOHNx$DNm=l}b>zxS2DufLhb@jP$-xp6=JaqYGJVCJcX9nU_6ai(eZ z8sGltt$nW@;u!by`VnF4(7Wn)gr|5+=jUJeS>N%A0~&voi~j#!j@eE2+41T{JDlCz ze{b;ot{Y#T-zxssdw#RK+RglK*}>vZPyGn*{Ank5yLJAVU!LpMuAaHaD=#U`{^Mry zoqdm6|M??q+;rT$r1O7v&AXKQzO$UFzphJHUQ_2+eqGmdhLg`eYpe*XC7ls$C+xZeC2o;j0or0e2f z%DwQo@%xp1xlTWht)z`N3VA|26N%am>TD7wZ`5ZaowKli$C6D>tPh-`{^+AO92YcOLis)~DPL zuN%+v`~H8q!gs~}gj4===X&YD$)qb@_AdX!yR1*|iZhIdeftq#e2|?K&d*M{O5ap| zO7GF0iw8FU5jLNd5Ai)~+%gU*AMwtmf4Y3#HLiKyOK5*E|EiMV?0-$#&zk{4)4lth2wTd&v${vcer1C z(02{oH-A5VfXyTD#CYFP*X=pAljrx)Dc6qQ`QJ0&IeuN&10Gz#dK&ji$A9u0!etS5_S`s|a*>|Hc|UjYKlR6-wSBC<)8afneK=t0>%P^ua*5MDt8(i4!)3D* z$Fn<}jNf|xhuKfhkJq{%Pkz<viFTpoDe6yt90k@_dgyySoz^} z>TA637cTpHKM&0AwqF?kGmb9)=9St@JTQB3zI@?+%I~i7IsZTWPq|Oyn)*fg%HOj~PsJn6zxqAr`8y)kS&pZ;@ozrTuRX{YjxS%zb>AV0^Zmiw`Q9IBoNRn})%F?l zZ#0ki=!5^)+kE2x`Ou&LApP9+-Sp-e=esDv;_Z0f6EoksKLw5(A3p9^E{7<|+$GS*7cn{@wi3@(=p{@V!es;d6io1P$&4=TF z@iptP=3C=)&z$ew_4&A9YMo#lwjW45+S6U1`JZ~;dl~byRG!jr9_RZs;;Ve-hbe5l zuAEZ&;CC5U?s@Vvf57zp{BN9ZI(|8Q_J4czkJAo5xzbDT>u2kM`?{Llw4Q#B&pOQg zuR0#5zMZGdZ=U!6#{ZP}xS#L;7%yBu)t~lVXzjZCnReeZPxQRK7jm3s~0UVqOY_n99RRd3@%aVG0XpxnLedC?^;Pd=& z_f4Pq*w%OKxOBYgv)^Cey^-$tACBZcT6zwD5XR-F)=B0|cQv0AKKjfH%+t2MO6RB4 zy7sgD_O@?Rd#gOQetk~g%6EF|>D~HL|LQF}n4NFmJp0jZv!n4l<;osUKT*FSp8BEs zBk3%B_xJU@alYSpv+LFY#tHFmT`)B-a@@KxJv^}M*N@Gwc6Q%&C!O_c%BB0(U)E1+ z&(e!eOR#skOOo>hO9eZ}eYx5Crazj(8Q zwS#GP!GGHM>FzUrb>HHDwjbq{{f=Lamre07oH}0TcdqO>J~QseZ@%O4KjU5V+;P8W z|3CTbxyx_qG7l=f<8tFZwHxcW?n|wYdv40Egpcm{bUbPC9}Zc(@xO5%{bt8g^KoJO zcPL&%*Usk`IgYh*Fz;x6_RRlw{OB`(V^{7||ILS=`5!)JzD%7T_tOt3e|8Y>dFFrP zfb$0w?m0c5UG}_JPWQ}{luyr@A7Ja5!_Lrt{yH~`L4cZ2k*Dn)r0o#zPnxD z+l_PyPo=-}@7G;7Wq)12abR||^kt{&t8^TDQcmyk!0N@k&3Sf2iq; zQhjaRxN=`Tj!Ulok3XPv$UjA%@p&HJfiv1S z%3sj$l)^Y5e?tCPM_n&`l;4ba9T%VP1QhSDUF9NQUwQKbY~Qf!dOzb=KKRkweN;UE z@CbkHZ9Ut20i~ZEP32?#N9%t3=&C<_PdWVmu6*z>8Q<&p_Wkl7avhcLc$WJPSEwA~ zP`H5S$63_3u=&TdcA=k->l}?g9nQ0`2<`8ERnN)aZ0dRStIz8B9oNpwN8Dk2sB+T2 zq|^N9t~-v`IzF|3Q#h^u`(sqiZ9-YL)1@JzWl)ow=X-tM&)(< z0HxRQc<((w@wesYlvmvAUAxGBx?Vil^;EoK8CP-? zI}V8dO+Cl^K&SB({o;q$IPnixJ;nV}?^DJ7rp8J0qj$CS_1`|~!+9L;&mL;r`P)al zzjM>dvE#q{;DhFS_W$CA@xR}{(i1m4-wom4g-6DrC_iNH3-rFlf4uVfg{wXsXP@== z{QdI>?Y_P*j043Jss0vMr1jeIH{6XE%jwtTb_l4t<>RUY4 z3DmsnS;zTkd`~%9uX$hPM_2m(=}HftcEZlT#&hR{<^!ImK6<`&2mZ-#GY)v?fwc$g z@caAod@tL2-0{7CFfOM(c|@4-Q=Y9F@Pl zhdZ@?5zmgBw+cUN@qF^u&VB#c?;oFB*Wp5Re4)>~VbDo5kKd9CZbFM%HzKXc{NcYBrdxKH`hjw+{fy!6j6tb8y3>}L5> zZ?%`BuB%?z54(Tne|HX;9j{+W>vu|LcKf+J6<4}A^eD$W~EsPZd34*ANv zpTq33bWUgQ`8mt4^C#WofVE@xTl(f7sQpV%oPYdJf2dqn&f*iE?)dCeSiL=m+wWX` zkJBCg<$CS%uI#7!uRW-r&TCiy?+^Yz*Y9G&U%u|7>ie$7-NLh@;!$qwa2#cJi%;MA zA1;)=Kl8tFK;vBJ=Lh)8H=p_A((|f^1D3v(!=1mBk5@hy|FfQwj{1>O{v+Gj* zQ|TZ7e2&jL>+V;Wf3M&3R(|Uqx^m%yE?hgYrqrRQER`Wx%l&tL6d{PR=Xcr#u8X#Lkw z{hoT9)^F~2^}XL`{(bvyN1PAW`QhXKZ+`mSh{E4`yk}1OzIUBxNBP~Q`k%jiD~I@A zoNxYpcvHty>$YbO`1LDnTtEAT#i!j;b`sCyzt?qzdq19j<2#S*&c0XSbNuUX=ljkG zdn*0DH(b5O1%K!99Cldz+n0OakNe?u!?S;$a*MaM?^$}|aO0xSyz%wC^ps!PylNcq za6j|TuRgdRPIu>j%C~abdlKV+-d}&`f7a3b0UiHu5BqvQ|1&>oy}R#&^gHz7e}})} zesMeXlpmn{#Q%KXqj~6^1G;Y9Z#sV1K1J*F&*o743i)|`@v`&UN#llc_~})C{oZr* zd4H!0Kl?rZt^BX_;RV@M{X9OEJ>V|dW5=KU6z#9q&f|acn=79BhjFI)-$@_4#66S) zelZ=#8CNQw=Y07)`5NczI}yhZ?|z-<3)6SYz4!e|Px*+y;D3Hsvc4OajHkvMtp{<( zSG5n>@hR?r(q@#Ft^IC}M1{T?nj`xqCV;Fc%m2@J zK8%xbw&_pb{QZ7<9mjbodv{!acR${~;P|2Tuf6jZ^d3<0<$qs4)VPXE$1x8NEq?8w zcGYu*^Zx#-ck8`{q5gh*IV!BU+BGo z%0W0k&%b{wC;o!*zuE=fXP)*CS9#)0|8S+(cLDYP=9RdjeRhuHT}PEiT+lkJ`~K{4 z{l_2t9}gb*`49dd4<3m7{o^B@jvIge{aZL*h?nAw%4xju&IQf4|LJi*{^z;>+ofN) zyqWnG`hLlOdK{l$;5gvad^isGe*QP!chvQzhboW!{`dh_9`U&R{LF{;UcC6d;h+Q`kvq3o%`vZ$Mf($JP7ZL`wFuUTo5m) zJWJ>9o3g{otM9z9_@zsvLaQU6Sn?LmtFJ#B& z+sbR|`N~!J=rg}#5AneHLv7#m{rEUx>kjdDA3Z!p{;g||R^OFxyh%Eh<7cV$!^+wE ziX9*R*LZl=TiI3Xu&uYAImbA`tH0jDhZ~H~Sw%X%z5dg>id4*Gtbj6ef1H) z-@{8s9MJeHJnlCYpX1i=#UHJ>sb!+V2wOOTLR|T=TTQo;&Wo zay#Xl{XEyp_}^4IvyV94!tc}OfzQ`zm+l|`k`H0|r3)Xv@zuBUUwb?M%-iJGeN%Q> zeA%D!E8ga%ul(he{~70``*6Sc8K&$juD$mf_WXN0^}L1Gz87A;j;>!Qy=NZXeA@g{ zdZw>DQ$JOD^Gj3?UH{CNw!hzcwCksP&io0-3&;D5N4(m%@rwGrFl}G7auc482foYO zwvY2@>%!ybwQ%u0^S*IC<=XkU9zW>9&pdF~PxTY``_#+*zQX~ZxflDc+$s<8-OF7) zRPV2P=YRDx)lbK*i;L%V-Slk7hilbNWA2sNJ!Sv#z#XTaE1tV*=lAsOymr}j zcWvC=apkBTTSuBl(bhFn?W*;l=XZVUW<1LEen)fMxLUnb|I#IFJbBhL-jwdz(fFTo zsbA~;AdVYX>R0P;nooPrPwDG-|MvGPzx)-(|6aB4&?=wrUH8jBZYE4UkH4D!8`m56 zn;It^zbk%aJ)8c<8_$aODYy9B{PynrPdw*)8Q*!t6W=qg7k=h|=lJ+v+)ug10e|c9 zJa*u@^7HMF+RvR|;P{?>$gQ7`N>BTfr}};TZ>k-~2dC{b)(+!@y@$}a5%;S+Ke*EO zUmnln@7Fk7`Oc5>xm-_qu3UfpQ7`Wx2Cpe>K4$+~ zetvNp*Prvdj^YaH_?6>03jOf%m^rH6?L)S1@I8`u^`p1@=;3|id(-^n=6@(2@4q|c zv30ek;-=o;h@0i-ru`o7HU1R`?D)OjR)5OhI5fT6O`KA{kv&OIJWzc2A06+_Zp+u< zfP4R*^x)rn58uN0AHTm8ud|*w{O=d9{FxUxuAK7AJ9@a_GyfY0EIrw^{4C!~=j?y# zdHNgQ0a32L3yfQT>0v*GmHYUgw=I78!PD$W_B{^Ylli*`SHtb%X7Rt@xx(!8_ix(w zCU8DHA@27_H&x%_xhp@w`Tsqu{lGmx#rc#w?q^;hY#gD+pN@a?(zw7sTD>pREh%W=T}^x%6qUFZMzhyL8f z=?edchkp3xFKB)1_|$kQJQc5bi+MT45A9Em`{9!R>w{mD|A+roZo=l>_wU`B$BD0bZ|4giF80rl z{BPeO4rpGF57b_p-;5{hJ1F^K=Km+%z8kF^dhcVZTn~RJp7@{jn(*O%#%soIEVJ*`1pnTE}Tkt<7xg))}8UQ>G_^&cDVDZ4Q~v!nN^^^SQNyK{cuWqsc7>wLUYJC)AqN7sGIUAw)j+7yXlUkMg32^YQ=FkN(9?@7K-$u6Wo@_rL16-kqCiFVA7+S$@-Vetu}r zy5||Md+yR-IXV7W@l{SefAy$8Vt4hkjsNxggBGp z>*?%>)^5N4Ha>jgEu4zadHqrGO`qex$LBiZFg2du)p6yLHVzAGZaV};SNe@l zIZyjQzxKfo9`}Faq2j}dw3qKb>2JUBxm0=n<>P$(&wLZ7vLBe@Mz0$8n;+ZW54iXJ zjrUETpT}Olb4!nON*}x8-{yI}_wH+N`i-~aUFZ7l&wo%qDJ&o7c=M?E=5M@lP8#QU zR{M-wcYgbku5Z1SPpaKHKGmM$et+;#^R4(GF4(#OPkrWpJ-2fF^|$i;EFB-LT-jaE z?>otU$5TFZ`+%qHK>1Do{*j-ry{!{cyuf%$YX|k;o)a&#k5_+TU+>iQ@xi;l;Nfa( zALVnL>g?m~`1|=DPUAeS9!|J?N~iozpLy5eeenZ)B5w4WpZwGC1MQZMKa4xbN8Ep^ zJ!scQ?_98S|Mc;^eviI$z;V52z4O0kz7>z;wu8+HdhYm3uKrGamf!3L z4;H55f0ftlS^sK2(s)pR`#f%C*Y-p4xA@7!&>!|4#92K4ZRIm|ZR1%f~D4dkyb> ziYdMsuba-_Z(9GMT+ExhzIxFgE0?(O^p*GJ|97uPT<&l+b`&?vzj6Gz@4EbtkACsu z3+5&H{o#FnAH(yE%SZ7+_Wtpu=6PSd+LQUS%ySe-G z#(%Zvl~)`*j;Z{|ACJcW#sQ0;Kc)EDpWm_U?@ep>e|wd$_hA0$N{{c2{OGN`fAp}! z-+P3uQ+{-%<8v1`_|f&;FJ3(AN00X${>7!fFYNf2uJeENIREq4xF8<$rlZE8-+u5! ze2*WX@i_m$Z(QkOhj`>vyZP4J`2IU@y78W}d-j_#0#fCca?)M{+Hs4S8-qQQJjDuAb&&3 zAI|$0`NPEl|HG#o(EMh+5C7|Y*L`&PaoJDoe*0gQzw4#@uF_xFcaEjY_eqrJzJtt< z&V9aD(tNEjURHfg|LL+Dzu)pp#A#ipK8`M4{RV$VYX5S4xa<0!iuJ7Y^UI8P-ow(< z{%G@u`@U)ORppR=c&YEHOqUPoTE5EnIH>Z83*vy%i+7d2-fxJD#SzbUjf=N=r}yA> z{qgfFzc|$P{VL~A9_9MS4^U~*Do^E+e?sNc{%ZFLOQ&+&d-lY8IBW5=&Up6YG5#AL@BE>4 zNgRY-cD{9_{;+WCM|Rfr<9XB0vj_7y?YH`FfATouXYmU85wH9dzwueSEnQ2me$;vM zvc~=Qa{}vv&L1vu;&uPwA=zU*39l*LaX;%h<$dRX>P z$u6@a+d-b~;3{MU48r}~$v z`q0nd(~cK@Jzu+bo*i}neuwGz9Q~!|kNZuPmvYw+r{m!9zj(Lj{Ve|1{n<C&`uME&tencv zv)|b`F8dHK{gk>S-eyISI>F&V^lwmAI>)(_{^IZ&(b|T z$CXdxY|k0z-R~l={iFI_J*L@H@82+9XK(!uqn-=TKYM=VsdnJ}RDB2^edboykL=(2 zv3RrRbN#cu8+V?sD?aw*xOE2Q&n;g4O4lzP#kY2Jp40i)cD%6mT>WIv?kgO}KK|p` z_c-9Iy)Qh~?^u_$@Aq)O*^hOc=S=@K{%8EIpZ=Ya*kMIv3 z=fD1`;(zk_-534#TR4sXDbN4>IQ~0Nsy_b9b$sgi!ZZ$+S}zOh|HV6%pYL2@{aJc= zq3j0=jl@Na+05zFs*;aA`I=hrT69Q@9wS~-@k z`PqHzkxup6@!$JY^PBv`2S?Pd;)}m~>8^^*24j%GftDXzSW<_1Jmx8&gc8%fOo&C@r`L580W)zq^o_UN1yqK za@y|z>FFn)$H9IVi?i_;Gd@x6LcaMU{`A2y^e2u>e~QnvuNZ&CXQq```MPsW{qZT+ zmG8UPeRy4$AJy?2!}%P?k@816y5mRlYg6v|xAol-`F!>R{NN%C@jR-W@xAr|FZ?e5 zi;o>XH9x>t{^$88|HqC>*Z5y{@|A1+Yo6P@<#{|&AB`VhdsE{}c9DOC@ulyoHjnH6 zW0&pksJ+Dh*dbntW9>W4eV2LsZ5%LrsJ`*5&tLb&u|EHpN8w!0_R%;I{}aFdZThZ1 z-^y?5dF*6b`%xd+`Sw+h`z?La#SZiHi}SHp98de4x?XtdxcOq~bY0_{`22p?djQA( zgxQsF{=DwfPWpau`4ryq-j7&1@c;ZN&-KN}AF=)R(zWl%uwUcx*DwAyt=-$N8~>}H z)?aGR{ciHxm$qKV`S{WO=!&0T-H$H6L)<6s_a|@RKYpC&kMyG}-S`n+=)F?z`_eTp z^gR6!?x>%bHjevFi17~ho9Y+wzvfkq^Kn4+)OVl0@y7A&7dHR!enEb9@xQeFuK1pL zH~we7FKixYeBd8==YpTV{O{s;@jc(^6`sEGzkNs9JevQZ{b}YY)sY@HL{>MM_lSlqj@1+t} zkGK_k)6aUZ-+eycx>tPjbMv0!+9zIN{ukdfAIAIm3&jEBX*fuJfbz5VFRF*;JCy@F zE8O>BUf&nl`7d0fo9|MW-{*3SQ)DNXd0h2^cksKN_WZlwpY$wz=Yy5I`gngmG%i*C zI7j8-y@1}=QF(4ZL^GY62b(lI}fSB_CwyU%`~)jE8~ zvtQ*Izt>Kz=U!F4;{iWQ`Twz}qub{{&A(WEWv6kph36-Fbbf*H!rDdst#lZ7wHv?N z9lyWkQ>8!t_ql6cUU=XA*!%jPIizx}Jv?iiZ`?1{PkL_sbbiaYqOg6};!$43w|4bh zKI7rqoAfD%Y4tK5n4PPaj;}uBUG8TO?!Vi`xUqb-{(rWU!`-!20K(eAIYyFQ=8; z>-uM5zeiVoXI*5zWn6K5JWINTr^=!8@8@HSf4X`)?fbRe$5+&gc$Lqz{5!+sg z_GgFdiszNjEgyT%!ms(#ueslNao6Va%BOU{tCf%b&wcvS={-N*<6FJn`|FLj^`q=Y zJlWMV?^{1O&No%=uKz3@r^COpOV{K3?6&!8_jmp|o^w8K=sC~pHN2pBs~_smN7ey>`&>^-gZ zztU5`*tj5nul|0m7h2EYmDV-V^H*>B{kQy0aU$`4_f6X``|kVg;(7D```tJGmnwJX zr+!Zorg)$Fx~u;6+mG|pc$#wh&UIYBQhI*tQ||Y@>-hMe^=rH@wLVQ% z@bdW^Z}CrG`5(^Lx>$Owr>J;KU!2l-TR0AAJc^pzTantrk z;}AHX^?$tY{qIv`Z=I(fUgh%qzC!7&{J#1r7aceK>qkDm{=r{g_Zf%zn|NPT>nPue zEWbZ~%dhr|v*97_-z$CkapfN0;fGe3vb)aT{ou00XU=!HiFP19I<6ug$KS8#zj8le z`PV+v@wSDZ_3*%PkDe#p@r~tAKRLhNIMc$etG`X-e9~{epnmszmHwjjnemgq2<2b3 ze7(#6;w~M>MdN;_+?uET^byavCSG)9|GoS#?sfd-;tP1sGyf}{u9MEr-?^Z2w9nJ? z`%cHt=6~YL5Aee`4wzq{btXT+@j&ZoT+sU3asD>^|HjR%qxgXxz57o(UN|lqKgEF* z2#z$nsy>BZ$CHg$jW^ka^(gVLe{^V!8X zAg=fMD_ySN^Y8r6bu5Q_U$Tn`+fbM_%~O4 zzMuTVhn@cRrM2rHUgd3H{0aA+-XC7~`Mv#zS3Yr_A6|U#=dXF$4I2^F^*#p+I zJRnZxx_^G8^ZvfQxDP)*`TpcOpPyg#BmChT@0*VQO}GA_-QRv+^9W({N6(#~l6f+I zL8UM5p}&>RXa0xRu@CwB@GXBhp!^@5A83A(_@DDr>#Olo9e=Kls|Wo=<+$$+$3NJyFFAc;{rw~s74GJiT8P5l(NPj>mt z{ahzq+HZb;JO7PGyK!Fo@jD=8Z*jr-2fp&Zci&f_oRwSs!uDBb_lKK}10MdZK7D^i zJx^x`M_Y$Czmkva=T)U!Jn`qVj#n<8b96jnc9ngf{%-x={C3Cfr|So6kJ6D{j%#G6 z>qm{}&TA*7qvx}4VRmxY+56FPplAC(?cwwXm1E^2-i57?gx{yi#c}1`Ix3E(U3C2H z*AH)b#Qe#3e5jidUb@t%&K zeslfj`k&|WGp^Vy|# zTs-@pecuz^apRNopQYAg#kY9+y>G{HfZ|Wh2a0dUmyYT2|LwYsV{0#KKiToUJt$A( z<6W%_3vXX8F5$YZ`|kcpj(6R3c9S-4sh8QCdM$sc`|8)$-{yBMUFLu6Zfd^G?yVE1 z;=}un$u1^p56CeKy%8x03 zxc2u-ujjHu>CrBz{^5IXid&8QQTf1$?urNA!|bK-^f%u)*f-ze&7V*?dye>~|MxYo zFdiOtejG7fIZn;zD$ji{8OLn?Cx6O2uG;$)*;D1~JHYbmJ$|KwKcMw$JT*VS_w&H! zd;j^m9>-~4@xD)T_DkQ(Pks;oQ{Maj^Vc5sq7#}zJBG(_qf_?d6e(jrSii4rn4*dtN!%6>gAJ1eQ%uFcybSCch*zd zgWvh%;5{$?$8Yd+7f%rH)cO;L8vj!c|L&2V{3N#@cO0E=zpc%@VR@-r-d`DMD#_4YI4di)ltaS4~h|Ni^Wlr*ji0;H`6t);saB2q9rfLW;`xu4dQMyr--!pd zzt}pzaPK3;|Nh~+-gWJ4p_Yv9$$M`6m>v!Gp^9lJQ;bNrcai8s5LpI_l!FMY*#_@D6F!K=!r z^i9pjrQ3Ly{ruXc^1JVS^c@i6WBF?xYW^;s*{AqC*Z8g-u#fba@0quD{A&;Od||2| zW9Rjc{Hh(_`%mkq^o!j;zvbus_sXSoj&C1+p}r3H&aPI^Q~AjbQ~4;|yk7nmrpn>2 z=KuF__ER~rE9slo&Tu~Ez4s%`?{6IDIsM`*A8XIgs$Dogtv{B|?De(%tGD;Xx93Q2 z@jY{I@sy9+mw4oxy}hdSkmEl~58vANE_#oi=d?~srAItRU+ZODCSColzgoX=`hn6v z|IDd&Cx7hmp3i&z-H)H^cHj8!>+d12;W*;qLhtgwdwJ@og{RUZJk`%imw826df2ym zd{yJ#{rK!deDw$C{c^&ddspS^{wezxKH548_i@}h|E|WZ?oW;9olkKd;i>t&@T-mk zZXDb1SL~|$v-8*XXuMTUQ+6yod$vBTyk}R>yia;NAO9N%-0|1`Lc4VR>U(@%`}ADb zm;aPM$I9FO1?vy<0DeXFllvXG?*MLHFjX&q^%gHxKHq=Salh$zuH&x9tIQj|{T9CS zKlbyN*YRgL|NORIq&VIG`B5ApUfXw2v>)Y8 zrOSG-^4tFJ_5rJ}IPz~i{4?+lzjxz9{VsSkd(Hl5@7go|g0JYO)iZ4!?s)tyj>lfc z&7bw~z>c5z?|i*ZelJn}aloG6zSj@0@`!(pdzqi~KE3(TJ@Y^5 zG9FFYtuX!R_53(P`Tfb`x_kL}p8k6pw<+C@$Nl0O?i=?zJWx3t4x>JCoL{)s;eHqM zwNSk6gUh?@gG;Y}F8eteuZjoCN1WrXy*Dm?Bp&5FhzgKE}vA#9V@o)O_rN4Hymfp8y->&)E=dN`6?xOzSX!~k$!k@p+<6Knz zPVfBhr;p?O8Rbho=BKBAYcJz=9cSnAdsIKtd_a57?#)M!UFmP*eRp2GcuRlwjqTyFgDUoLyr&;83A z|NEB*&+{Db^W%@%{@&UNe_`qS)wlG0`O^IQ;*NU{*m!=l`uyQlO!C)0Sy}B&%Abii}Aj%U7W7=>-~Y|4R{9{$&SK$yRr z{m5Us)?qlI{myt_svi(`|DQe7eo0~bK8-8NfhwoQ8JsUJ7w`Ml8~3BiqwkQ|kBWow zBRbmo!sBM+eyMqE=bI;)rwdQbD>|Q={|K8uQS;-&|M2|Y%jdf<9T#8r(Dm)ZVDGQ_ z={e8eJ27AHy1fsv_aj>8cKrGJ*Zc^#ZpIbok2oz|xMlAZjQ6=7zp##GH%IH&drzVB z*?W8eXK24Pj)fyy|MSa=102rr&)0GD=`=p*x=*g--mB;M(KsSMv5vp4Q(HHfXBA(Z zV*Jl>&!^)acU3;Z<7(z-_x$kd!1dw`H2=N%18%=|%HHw^{I~EwN_ngxA$~!v0d>l^Eb)~=d>we#x zy6d~^tMaYAx=uds&(#kK;{w@V>bS7}w|0)h@@$Wfwb|YWX_o~_f`>`)TKFrh0-~9Zhzy4-lz6)p^SiWj+p0nqbul!QX8|#<8 z@wQHl@0nkBJU;{Nmfy5_jQ&x-M3r~C-)ZujHh#IEdamDtY9IAS>`6Xo^;!LmYm9&B z*R#{?*!k>r+%G>f_S8D!nKM~0+~@c2uKSz!Yj@dqs=oK!?5cFGf7Bmke|LVVo$vT_ z|G4~2*RH3t=U07gHw&-*ExdMi%4eM7T}1dkG(Ij^__C|yjLFEytU)^dRV>4XX!uOM|j88|NTDYc)xzvDYx#cT$F$J^?rlT z@_%++b~KK+`FyG!Ise&u{FJ+Hzn8qrx7n3){nR z->B>Q9l?4@_^#RexZv@>=(^+oR=m&rZ`^OHoWytZxnEy9c(w0SUu&oPeW>?AY2VfR z`_;O<^Jl-V@a$*0b~K&e-*o9(I^{$EM)j}KX}+RA*!+)^_>*#?*596cxZl^` z_*i~AmO85e!G6!cQA0L?_cG}zwi5xc*gy{ z{1%S;i6_1{?Ks}yxO`CgT6&-Lng1#8?>?^o&4;@G|GMVq_IG{zF+WuP&Fhpa{#W^a z`HcfUe+St8c%c1i|K%+`>dA3x9jUxm{`yD$jK=Z*_NltA??AJ2cI1BRJAO9SVbnYp zFY9}Uy*Gqi&F-~3c$uj%{8*Kv;N_}{d3d)yDlD*Zo8*@N?G z_Ei{{QjR!@eBvaPqwvNZ^Cw$B&ukdARbepGm1 z9Pj8j-}v7YuW-Hcrq-eS{%|zBY~j_zbmb!bc$YB0E@6J9EC0$txqtDpU+bMOT>1Ot zy4?Hu#`lajA7AB2KYyj8@#mKx*U69T^$*YLc{w%l}FL@_{SxLu(zEJ(d3W z-T0q=A^T!awWH>%=JW37|KoXSzXv$pe*Klp(KzFHWBz=Vm*=|$ug`TKKl+oaBCdLVm;Xrz4tO*>h&#?t zFrMkU`T4~)|N3#C@idRc|Jh1l+8u#OWG#)3+k8Asbsqs@kj@OU>H9x@b;y3Rq`~RcIdHX~= z&mU0#<$Z+C~S5w)ANtwfY!A~o5$df_RDsBTrkC5yl*fLC_jCF zICWpVjJ@6GLkq|GJSUFlcTL=my52nYeX9H%HxD-cShu5)(-@lX{c<%J7{%bzu zK03bHdlbEIQTnO$#Qnzqj`|L>`~T#j=lD3`;iL9Vvp?yw&uBc-`j|bvPjL&!%@6qr zs>i~9Pi`HapPTt+?HdnN|9BwYZ60d98gH1tQepGj=Bw#P*K>rG6aD<<4@&W2YF%_! z_v>e^JJa}t-z|l;U)N8KM}^^9K$N$VXKY5gAoG*@0 zyK~&Sr11_v+kWAnzv>x(nAT2;XZ|v+ch5R{^T20~cf>cF2c7+ngpZvP zm7nwD6uW-s&1=ig;%QvZZ=c;fuMf3T@l9KQNx`@A9#J!1yWr zZhk-excH5C&+0w4j;F@E(vglk$#2KAlas#L&9j=<74LKZdG~KEKX<#YUev$(dB0{S z%As-fS(V58`V;BRuJjk{H%>pY{^V5~w_Ly98=e&x5bvv6|Ll2p)&B@j<)iSi^R7Sr zg0S*eUX3H!lkmIT@43Cdatrf!>-%vLb}62zc3ZsZ+S}}Gb8zsK1z+FSDnq zb%OYCzNzOH#(OH4@4V@^FJ(tlyvX(Oqu+d}bi|Q<`=RVcn7U6p$*-(^t>$UPf4;l> z-N$wDJ>|m>j(+b==RX%m`^JO6Isg5~`NRA2WBkgszLIXLAOF=y*g8D_#(zzp{R8j( zu=4qp2Nx6X2}`fzo}1d2SUCSecD?jcc2W5F2QHt>_xG;x6c79EweIx3r|(?ztuJ2r zR(_wm@>jk5+FLz*`Ayp&tiAl@V?O!y2OrcP{_^d))mQIX9RH*FA6EXxTj^)-<>Q-= zb>{e=^dJ5gKQNER5pX~}uy%ELH@n8asQ#C}pW9VF`mcA}*DDvq$6OyjwEq0br(wtM z{(a)>ce?b$%TDL__iy2U`9*A^#e)w2>$&s)^L{n+XMSkrZMaeUO05Gc zS9TT$-1`t;`5*3ReSG}(4)0SxcMdq-r@zDt)u;Ca#sz)r@j`B>;3%I&e`|puXawouaDw>Q}@ZwU4QN^{LytiuJwhh z{?(8DG}#6JH1Xk0@jrYD|DzvY<=b`RmF`o|-LG9bKh^&Vr^=__6RmsWTgQJ7$BXx6 z4-0#)<3}sUxR~_Eg`MXgdi0g=#U1fa{E_+|!BO$}ec-726HeRr`^nq>-%qafIc`1W z7a0HRd%nW_UicfTf8ozRY1}U!`Q__8dpCYx1$M<7ul&`U;;g^<;C0qF<9^e>x}M{` zen-^<-ZxdBfABUA@ds2d_~7o#U+{3l`4N8c>i_u>Hg9mB{*Ia-P8;8SZ&*L;`ystI zPxzy&zJ>dK@HD%?1I-`ef^kCg2x03jYQ07AIXo}^=e+j}I)3MWj&J|*;-fhCzrU`Z zy6=x4_gkm&6BMucigjG`mcCzX{>A@L`FT%Z%I^R83ac027wP-T{T`Knobrj^rRG<{ z;=|=WzVg{V+|8Tv@6(@k-#0GpcO2K_9*&y_b$;>14f%(~`*6p@{j|THiznts_xF$I z$1ic0_+Q^qW;d?qNA|4$HvT7{=7Hv6^usH^UHO5z z&bW$`X}?FakIu*a%s=B1doTYp|5Fd=`xWtG>jUkG;^KGRy4HRAS?z$D4;F5Hp&xOd z<5TG{?mz3e$WgonclZ5f^>X-M{b!uwnFA_c$HxJu<9|49+;sbf&2ahw({$ruyaTz3}V)>iAjyfakh94`@C% z4*2XZv32Woehshs(N&(!|KbMfy?9Hnd8vHxJEZ1)}w{&Ejn{|n#k zMOga~|8(mv>#@qQbiDhVp69sw(_heqr{Y<=tKHoBU;Qt;={=l%PsVlg|I>~Or^>1L z_PxjKUH(0P+VlIJgB|(3Lw==`IzRuvj%P>KRl;|5zj-g^FX;K^3)+KtY8QJSRUFTA zTBm;FN!5en(_JUs^|$@LG5*)@8=e>cQ!YI(KS}*Z`QGmk>reWwvUaB)kB$eVo?AN@ z7k=hm^2aWv)BG{MT>87O`DF7K&)Gb3$B+NA>)-9)q*HtDcM$&N)kpi9*FVa4_453_ z$og0HkpDIQ*ZrySyZheHad3jpKl72bgS87rN=t#uKGjass2}(RzJ`A9G98i`@zcN^jG3h{?GdS zJ)?Iy;JDxV!*S*5xaHQtrGIv*96fLPuk*j>{_bAC_kPfEcA=c^TEDUW<5}Imarx-{ z|5ELv_V}#&8^_J#?<$_I?>Jr{{8`60PdNJA-q~yMKl4BBQhmzbT|bLYoa2XosE66r zlwCf@H#x@u=O@44zQWRZ z=YIOdJNIM%t`qNFrTfnRjJx8W>gT_Eg(?1o4^F@LIDWp@8~@86j~#sfasKSzjqiQ= zZGAO;<$b^OcK);U)j#lrE4TRGc%Sus$EUC7=U15DAp4f?sd<=u-F5k%Dj(-7w_pEM zE9bZ$|ElWaD{q`{`n5-xJ^tn6xxW8VIZxHk_@8=F{`gr{$3pH z9>$^Yz|YokvUtn*pLlQwisLjs;cdz>UX$OS^Zh<3pQZnuGJJ}?jr&bk&he?{ zY0_ytuw%M$Wqy7g$K@QyAt~;ERKDEzs^yRW1fItZ@J02`e)z-fJ0WpE@#BA8ceHYj zBX2*+_~7OT<_(^2ewF{-(ca4!&&`kTng3O<*^hYDFZ<0t&UZZiXZWAr(Qr5WRpN#G zO0+}a`T_Rk_kryFlQ(-m-0zhG?!AC(7rr;5e~>@=i`VZa=IOq>TYIrj{BS?zg7c04 zO{FUin7;DAzR!#Q`Te}#n|}XE&D$MM@0{;XAKcD-)_I(P-{8j|xIh0A{)At=j`Iur z(skT(yr(VRmtP=Gh700m#&_!={qyvrD}G^|VBaCe;T%88K73DveU0;_(&zXz{?~U6 ze1{m9bpCL{`+j5T_@lRYal^hZd(`v>qui|KI&OoT>FOKAAn44@ysdfBa?Q ze&@J!mhPkRKVjo$*I9?>cll3OJow)<{?U8v)Mx8*>(A0_9f4a@ z_Di?Eoo=13|LFYIAMqUX1IOFy6vxqNaR9}iTH!k?vE4~>%uH?L_OdOuz~);rQ=9LQf(*nV;6aUJ^6O) z|FnK*C_nGxTjHynrslWV;rrD(q;j3U`m?;tL$bHl!}2Rkizihs3s>*$*U}GVFVF36 z$7_GuQ+6}X#ooljzKU;l)IMS5*7=^V-#Ph?Q^oyCmwv8vKl4%h^D5ue@1okP`C|G0 z^|yR|<)P*eo{OuLuleXlOUM7Dqjgw*81kK8$+*nXXC5OT_k1ajd%l&+ zJv=*^-6-$wFCKQMT&A!7f7-G0elJh6EB$=WnY~SW{?gezTmIS~e&>JH+pC}7sn6Bx z`_z1geJH29%5V1b+)vBDc$9bNr{i|dyifaZ{j0|Rj33W_f7(~+c-D=3RDAora4P*h zXZp+om4D|``756NE)cIc?R)Ple1H9{outj@&v+<($6r?c-rLvGDWAsY^1Jt;u3tR+ zT+GY$chvkaKK5I0`&Co%fA{S<)A2fdNcr4V{)N?N$K!(R{@ai15C2;{-+7Clj`Pv) zJ;LpaRX_Q^o$t_o|8f5K&&ApD&$C{ZAM0&uecX3yf9e0awg1@oNu|I2#yCa!d;VTAyHZXRmvcRJz4FvP;&)&9 zRI7(yf2)sQf2*fdzvui^JrqyhHx~ZxBmVpn^&@fD-+uE0%`!cVzp1}vK zi*TXF;LZI9jE$x_Nt$c1J+KA7mhb>@OLV{SN}D< zia!JH6bJ0SI92btlV9N}|4{Kw)l2brJnp7^^3#g{H7`G$@6P?=KaEEszVp9viD~~ePt7lNdhhjzSNYaIr|cl^7Y{5R`E$JY6ZRg#>{>d<{iGv5zsg1WtG_AUAs^ZsySl4( zP&>?j&HMpx;=9^~-N{+&8~Y@#*(Zxt;RU4wPTobH@uk-@Nkd@9nvG zpXa~J|76tf;_WlW{fzhd13KP!d5`u!z)!CIzIf>;*M48T?{LG)Mfl^#@ycKQestAW z?S=oK=bra9&JK3|gyWTXobmUsuXOr;CjUMD6OFI&JnOT={q#pTAb(H(fxmEB^?$gO zU$^7l@4!!RIu4k>nRtqS$6G(^e|;x};$Er!!`g-K1#2(9KRk_Vc%R@$*YO{{J?}>k zd&3RIoByDBcHB_dasGrokMhrQT)Krn_v!WV#_s3m_UDiD_T%zDt)9-4&((j_sfx;_3Z~A715Jy!k7dw@asamgBE#e06*(|H9Tu9iJa$Iu1BB zuP;63ebwvy4&!~jFUx%WmHRE+Iz4Wse1*rcXxGh;aPhpWjrZeS@rd~;S)axqp1&Xb z(G~xXujd_Y-D*A5@o~WRuZ{mv=Z)*n`s&B^%s=9P`Cszy%daXv+`eDwj_0NM74g%p zobFnC!uRm=@_*Ot^puNyc0a`@l*?WJEj-8d@*U53)z|z#hwpr_@$0;&B|oFBALAV6 zRi8Yb_kP_vvvqL&l=&H+L(jUmc(?xLcO+iliJ|xwWd~Gw($>?p$E}m%#j~5U&dk2z zS)MCw+>O;eB^I#VM5^zh}qCPdvBqYrPa!F6wV8f9yj!9{VZ3 zg=?3dCp=Y7-IqP-2MWLPzt{H($|wKt%EvmO{PW+FpOwSX`_;#B^E2no*Qxnn*PGW% zZ{O>%4k#U8d+Rs&^BMpAj*@*G)z9_2%T&4Gd{gDA|DkvOr=RNh_5*Jp@b(2)UfNmd z-1oK*53D|)`x*7&_|dKR;}_CZy^m+)f2`cH+xa0+kDr74%&%&9;}Neqdm3Lkys~m% zKicFrZr~Bqte13Ov+&t{A`up9d9QIy@kFMj-<#Kpo`FZB1<6=|x zUBA$NRPok7yz;-k2ZUENZ*PCF`Zf>MPnhRRXBsaw-)jALcwzTH^I3elbfo63!c*gO z{Z4#NyDEPhf1de}d^yiv?z-db)^TwJM=ToPxUv2 zcU|02eK~G?q8rzC{8jh6*N&g?+IQ;rx5{h#3r=}CzVcQM)!+PhpZSIOonOB&Rj!Ut z*>U4qe3qRTZ{r|)^xWynf91@K)=NGT_(A0D9e9%0u_@0mNx^ctL(p{If9vnA(zrN;=y^jMAB5UkJi2p-@msb_E32Gy#GWyUqAS&`uq5w`tElh`7utU`7QMw1%83?ifLT$-S62R z{#X9+!TkNS51dap?uYwG$MkboeuVKF>3tr5nm3*N7cVa2I$Q$Z(Lc1$@rvNVDWW{_+J!kuSwR7ijK;^7GRsO$nsq!6nJ^9UljUB}`w?A}# zX5N#eoDaYAyf|K5PkQ2fxLx*Km_5{A)7=+udJU_0zgytI{1)-1FTB~e{r&94^Rn~! zEjxIBJ>s0%&FXdBPyTS7?8LeZzcL@&cP_>O$N#PeU(Z+0cmLScuX0uIhx_gOzO|=! z`QI}K#NTlCe}34lao6+Am#O)1`^=r!AKaDwbszos%9rwgRryd~Yd`$<-q)ViuBO?; z;f~p@^y2ZQyM4dLVf^n)SGnSN-jjCx_?ma~=fl4mum1S$y#2r9fcf>g{}--#+Wh_8 zhc~&;IDfS70~BBH12n!j4)PCleQMovxF0);1Ah2WyaUf`K7F`f>5lu2D86*m97tND?5@QU}T-=X4ozxhz( zlkn7hkN=|g%-y-4auBw@>wY{ij_mo?N7TH_ywCWY-`{=*-hO11#*Jlju9<7bA0zwFBK!g1#F-IV1&d&~cEoKJkUGxy8q z(foFW)icEdsrN_92Ro(ex$t?9TF2kdndG;1eSBx@q*pah`sYXdt$*D2$>X{6a~cQi z`0IJ)?fP`@2durAw`e!w*N#%_D|XPj%I^k_v)|IudE=FF_~Q@onaVXgC|{l@f3NlJ zIm%_nXBX2Q-*wZSe^=va+G%!*znt&f=wB-5`C~rYqw=nvQtQC#dx~#WZg{y0S$NT~JJ>79W@9XiL{Pw1}p!>{Usrf6l{wTilyMFoU zyB)^s()ZPe;uOMkTu;BH-0Mf{XY0SRch^1lYxm=O-$Lb}->rOz_Cl z{x2*a&D&G;BYgCk=NUK5_ov3CuAe?%uRS-99tVu~S%);QZe7N13y;f{?(sA4<9N-V zFngfv;a^kb;rhyD{p|DpUe75V@GEcB?i`<*mvmj%uV2#c)?U}|H?KVVea+MP z*_wCj2YzrV`}p3a;-SLdeGAk7IsVtUJU_s1KjJz5f8TkF@0tG{|F-Wxu0Q)>$GfO; zrZE3G^RIEhUw*8I#`ivY<9pMeyH--IgZ|y6)}1uoH~rz;@zzK9pn0L|Jm+WgKm2g< zysOIf@I>o09OGH>%bwHmUwYJw`_vDvP`;;?&z<|-`5)d;IUhazuXXJSi~pGiT2H%Q z`^XLs|6?E8$M>%En#XeLDMz9rwH8Cy#iaIiPmzIIX{&|KGc6yfFXBUk$gy1BBDVrNlQszc}E+={Q#T ziHFRu?Cxjgd2zrvj(L9mdG?XTd+Nve1IkCg7l_~Q2;&yk6~ghO{HA{OaUS2ue~RDI z-j5c)ng7(`e{sBc4Q_Ki@R7dqGp=*AdaJx}z0&p5$9=ev`{P6Lzm>=CTbOzuVq8c( z>h)-L65sQj%B^r*HGf6d;exdr_xHVzh12E%xL_rs0*q;aVD zAKq5~8`ops_0RS93$yogoqXT<;rz~~<>!+tzuG(d&Ht})PEKY!%rphxcP9$pShst8W-sgAN{TG3+s1C2T&P{{Btd z*Xud>pYuQW<`0MinxDi4-{pV!4-RM^)_8LF|C6r#0P()FFWB{Qzi~k2)4VAEKl#GZ z_%k{_Kf9^&i?`*6XP(sksqwJ$eLuzd(ns|}(%F7e-$C{r^l99){n5sg!oPi~^z1!~ z=Li4@Z@A{7-$fjxX%_ zXFsw2IIi{Km5=75^G{lMesS~5q2qzA+grD`KKtY#=d|;$*Y({K{6>E!e$T(_cny1X+&tWK%*);P#j8Cz zUOl)!4v7C%j?eo-*^T44UFQ$qR1VJb$HF-)r#PA8!c+I-YUXv;SNC<^KR@E%I%n&a z)=92&UOp-NFWkE6_59X<)BNS`{IB)ZM_2jZ<6FE-m*+|6(myp$$hUs-{TlbuUphZ~ zIXWITtvt{9eRp?u_w0XV-CQ}Zyentv^*sIfJzd7F>hF0!tb860SbeYy>CT?wT(c+r zqT|YGDqi+_SJ!*K>&t)nl#c9S{(a+ocMhn37S=zneB*xmUElm9J2cPtoVef7-sfkY zzJ4k0x8G6bf4%pkzP^v4-!r7&{p@5~x#*A9p6X8=kN@SLF5ljpQU1pP$H7*wsd}qE zt4DV58fJ%%r=R`afzHP*lt=cPKa=w7{5W9e*|Foa=Xx(`{kyPnb}B#PeTN6`cY|@y z!usp?U2nWwxrkS|=RR{s<7USX_bZ*xT#!AMuW`Wo59RvFBfa?rv-jq;ukWYpeR%xa zotK`e`Mq@9^?tti#udA7&sATZufOQJvwn2^tS9Twv^)Kg@}>Ic!u50W`(6Ju^&HoI zmM%S0?Xz@EU-#+G4|<9pW)IK5i&QW7@~?j4zpFoXpdP0gB)xOP-7jAC*K>a3p~j2xz1Bg${P zp8c||Yx4K=-O|=IcYi+d$NP?--J)#o{>M!n|F3W1`0AJ6-kbR42gh^1 zdOck5JCF3`FQ^_~!>g~UdNWU?+Oy}fYw4NdDasj7vHr21p0@sIUJwU#U;758YcDB# zweEk``aAu#--Gvi^Y+*G`;B&JTwrgniW}jGaV-1~FTthq3yS~wu5bCI^39LUJo<#k z|L)xE&i}@lq#v)*{(G-m{IB14@xL#8+V7A5;hW=rQ|mLF!agM&5ZCa1+3C2()N$A0 zA=@|1f2`x<;o7y`}b8UfBT1bK6|+HKlUV? zs&Cf|$06_E`Nj9}`e*eXx7wR=KCV`M;7|N1@hF^i2KL>VcbtV_3O&F zemXvQ`~d9>?)i9D`+XOlAK-Xy?dX&1IoeaY{lIavIAzb3FYW*2<8Z!y&y+8Ijni?z zY23>B-X|i1>=bA7e!t>795HUEeDOJ|eUI-QZphyJewsbxPbnSw+upT#Pw^_B=1B{? z-#9w%H$T9Ir@rfJe#Y+*hjm;%xZnF0r?m^eC&U3OKkbJ9d+UThyuSZ?uD8y#pSXGUey_}5aPJ@N{ee(IuXzN=sF+QOO?l+`sZSlL0iigS% zEuHci=N#uVe=UDBj#+uc>pr~V>-_ZjdcSM9UjNv2dw*FRP`WFh`753Ba@=~JvP1D` z2cvjFcF7br?dFoHBFFc3NpJ(fntz*SwyxV!# z3%{OU_~`Tc%f3_3vEQ?G=HVH_?z^k`ob;N%bvzE`xcu4=q8z6BPhsn=G!Ex}*IQRQ zJ{6DfRDa%in*DX(I9mQ=+Jocjcj`Xn8QP?uD^$sNA|OJT>Dl( zj-PfsdzhW1ukFk8N^hL+&hg4;9ME_!JiouGd0FK%?)S|5)PwX-m23S^?@N$w{grgx zb;s{oIh^-d2^(jowV&<#ou2lz-xsQfes?eql>X|IJ__*inE<0L#n;la2 zDc^TBugY%odr;oO)2)L}I37DcO!ibg%>Vb*ANcT0*BLi{wm#dd{!Mw%?i(jAth^jQ zy6+^7cNbQE^&j)w-u}r~9(G^vcy3%v{GUA1(R%>2FJZrXQNN4C?c#;`W&D7 zbbiYIi#Jto-EZC5b$6ZLqkek*7F|Ck-tt|)CVt_m_=Tx>Pe1zn`^o7~`#nUyT(5kn z@=5EbUEgz8?$6_+`?9-n+h={{e|Tosub=(dDj(T#`PXjC=PUO+`FCFXSb5Nu(^R{9 zji++Rj-0=T&p6ZZd->kuH!f6utA~X*j-{vEPx+Ug%GvXZcj-L&v+gr*zdz?SeeZ@> zulxP$@IcQoUQfll{$R=u8XundpZQMwsrkKp;cn*7-+R*M_y4I!{7!rRKOf`Yw;ua^ zJqP!r-@bI$N#A(icOJ*j_d|NlZ@lgA?R&lYJL?qs%Ddjj&+xeW@i?FPz>dfNaKP3X zc%S%Rx!=Oi{BQTYYFseBclHYlFCLt+^G7}Rl~3{qG~eP^XuW&)M^ujEe($Ps;`cPg z--M_60shK^`#Ju9Kc4feAAI-iI*J3Tm!t7NT%-Cr>U!h;G_LskJr?7?eZV+KT0P<) z)@#PGsdW-wFl`FfR5=ZgD{$4s@G`+MAs6L`W=-w(wzzi_o9`P=UT>3GqU{|KJc zcX0VR+24vwc>i3S4cHDW#aZ>F=I^}m7_j8?kP!7$vKEBfBeIu`YZai_SyvF_1 zTk-znil^hHV>}R-#1qf{^UlX3wbP|5#pUqI${kl_PshLS$B(ez#p8=Ve)G#a;r9I& zR<8Cr-*x;iRWACiQ(p7$o6bI@OS_ey^Ikyj5&Xh654Atndi`)e_18XK<7T{V?*okg z;U*oo512i8@1J`9v$ydu|3LMwzc;V^!Sx*bfPZl1`xmeKe{enD`vRT!oW_N?;fL4! z@CT1}fiFtmxMR=p{ypja`0~Fq9`U;y_oL>QjhlBhpZSZo_l+l& zj*iDU&C?3^JFaz5&m9MxU*OJ5{FVXj1_z5|G%Io=h{iyrW53hLe9O1Li(etWb$9$so{CLm!MC*3>f8YA8^=##7yeeG$jeD=_&(^)3-}w0K z*J0h|InqPzYo+*K_4=ygbg6OAer@wV_56jmeBvX`ALD7(m6dy8&lQ&b%C~Zp4t8Rl z7T+5WeEwdA`V&99ojs=Wa~)4QeAaWc^C>%$j`Q81o~vCt{ysHdt=&yedv(3|r+dy_ zXAjfY^w0m0W*@zm$GlE>oNsFW5KO%$A#-(=RZB|eF)aY zuA8za@!~Gjcw6|H|II&nYFtnr?vviB{-E@aca3vB+neWSm+2{|mDg!c_v@sWUC-X} zjKcB1!vXVu81FNGcHR55_=ZO#*faYJN`aZ9>$Al_nrRrv%;l!e2M=U zdwBOf4f>Dq4*lc8pIpb47ajLIdU#*g{o&)f!~fbBt6#tKKfI&s$N%>JzGvR3etPaR z2XuV>9hE++|E}MAe&49`pVi-W{WAxAjsKL(E8lzGZ|eC=2i0$jf2#g^-ni^D2lPIR z>g(`7^{Tw+vD^Jlf^*kTIjvoX;biOyH#4ug@3)n|XTFB>mA@}O z))60EzXV%PQ1RKZbX0u#2ihmx`Xj%;@xQoV&w1v494#k1r~Z{H1<+r3Y8^JqX8fzqI4?8#~{Ni0i})`R(Q3C2agZ{3z}u-1ksUJ?Y;o z?=;@%eEyyL4sP$wQ(wIwFYWot8&^`^&-<%aKd&0^QU2z+jT7U4_+IDnDE^4-bR1B9 z#|QDi%I(K*!SGkSP9sfag<2{<=ebZBa@!ako2b_Hs-~27d|Bihs2j2@n z959}ooyYx}AM}39A3xq#XnwG8_J8;vE{^|=`$-qSz|}8%P`}gc>V&^|jT+_^^;_*L zmRUs2mJSsaqpwY_dnS0|Nh4D{?kK^$MHSmwSAHN z_W7&*!KLgbKYsIv#({6$6zBS*E8KU6i{~%i;{EeC?fD;GTrd8&_XVc=-4K89d)3ER zI*q3|V4U#qKjHZWQsbTP@EY&F@OIx9F5c*PTrmG8;kcpvKk{P+UMy#$kU$J{AfHczUMy2&9gd>GZy|?YM$nN z9FJX%Q~KU={hsfv@CT9)ywdgZLFK>wzq`-(+T<_)M4YYkypR7Gcb1QF%U3_fxTg7A z>u_99`}e&Q?az0Fr=Bb9_ohF4%qwwf^UL?Eaq2JL&j0D#c>e6)raX=Fw0I8B5LO<~ z$LH5HZqs^R`r{n;^Xw8|j91}u+RIV#AC7tQFF*Hk=sO_3_hR4vzRP@npQ7jA(_6ah z51Y@#pUe|VXNo@v=ikRpp7Ws{J3nPl-T!_y|L*!YlW<%k|1awd>owzT>o(fHsr=}0 zzuJ%WTkDFW?r(gXzhCQI>p;il!+3|Y3gdYl-}%;C#x2LG=k%S4_C0uip7-2IA3sgX z|D^Pm{_@fIEq~^5X&h=i%DS%ds=RR$Ve={4d-Qs)aQrW=-0oaUxxM-Wo^o})`njum zE1uP3^&P9ai`m1gx=uQk*Hn3%_gDV$ zzt{Kuz4AZfarr&vCcTbR@z>7g?|1b0PrLs99@Om7eafkFXn*jy-*oaXiheF;m~UGL>pJaOT}hiiW;@0Ih>XMaj|oSpA@Tu;4M59#5w zj_Vd-<>c2vsdF2Zfm^g`pV;OzukArM|z6aeJ4K0#hZ=~z004pf93M5 zuj`)Y_no!hwt0Yg>KCrx2|u~wah%Q{aLNw;`8vM+x%|I{)jPG$EZn?)^J)E2$6wR) zoL=Q4{pJVpu71amFJbjo{+@s5aJ=isfp=Z;vk&*N*Jpj^sODjv@3?Xo@5*2L)WcLd z@Ab0!pUys}(y89{n|IYe#Q}?7e(&)b$E0KXhwuJ_rFZ#jJYdg`Yfn@^+jY+>J@^%V^d5UCABVph7hm6}@oN9Gr{Xidt^SKw zy%cZ$re}PfUG8_O)!Tl@-F&inqN`aoyUFgKII!1>N~YK3;#6ha_f|%@vQfMpV#xx`}5xQmy6%U<#4zUFMB$?ukgoj z$M4+Fb;8|0J@G8w*Z3SC_nRL6_wN1Df9Hz3f839X2N%H!JAYLBm|x>(`2+4ffxq;& z?)#<3K49GNzh3d-jOtf8R?l%ig`^S#_@aDb;6E!fBTH_J@u_#*%cmQ z9n5cLYW*W@o#yvM-(?gwU&jR-r<)&&|Hp67dDb`#&Qbf_zRT2opS;}{|FaLV--&Sx z?=8WTJfDh(KN=3uKGb+1o`MT157$lgQ^NFJ{uf_}H{mhm?`Y+dzmeY^N|$_`@u%M- zlrs*&zpegl`$+9)bo{=r5%+L@{BJ5fc!hK*7v-LR7#-g^9Io`oZTQ!{^1b{FalW`) ze1+d1&f@#AzN^~4QM^^XD%YO-)5rPWdON=IQ$Nxdr&Z2}+tz;y>u0F>C{BgTNWbr7 zNbl#b`Vv-;-9J02r&PX<&p*-pz3Yu@#}6<+x8{5DY2NqABOQCc z2(4U{pZVHUBF1}kUjU4FW5ye$R^p?&rCCZwQ{pe%t?>_8nip zs~s-5{k*RCU6cRyp}%l_?>C+|KfvuPPR&!|f%o?YHlL3p_I+U-CGI!=NBe!jK49~= z!~Mqp^85Rnw{nWR#mmfto;hI0&9}w@T`&Bs_x;D}-}g$U%@cbLKB?T6Ug6fc&c^|j zv-#T8@xI$OzrWAof97+gzkFDywZ7iI<>}o&P&$3bxN^ZAaK@wh%Rj%uhyU@@Y<>Se z4p{xiE8>6br*S=1e!{ft;vwUH<09&>=REU0{h;{*?#^#Zzux+Me66tciu?7S$B(aa z?YVv5Svurbe^|b^A2Hq#e`r5(ep}u*mLD$lK1Y1fe*b@X>mOaGUn~8o{?zp!U*&PM z^^)swuanMQC;j<5nTHqOvszC$KD7_6@;)4+b=;j3lwQY`Pv_@P`MO?geamiJXFjWT zW^yrcQudH+erOON%Ve6WMN8Xx7?x{;dKQ1KOxm!0!nf9&D# zwBqgi6y{s($?sQ3wb$(G=Py)Aw&P!a3xDm= zj?J5D&mH&t+H=aDx-UC@Za>YNDwo>NYdJ0~UgbWnW&9L29#$Wz@$WUP{LDA*YCOj4 zj+V~X^b5mFU18}htY2^*_n1o8;YPJr*WEeL`*>65<3q~h-cQJ{`LN?O9#T8{=PMk?i~pVQ zj=S%VAM;rI3O>26|M^Q@H~s&U_HRAcB=>pdS*0S2RU}Q8xRWJWqO7g0Zo6lInS%jl zPUb6H5FtZ`2oWRnpasK*g*FTsZW#U|y?*O@Zbs&MpSMKK9NjA-BV!+t5!d=hCcEO? zv)^lfg+KAvzTFr1kq`b?ZGC^`I@ODE=)arqrj;Xq@fYqxJ>^}wrF-Xl`e)(Zw+nM! z{MzNTL(dQHZ$IW`8oxX3w|0yJOLshXcGTy8f!cj`r`P|Hst56Fx5~eEo{m$c<9<{1 zqkQ@`mCvi2f9*lA9p|wyylu_@Dmpi)Xyq{pnXff4KEW z{7*jq@~NHoRWG@J^OyQp&+ENM&hz8gg}MKSPyT10Y=6RDDGoTU73aG0uJ$2U`@UB` z#?8*|)5nB7`#$icoDll<*|OH@?ZJlpYf*R&HsCk z>-H<}@xOid^ke+b`u1?H@two}YLD4#(azUS@j&No$N#cRIC`~T!<^;A2K7qa(LuW`-~&xP+f&~w4_MSt0Q8OB}Je|$(h>N`I4 zVf|nE9p0iJPL+e*-!y)D<$tg7#jEOHweNL)S0Bd?T>skhDXrd?Z`bwHGajr1*!i7v z^6Xrc@95sMGCM=x1BpwVbGr2lZtow&dz~+ii=XjuI4<7AzjTkr_deu*;#dErbM$Wi zhX?k*z_{PHALB=T`ChT{Q+W24&K*wocf{ZF6zjR$9x-r;~Je?5Qi-wkm;|LLzi_~VuPUG4vb8z*$G`EMWX^X2or zvHFiMzVg1@%GdWua7{dry+>Sd=aGNHI&`xF61R_@8uez@zr>+@HPW=T-5}xFCB#OLeCvwY7mX*(F0$*| zqk1^@N#f(rJ`&%%=99hY;eO+PacBPeVdbtI+PC|2pK`2RG_EO}b}D?=_2b;j_uflc zyWxkf+wV%(^OIVqPwnHmuls)K%-=pjf4}eZ;}iB1`QLTnkM8>H5yp>N*LluL?`ZsT z`Hq9i|MIr>;s^v0vsPo~TF zoom?-zTZFNV)A30()#bmIoirAU;5S2_RDxrcCp&`m8Y(~((%8eKYX^k{Tq8R|F`M~ z_7U3AI{d2EuktfhpBqA^;q*!;Wl1ZKl+3F*1!F~RePrX_o%(zKM!o4l)rJY z+22k*S6rVx;rijm4^B~gPrtrDd^p}->w9)pSG%3oqkC^b_4~>JXIFUct6cFv^~F8j zcXaP%jfa{?y6=p8?)ksY55{%Z_dh}N!^XSzvOkl4`f9&>{#R)K_WJ+9ILLHdCGPUs zBYo>y?UnZZjoJC(e*CA_744(4M^>)Z)zj^>j-8qN4}ZGzNab_?RQ)WzYkAD?@vm{r z@xS*~e1(sbiMROXj_b|;=<9nKPyNJU8k;(>qsQy-lzCzul*w)Zbe7)UNTr)+@>x|GTbd z+kfo4fIoe+(~A2^?-$Sd>HUAo_w%RwpTBXT-+$wPzxQ^|H@iUn<*%OMroCUzb3uIU zlBR$2bkANbZZ+OFz4EU14_Es?>nc3(s@L`4;jGuF@K-gS+;{YxBaZv|zH|HPaXkJlySg-2Xq`?jPT~s{6Q)W(VlL_xPW6(78YRF+9Wn?8mNd+@SI_-;5v8 zbKN@1^_>?L|H_eG?H+Ll<($g*^?hw9_wU6u z&biIft6qFZ*Z$4-HL@#B+5N@8;)d+;ivRFG@y1!DU%GKSyzIE8hyNWle^&qLhu2U0 zD3|NCfA96cxoVI82lPDRwqBv}zc?(n_9&jt)5>r6r`P(|UY|Yc1MmChgNw#xue$TU z)9Ul^!uq**^zU@*hy7o6_+R~F&yDolxA$etp8oWs%GLi|)ratvY5gO6zS&ux^YzEhj~ys`O?GN@9I$xek?c^#=lQIEkH5-i{W7~h&+97(9Ot9@ zzjfT_k9ctOSN^wgSH6|cxV!4cqvuuW8lUyoGj12pd;G8Suk88E*Y+9H{-??Q&pzap z|Hb+K)!Y0%We2F9uJ(V$>-nkQ{>`JD-UIkIk9v#ywSS2V{^7$vZYZ359o4?h1M6?& zgq;We3na`udAJ4=Y9G6f1awB!tMPe zKYjC$quQ6bKDC}HJdIPc^T%U)j^crF7<7;@lN*f-+r`DJh1!hfB(Z{e*gBPzS%i? zZ{hNX|HN|hj z%(@F#nST0c54>pF{pBNnTp%78XR!{CKhXN&aqCBi|CGPG`(A$Kh$F4sckO!Z(RXTI z`H1~U=~LlnAJsnIcxZiOa?T>XqBNYAT($U(egz z)!*SR<==i^Ii#-~_?7yzFT5&ye(u`k)VKUr-|@e3K>eZm!S}S+c-|}5`Ivj*)A7IQ zwY}fXo-+1<4{^G~crj_^fFXfcpRi#(^r=It@ z$B|lpTd(E+)kRzP;fdCPIJf^lv!DI-XMJmL`8ay)6|d!5`Chg9iCgx4rvArRKgWfY z_qf?FE9dm^!Pz`K@Klk$cdfoH3e9wOJZco|#(D*dY zjbr;Zwc{_noHpMHK1H~zQ(33?uQj?0hd>dL2{l}f8;N{*Z#PEdF%n# zkM8BSZgBsHIu5*k_2K@ndaj>or~1QbpXR6dpXZYGA#MNBd&%YBenPo^@hnH*|K#)H@2{TWfA5X={q#*cAFBR3|GDo^IDabLfAUMsJ}rAc{^jS`x3#W6@5|%HvyNJ) zUHPAN+Lh07?_4hqIQOfH=j*Ot!+)In#RI>1toMs=9Pg-j4&OWe!hgsOKeS`)e)}u& zI7jQgseR%n56(Dc2cmxL3)AXP`>MyZ_W+Ln+4pK!8pr$5n|)tuKKYBsb#^n_8clXPj;5&`^x!*>%1-d$*z~b_?`0SzVayfxbnUFopAcc`}a40 zpLu-$>!f%4zs5oH{FMh)p8OAg#hZMO`KWdAmH)+E_x`_ezyJ2UukXI;=k@3D?dE;Y zv;4OXn0^1&RkVKhUq6eZ_1@*3Ggy3Ezu;qW2Hec~)bithtNiun`nB@z|FXsdUS2yL z`_bI$UHeU4A1B-R!2z{n=V`lcJdMlM?{K$I9`PKle7@u1y@UG>@Zo;F@2&H{p08I9 zXg&}h`#$^?_p3i1&R4(Fu5sSEKc?mPluv)bvD6#Rm7Ubo^NszK`P;e5+=rjV|GbCK zeh2r%_4eMsfAz-cdY_;51deCFYkv3tL!6IYU|fLWK7aE|RUiN2;hrjg_J5!LlK;j1 zaJ=&KC%@E_|H^eO$G9N7KF_1iALn{q|JGCOU*dmL>8h8$GmJm|$-`}4y>q`i-xE*Q zr}j7M+j{~3_N^bs?QlNzjsMk;|NZm*khtC#k9hDo^C2}ZXFnLX%isODpM1spa7u3b zC+fbbbl4Fdb^UO_!r^!EcD#=L+wm`a?(7JSd-jT7KKc#L=Q|ee!$0DE*KpLj9R1eNaJ3nh(X#M`)_lo)3XUor(H)*eU!#H8~g8Bo0_owWF2a0Fu#3!xm^Y1>-&+hLWf&VM;Ja)>;WnFSr^PBI$7(c%M zVn4=>SIzx*k9;m2&l~Yi<1O{CQy$lG0RDJo_JHw#SNp=lgUWZ;PkF0%&nwsMt8kO4 zaNJWognO$0x-V7!I4yVkf_SRHZ2zdA@KaX&x{jPfK z1g)cM#~;6i|LUgf2yoN*U*|vW{LlaS#>4dR%*wZNPAji=s+{?&KW_ah|N1%ZSO34- zF&D0MH$T?>*M-0cRhXV{|7oZ8;ic<-?$wL(tG~4;`!MV4qj$ch9$cTQe{S`5)%h!b;ZyyoaPBJN@EW|G)iI?w>#0Q|sctdggb$?|jcU|GpEU-{F6r5A@3Y#sPOe zwe*i2+u?iezw$uqsm=w*0pnk@!;6D`@!WUdesQw@UsSx}nOgsivt9jneQF-C;T?Cwj)JY`*BeiR?|f3op(G`pwX*Hw7q*?m;L zaWUs2ujBlT|H6qMFOWau5C4nfamOWa6ZQgE#s56tQu+Mh+x#Ezac)9>ouh5OxL;Sl z`KK(mi;sO*@gAN1A3Go1Zya#C@1Jsek6?Ca({Z=MeKGDg z-MWg(A3NE@|G59#FWq>O=actW%|89Qu4 z;pA&PPlVi^N;^^E?7IW_mXetgpKp+_h|V!_I>r& z<_DZyIj-DS{@4Rfvp4K}JN*yvYfsLlT>t7hf5ibkx7fvf^O5iW`J(er{crPYkL!J( zm@y`P8TQMs){@Tcqw?dS48>ypC%?xQ~4f42jS z|B0WSrSaQ!>l)#Wo1>ny>;$LkN%*Pw)X$B*Pi0TCrfYdHC(#g zhu5{P{mDD(`R=;s_rl>R<~dy9^T)i1gW|%|Nj^7odek~NMF2ExblDiag!>~wchn}ZtYR|?;LRa?`Yx7zukB0&v>@KsT}@a zs9#+Dm%e5?|1vn@$>2KTfDPtoL#c(2|Pl5Tse{c*1j!uJQ-Ojpr@j_x!1c?vI1Iuk=6mz37v_IL_+r zmGh1Fy=vpw_%Uwn+mCvV<9^0%cD$Zrjr(}B=f3uwo_LDy+OF=KTYHt?qbqm&<=MBz zPsiKTcl)QidQS3JUsuKNim&VAZ&Udw{Kxbj-@;ozxX-@-s;~K5cv}0f-yJ@e|NXr7 z>8HCdRloIzyL!H_pVIYj<52uZ@At`X?VY->ao+mSe7N{+sPDiuj z``tHA^wVGJ&!74F?I+Jsf4TeqtNrpX9@p`usr?F`H|>1UmG5=E_4<2uf1RTp?|an` z`IvR^Hy`CYdgo`KKJxd<)9^j%;BC`*-Qj_+?#09Zo6r3P3kds+bpC}qJn+i>#trd5 z{^{4}KuPw*L=A@+cqGENFJWe^xAIf#y<8_VOcwZb)Z;AWi zMa>&m{)bQCH`ULH=N|t_SAKB4>A2rjT_6AJc~E)3_r}Sx+l%w*hwS;LajWBQ{dYK@ zmObZ*#}l*b!hMwE%J-B5=bOL%87?%f{r|_aUEHt7jPu3)wAb-(eOCC|YwbI=&QM;@ zt=hGA_MFLIKPaBG_rY~ev~j@SxEME8|DQa$U-ilD`Klk>`Cs+--yZwPxL^8TAMNG4 zApiBzF2>W}Kils|zx*Gk{@wpMo(tZ)W1rc2YUiq4ub)igfw*}6h_WBjkM@7-o-6ii zJvaAU-E;EQeXZB}{eOShReA4T_IT>=QNfRL#L2E&JICLQ!`lC-e#_teI9ucE#M^rW z4+j+AxE_7we{)Y4e!TECKXbq4>&gk0KYPaIp1b;K z91tHg9-Wu&dw>7iqdeb!uADgD_q z{^pzeH=pY`>&Mn}y)W?2|HO~~)i0@dbMO3ec7)j>ny+>~WczIU^24>p=ceY zdmlmPpOv%u;b_lU_L1I8Fn;)-9{tb%g_XPfdVZA8l|wlzSDYYwM*EBS!8k(U)rb4- zyQbqD)br{+xBBNl#TmKT-xR+3`s~p!%U|`VU&V28s>WUUeC2;TPaFRezy0A9Kjog< zFB~4wIO5h``5%5^U!q)ik#WzBm$29Loo4xA|5Cp0yx0EgTHhaYSFfl43Ris7akAL~ zI@f7@&b{-UJI9I}o_1C5*Z7oQzNY$xcF>=%?X>n3u6Ek~%==0Ue^v1`e#KY%#rvUM zVD(bD*59c5wSJ=3O{@27yQrV5TfTG8K5ZOyiUZ2;j~?;09@KvR_pM&`{gT7WD{u8N zj=gzI|F4|Y$NXvc9Zpz1AA7=Ue^9^DuRrNWvlkwp&5aKUH(lt(Cy)IKe>|q^>;TorzO$L#seEg{sd&5Z z{y&d)=5PKhp314cSMKU34kuss7y9+oerxXWzPVp@*Y)f6DT`<4Zm0QwoZ~GYAJfJA zF+KMwpMG~$^>*zS`rFmL>+^r@@2;!AqqFzyds^0|;yZfkyZhGe>E;>Qd6CYuob~PR zJlDI@vo6=(t@rIGa%ZnM9=P+t@j&&QeP6ow`>`)7o_HU7z4itF#DAgdvw3+iw8eZZgyMw$0_g?=M|4O zuV3?HzU4mp)zi%mF#jJu)q3ij=WJgR|GU}~wl9ef;*Rg}lk0au^tags;#c+iQ;f~fm z<9y?Ocpv^Z?#Dj=ysu;Hh5n!G`QCn}=dN*(9m{`t#A7|k&5qDI2VXy`KlZiw?r?RxEh zzSmKC>OcBJ>BkY{jlDN;obPD=Gs=f>)kpoM{{iZ+{Oi|vdt8q$-RT#P{^S3F${Y9m zoyWLP5O$~WubylBZpPtV&C7=e;%B{gkA2Yp^q8-$r`Y2iJsd6`H~#1U{P>>t_8NcL z1L7_2PxZfl{@{MD|NaLW_mf`seChx6j2D;e`OQvHf7^QkeOE-j)9eHF_g(iM!Q9Hr zPVTDmjep`_>PbKJoQ?Z&Xa6^Kf8nanFCOU#|K-z;(7#yozjDCO9@q0%5AL6S`lu)O zs~2h?(Dm6J&W`Z<-Q&vdxy`Q4dIaa{|0){S<96Qqs_Y-R)9TrCo&DsME2_`j@kRB? z9arqVj@;_2aEJThjqKL=f5;PyXYq|IPOU%Vk+`M&cOKa~&_3M0?5gJ5!y%ea?91h= z=X9J&eY1<3-5|Td&e^`I{j&O)echdN;YQ-8(p|o$=EL$c_1=)?Z|_ZH_cyKHe&emY zIBNWlzj>?ri?1rD`tU#A(ZWej_;lZCDc|N-yb!;heW7|0pK@3)SDxHg{?YY#kotO! zpWE}Qa-`CeKjVkLdZhS6+IjJBJ;s0WRiD~jdhVCM>1oGt$#ILgpm?pnrt;HzEVYlw zee4dn`NtKC$G(Ys>5Au?kNKMio~<)ikfziP*0zt#DUofj{E z*?Cz%a%;!w@+^+)sS$`+9DxKhN>f`SDx3?tO*he$(3LjN@^?>Be>K zdL2KtgTP0#{uIj`X_(w z-ac^al5`QzW3B~F#o;BHSVMS z^FQC?u08JO_npV#&pxK>dmrzy1H8t6Z9o3{SK0qaW(a9{cpTp_uJ!q z^Pi6A?LPI?eb@6#+I@C)wU7Htf4b|-&t0$K+n;0)IRDr7S0D99 zy8e9n%lhx@cXf6SeDWKYimy=RJU}|Hu8N zoeLI!c4NKg&+{M-n7yCFO;yx<9quKYx-#&l%-{ZppXa6_te6Vor{l@*K zcmjX?4^PZ}_+M`633s^PIG}yXmk)pS{>5V-R(|c@#5WEY|NG*>0c#)arak`ZS?}lk zulN7iAOFQg@BGhwKm6q1Jn#F#oBrsg?*Fs5b-|xK!r@xt!~YilzkAj%d(rmc^6$RN z@#DAklJ$%7_53s*o3HjhnWM&o{+Qm+2jhRu!{cy$SH${>y_ER7zVDiEUN%o#-*9VJ zJS4s`jr(P9g@1?-C%mR-9mzc%2YhwsFFo^U`;fQ`uCnyIe)wPOulNPKEByrTo9buy z)$IRX`JesT_a7VsFTerahx;9Mj`#3B;qk+%dXM*g@=W)*^N$naf9{ixbz+=litj0J zc6ZtluX$DNm4BR0f8d_~bo_AI`yV<7Tlk%Wo&DRMM~gR}slS%qEC2Jo598H$n5We@ z4yOL}4}7nFqW_HpJ~I5M&v8HfEABU~-Q#!lZ~5n;7had0@_`rp039nN><;LbBwzSQ&6b@iHmZv1_2+z^Ma|9Wp<@9)$<;<4G& zmXGZ3aJan(@SF#>?snbt&igOpy`_Kb_8!&z?04cD_tW2IU$}VXOFGwhaKXxZ>=Lz? z`+w~*%X)vGc`?q1v&6&hiud$fr0TnKx$ej1zIfUJ>d$}rw8Kx;#~(l3^8H6ojqe#x zIA7;zU1u*BAAFDhbxv3~>H2?9e$qdA#*6=D|DW9;`?Yvsc8GYA{Ihess{ARhbH3^! z`#aa&vV-OYU_;8-ngZD5)S8W-Lmf-Pv@ViPvNHQHn{D>tc%8V zJg2zrEASuoz`}j{N%o7=(sf0kL@ zZ>OFYr9ZyA_gHscUq0{cxO4w;K=;?a^~1So{q8oF6;vE+(e(4py{kr+H{e0!JzHoj0L49B2*Y4YI*}rvOtLGSh z&$a4ne0TMGwEN@L%2)VT-9C_(j&@SMwb$ka<5@d4Pxam!ZqFOqI<@x;aa+ghZ&T}h z^Y&G(gL41qO|$pI_1gD*`BeYZ`@jAAUc1(rUp}8}xSr?Rhy3r#17Gjw#{b6C;&F%f zaew2Hu5+;X-&FX|9&UQ&f%aA0)_vLY;dWR4=lXG%-v9Tp5A{Z^-n+N>K6|dWg}3gW z-t+sK|7$tkKY#50EB}*E`>OJ({mPsiDF5sP%`?UKqqq3ufVdzo$&O6@;zRAvT0e=W=jHkT z)q6**%d>kjkE>^VZYurwo9FBq&+QAi&9{x?aXS1Xdn*3YZQN1mnZNZ9;qeRcrg5CE z;{o!a+#gf%v)8)nnOEYG_ABMD^UTV3xJ>2W``r#V8Apjb;VRkd#ierhom#wa=T+l+ z<6Gl~_+Ihg9nP)B5920yRop9kF7KQCKR)|kKKZ|W^8b3M(f-LJ{3nmmPwkI!v~fr6 z6i>|VtMZ)l)3xJq>xWl+O>SJN_7W~`gg5m6P~U@5&$}xFvrE$k#bufw%p`$3#8UZ_3YS3l@I9_Bgroa1=odh2h>s~@UY z{ke2=Ae=tp82NFKe&*U+>Msz2acm>ESNs-T2)%ANBMvpY!jy8%}6G z#?3rWX9sxafBN4aJi=Y|r*CeWJ?A*!hy2g@lg?Cn;yb$hOv{(2<@LNU_v{0APMGGu zbHL5t&i@*h@wT|1^x}NRU*S^e3LmHQ)cn`a>%aEKRS#E;FWSere>~B7VD9$-EeRQ*j`?_^iVKli?S z9RK_Dkw5DN?}2n(dr|qfPP5*O4_x`5`Rkv(#fSg7fB)~|jI&#;e~53K?;ld-^?elF zNV?{q@)3_1&oJJud_q23&*3iegEtwMc#QRj{k(P_w^{hbb9bA!q&rn!Zu8bv<9^Dw z_avs)0qVv3d5@lYTm7Zw%m1_Ac+6)<>k?)s~K zDP8^Ss@93z)_GSuP4%W-v!d(*Y=Q4 zZuLyndz!!URPOcPm3Q{a>H6*Zr}?0C8V~9(``+>7;?-`2yDR_dW%V~Mm)d{C%iiaI z^3nC__}=*6xZiZwm(DrQU%QTTR$kAy^0)Gj$2SgLuUzwwm*Ri!8&43f{;_nYiLBINx2>yZx;BM>yk)<}Y9O@Y(_B^-PiM^^}*J;@)ft6{`S-T$)la(d_Q@r@^kAq`TyWe-{*h0-iQ3} z(?@x~^?VK-#rycj{cuC>&mKIn{IZXeF75uK@wgB9AAcN>T?l?>{rTCO&Q0wP|1r9F zia&ci=`6kCQ*QCTr^+3Nblx~FS3dDl`Sm>y{@;Eme#7n$Prw`PC+~bRK3Khcod1dU z+s}QU`pu5>%QySKUxoi!&pZFCUw!pv@0Y&vK+pd_d$w2SgY}o6J@5O$+xJC$XQcRk z{wNRr=iG9t-mJ6Jo;N*DjWh4Tuv&&n;j3{`%|t7E0edS$>wU)ILVO<1g|%PDv{- zyF>Nx-=3Tz4iZm`+u;_@?H=woJGEEUp1u=&)$u^zvBmA;ecI=6u=+tf4NsI$9FTtN zso!|?*TP@9WA(yc{T!}YxjuADr*o*d==C|V=Y{nY9{R=ec{0Tx`aj9@#k?(iIy<;M z4-WsurSQb~>dsv|pIv^{JNwGYIxR~yL&vC$Oe~XvZ-*CV2zv;Ih_2qf^ ztw;TOPLA_+-Fac->F~ZUp5@bT{a2^LDU*%@6chtXUxobb^v<|{4%I9z2)H(`J zbT0YuMdgW4&i?P{D-XQ$Kks?8zKH{>-|YYFw_5l7_EYUYaH+KKQ&@M{cUU*Ho{MMl z_nl=NQhwu+{oh-7`HgexFNK@koxO>=QsX`BjSHYrThMU z`PZ*^zWK_zDtGzjKaOc#!0mZjec^t>9sbuk^f#a7lnyrzN#%2jn|iKxj-&6AnUC{# zE?ByEdoBH?a>uLm>o~^YSFK}bPkHA*_H*TbJg@eaPyRT`+Ce+nCtp=Rt^HE%>b}*_ zskg=Z%9GY^ckZG+ujP;qxANfwuc{vSE6-J5!>xW6AO0s^`+e&Et1kSjO79v@zsp@d z&3D)9i&uXsf8$AqSG8Y?{~eBXzPsVRQ!lHZ{a+pT8~?K|F%EoZM*GiB^V(nPH>du8 zHTRwW>F3I6y(oWE{*~uyr)E5lhi!j2PIdlg$90US_|BdG;S2oLPwVqI;P{{a@#JG_ zy3N!xkQsd)2 z_wnz&S=Qr)`{74b`8{8%hjGTak9}eLi8!nJ;Z`2y)9+tZ`ITd8-)0|^wjUd}(+<^F z;pd*ppX<|W{qooUq%Xee`*lB)|E{~gaN}`>UpeeIyZ*i|+*CPh*V&bhGsovVcU-6S z=keC;0F9&Sb6oInz5MTP{XsnVT)OWFo&BNlDBSD#?KyFtp=``(+q9*uYW`7c$we)aagzpv+i)(3y~ z>>uYnfa8ACpFi@+9xeX&)w4h8Z>^WN4!iO{D){&ba(s`K0~Zo(=g4%=o#~!adp@yC?Kw3*iT~9P;(p%S z7{AL76c5C^*!$@R-+$=bY5l`@xLp7B$GkmNk)F>}_2T&*|MUD-?yGKnAir1t!tFl! z?fKt$sbArP-Wz7z*#Fi)d%k#H==b{H(d_cFe`ViVK9A0>kv*Vs=iIFIK>Y9TA9jNA zL3V=rbNp|5-Y2L&uJ0RcJZBH6|5cu&)zjgA=HIxT{a5yVY3J9Qx5odjUwxE(vc!~5o*%GdZ;YW?nh<#V6@jhh_q zxO&(*=h;!F_9Nvl{%0O3-~a#cKl4i*(LM?fG=H6Zs+Vz_?DW*1^|kt<;~MI*dOQES zbI)J6dp%d*+K0dTnQ9;VOW*?%Dl~`;B*Pe>e`9 zn&<2r)ld7!al~}o&pKWF_Jda)_nYd!wa2}^4zInp-)noRANT*Ns@$uOYr67Lecb!+ z>6gd8Pq^x{^-%ZSIk0tA<*uIBpVZ&{tG~lv?aTF#t6HyE$BhdbuenqGy#0J?zU7v` ztN+5OzuIpa=d%vU|7iJq9jBYeKGfIn;#03zmH&Ib;-B){dUZT&9BX!t)0O+q?aXiP z*Ivbcw{vuzzjEGn{&7m<)%C5b?IUm$^-tx~y7=h0*Z5N0NIvWv?`mDu_ejiF#Z&y* zt(&b{(Y+22&&&h6XZRFC6=AM$7Qpj>HOP&>DO z9q*dj&o)ltW_SMPzAL};|5f|#)o1(=PmBXz?GI{)IA5GlJ9AI<``RHj4&Td%{Zi?6 z4%hwH`>gxB?|ts4KHs};zELm6W$nFs+P>=8uU4Pgr;htse^;;LfOp=feO2k-o^dWc)H_j7LSeY-#D$lsm+HlUw-wl|BEaA+ebX!GdKOKr~mh#`N9F)NB`tmf6meN z{O*6l&5QbH^A}a$&OJ`gI56HDZ|TN|@yg%)PB-uO959a+zjaRWn= zqm|QrI9l_2^KJ3T-~N|bI(N6{Qu9djnDRDH(aJf+rP$@+U(#bw_02~^&hv$UQherb9XI19Hj5sPNjdiSbS~YGftfc=KqbycV?E(RdK^(Pgi+zU+o(o z)%>WZ=K1^k8?_UEs$Q(8ue#^U{P%qD9BTgFb7v}^_W7OnmR{wop1rTH_NVIG^GUSL%NK>AyVlPd|V9=f=k? z&wu&sJC9k%b9EXwa~|6M>hGWTjTh?Q=D+MQr+e?FaeB@P*FN#&eP?9nc(W74>ksE! ze^wuTkHosDe&6|U^&0nc&H!ie-L1-%oudAIxUcfpKjVL%=i`2qn|&W1!=4YP8~5w| ztH1v?@BZ;q@u0tch8NC#wC~l%55*_{|LhqrKC*b5H^=eV^JQOn><`7mpWPZ>I4yt6 z?>(NrFXDV_eDC#~GI#cK<7b|e&g0(g^0L<(|FbTRmyQ3izl)C@?x+6#<-=cjalqVv z^Hz`XId+!nb@rC>TfN2c`0L+zpQrD?e!6?Fp?E9TxF37P%IW*c(mUL*^ndG_Z+x`; zd%vLg|CgKo+JlSc|35$1M{&LnxnKV5l?#UhTUW^s#U)#ZWw+*e)w*kTZ1UrItsbZH zUA?~6^Zf14%71o^cuD#FdexsxKh7k+^5?v)bmgz{dsMq-XGg6M_ufJ4@9w+WH^%?2 z_HNe4rL*+2Yy9NVpYxA{8W*`+zj}`1qR#WO(@dM^t()+dqsxE)pR_(Z>k#>j16IGS zo0tE-KdoQjG4dOix${2tclBR5>viR2hbZ3hI^~&Lx%gjI|KwJWcU?WDr=8YbAk9al<#=qwH&R__MMTwFD<<*Cy>9n3xDT-uIC>&b${ul%FX>@K0f4^*ZMvA zT)6Bu?GFn#d$if_^?pa(N`AbbOE~L{(!bk(+OO6R;?34|+;|RkpLS*cmwWwX_5Qwk z9v5#~|Ip5N4zJ$I*Z6Yvr=H}Ws`rnn{!_bry;=_xE>3El!ae>+rN_T^+bN{@Z8neTeP*mj3pGwEXV9q_exd^FRH&cAVaM{oqp1g;9sMDWFn#Uk@>~BJPd)sPzkYgE{aJfV z)jRjA;&ruKif`nuzo_rm@%=jg^_*!vsU2EJ#QDtUx%*D5|9QB5KlZA3dq4T?dmYsO zxVV$|K1}rh?kWHNH~!+OcvjMIp4vz8pWUDRkaFXG)PB_Usq?qa8BhOV z{udwoH;?*mvSj?L*_u z*4z5e{wKA+Fz=af&O9kS_EPbZ#>xGE75!THY5b&k`S1Um(;!ae=QqaAa{0ofOp&i9|He~hnv$o*#PvC2e!jYU{#4I6-|Q}xL%zQ8Naygs`t|CYU1%II9u)t> z!Ei5JFpc|N?fvjR@6Y-2F?)F4kN-{U$ML+Kv$=D?d;hN;>Nom%{mwYRS$iJ5o(J%} zs{i*~y7O`Ke$OLXe6xT3&yRew^BV^|{I7CVZqIEQ7zey^K0J*(KBzwZFB)IP0o5}O zEM5Nxmi{@9UA^nqJCAPs#{ud5XBX@JmF!gGv%+cD>`~w2f1R)VZx1`g>`3FB<9^d) z2dbXg_Z_wVjNkqKV}6q!)o*|AO>^S~zJr8A{kum!uuJ2{{n%l%zso-Qr;qrI&)g8z=Z5`$3#gIpco+?5Wl(xqWBY{MGk>os)g#eO-^g z9q#8GbnD;vUG{&@fyU8x9=P+m*YAgPecwIadj|JilGHwB`BQG|N#*s*ZsB?#qH-3#da#aDKI^J@;BP(hpWUSQ9pbs=*EwbR_}3409{KCKlJm5HFP}i8;|;nyN&D7-a}|Twd>*)uJgsUkM)3diqq{p@;`f~iyO&@{z0u9 zY#%^?vtF5AU&lT>U7&^j05J&#m&2 z+81yi%|1{%gH&lO0 zKjbp_jeK4?k9Ok5W%8f>-TbF_`_kPvHJ-cw&i~%ySHf8bQvWBV=lr*J)c>z4es1eb zT0K`DZsmGUPySX8{i1o@KB({Zi1(Ev$Nx@!u3oEm{?~n=^mE7kq{}`3>HL+a@Ut(x z^T6@Hk88Y5yw~=B<-GD)yWIKjYdHN!xaqDRclEdWG+v4~yFmW;es|}8%ImszEx+T# zvjaWnfL*s9yQ=lP`l9Vu;xqEmeq#HW`H%agU-8v z9>yh8{YpGX&-*T0AMf1tzI$`Gr;_j1!{dQ>^&G{&tV8f3&)cc{)T?x+`a$KIp8ag) zTECgS?Ww=6kNZu#uD@3PyS=XUHh)?@w68F)<-XU4{!qP)JDu_?k94NWIbIhBxmA4QaK)#6_#1!J_@g-e)one%eRS8C z&vCeEJp1&&JC`<}YX{@2esS;r%Ef=GehWYTU;Ax*ZG60rQ|`v|=D|Hbt#7LLblh+H z)$@7f`<|X#_#d^e$LYTDIN#SgqWAT&0BC+b=YBurf7Vr>Kk{S0_svK6+|$GTtjB!s zqi}ID959|YwN4Yy$Mnko%shqr81H-a&(3b~zsLQq{10EVj+?sgLoQf(%l|q5d$^zS zblz7yALD&XcN*XP{JBq)?uYy@zG(mGTroR9Uy92f<%`F@Q@Y=M+UH&MXK(&fe9!gx z-uEx6UpOBeKl-z0KVkou|6jiKo4&ZqzBQIByye69B)Q~8{ZBcAzo^L_bQ zzSt{xE=srgrulL6>+AxpQ=32E%J2T^xS#(A z^3M*CJ={rW_K3!F-$_0k@M`yGoX7X#oARNY+6#}nYtLQw)$Ie-%ibqU&%E7x0dX(y z1-#DR%27DnO8U-kPix2QOWD1Z|Ep&InO)qm1HIdY;={uI-J3nx-+lJo$LRC?_r5{v zr}1QVS)S|bckMs9)r)?mKWrSNul@4=T|VVwZ^#aB{hxiHekQ-(o9KD(IoEUl`d;FA z8V-oJ{pSZ4`~1-!>+Iy@ASv%{Ko|=4=!k3;(dglKc2tr{Bp-H&N=Ve zuk+r&{>WFnQ-A#Q@%)a{{qv`e_gQC{=eW&#x#LF1-}OIyyZ#4HwH^?j;)1xD^TFPS zL)mS19vF9w^ZerBkME^_{N|5qDd&~{)$ZB<;e5r1qxql3JZycj_Y21N?mSI8alp>a z;%$HPh{yLv`TM`S`{GB|J%=;NFYYH_drzQqzj3hC_mI_B_J(~wMSbkM#qmGu8Tr*; zdVZ9D=tS5 zEu3*#JK$f{Ti3;NcqVRIdE$QRAvd0;KH_pm$Dwe)INQ;l+vPj^MdRx|&Ly4JpGUi| zdN6)UA0LgE}#{j7hD6Dr@Wm&g0A+CJEI`{Me=vCqrB`tASu<;y-r{?uFfj0@W*a8Hdt z?&;}A^(W)qby|AbsrpN6kMgIUanAaS^5K4!v+|BlDR=&d`{l;nDg3zG>{Z9B)aoN@5 zxNPYgFWtX#q{hS7`5TX}n`i0z*U`9{aQ1h5kK$4MuknG`sE@0v$J{ue`W_z~_e=dh zUby&|eki^7xM};$*;B@QrK?@_zxP!CtUpv<`LAA%)-Q@@;i+&_{iyp=1({>c6ey;x${(P1^?)-g-^F3qSSz z=k|P~b5Ga4`jzyIgR2@>wcD#5XDjgRgxobe$Y^-_A(tNzlucy?2>t7<)L9co=n?Gwho#s$ZT^oRBp z@h$zVeZ`%psh855Za+BQH(po&Si6f)zO`TZuNT@>96>2l}IQjn~r8EnaTg z`oD6|y>d=he%d~CJTKMX_)pa@_tAyl{deAH98{0-x25}W9j8pCs~lIY-DZb3?l+D9 z=@-Ji@;>`^{zq%)wYPdIzlW1nkJYE~$W7I=d7SEx)qCI79tV6?%Xf#pL|?-pKw<`xcG`^ob6+3y`)?pYP|1b_Z@%f zeessxtA6^Z|8G6ludgb-*K&>fP3;5KgL7o!pR!ZYe$(tu@IUQIrTd-d`Q5a3|FgI2 zhyU^a-h=zm^M1g&fA;1d_xtt7{;OFLcl8qkDeO{{Q}b$N8+AaHFH*-S^SX{M&ro z{C?)==70H;U+J1JX!A<*Ab0ca;eR+4J4$v_Y3;y1PJ8^| zaW3xqoBG8ouWG%2&drv;x$95tJM%v}u9uw{&X#@O{NsZ79{=foeDE&z_y6(1oxb&$ z&yU9G>WAxhowrfH{I{;e_3GDq4>vV#^ta0Cy8G&P`%d4TJF`z!9^XCD|GxRS|EjoK z&oA|5-~IiEnr*-LP#g>gWY5T65dZTW{rr*cl>;6gX#If);(*x;>eunUY3~nB4)gyP#3FCdPtLN`rv~YbNr|;X?_jj(?`-#7J%#ObA)^~*QKIiEh zKfdc+yZ-%~9V8CuTy5Vm+IimD`(3%8{`S*1&X-#E{^hg1gu|2m_{|;vv!4BTkMyle ze*Q?;`YAi@-+G(B>6QCs56J%S7mw=w^sx@cwXEN>51jj-KK;#$u20P`hXc0%$Gxmu z;$!1#os&HrFt_#0!vD=9zwENOm4hm8Zu|^C*!kOWJ@$8a^q)R79$5bGyw3W+@}=hQ z+`su$`y%c*Y3nWjZ^<83AK6pRt}^>g?Xz>%S9?k8E%}&Qj~~0k;;Vcs@8N;C3O*8l z!R^NRrtXjDP30pVb64xa{IfgU`wjVD)0a=~srK!9>N(f-w06XA=He{-ZVES$Qi}9N~zf;cY^Ft2TedBEG9*e(riLdI<+*9j=+L673=Wm?V zbCbX4)m4orZu4bYyyj_c^<4PUshw+=Yq|7OZuy|*_p6F8_u*f;@85TkUc72ry_-kk zQ?H!ld>{9^?$z$x=C{@#v-jJ&c-LDmTfd6mzWA!vC*0O2^qY_Px<2lvKbZgG#rDJU zkM~WL(|mm`uX&*U6{pjG=f2jHbw}>{iTyk`PDAC}eN**Zy0md#yk~!$JN~ErD_`Z; ze{xUn`vmLy)@`$!9RHhc9hZK{hsOWzyl?zZJ+;n@qp6qL_0IkD!~9?Q-~D}w>Z9_^ zUUU3@dd};wpOk)lO8#4Ku6(KIG=KByRrUMsAD25kQ2hD_RnF2Icf9s%^HJem`JaB{ zK3cxU&rvAxf9c%QcYpcXdcS_6 ze^%c6I8=Yy$9TQAlXUDq*%MS>8>jUv{j_|%>Nw;n=gOPTe|mVE@~gkA>SwuUZ?|*L zsrs$n4mXp|>Gy|+%CGWL{paeQ|JrXV{ldSm))A$*@5HP;+b?#0(EKG_`^T%^&u^c6 zpL&$Oa%$Ic`HffeT=|2DKy8imTZS#5lul@G)tCd^0jd$w~{bBQ^{F=|E z<|p&w6u0pFnr7$6J-fg0zVE(0?|ip5j?}z+{a&wl?>x}RGS6Oh_I>Z`XOH|@kA35j zj(re~(@hWmE8fG?K7Hi-&dsEI=VkBlztV{#UU}gA@k?)Zdg6B<-X?$93m)C|^d6sl zmETtmIRC=m^Z!~Nc7LTe{W$-ted2$84;aV&%V+OHhWM}i?~&cd zy3KgduN!Z74k(?*Me&+XuJK#n{l`c7ajyUPTo*R4nimR(16D5KydUtm^KZPq@)`M1 zp3VE^d;iPGuX%?yj~>OngrnA3&Y^z(s6Xc?Q~uw5<8I%1)58G|{~M=^XY5?#s~&zQ z-FTjQjo;0VZ{NvHvf3+vKdW!e;J_yf6ZhC$0oafN} zf0%K;_?~%u_MvzFSGer^aIWV4+V$|h+I8n_DZ4n_4<|bA_%?s*+JY)>(AK*-ot4J-vzPG@?8z>=KH$Zb?)p9*#+W|>;%90=!f1L zNV5ynztyXL|LYH5_N3;{deaX{S9dBM&nU(bO*D&om4 z-EaKqpTGY+uWMbgbGyxRzyJIn#dF*LDXx33>Sv$)-rGF-yHEAp|BFX@zT^9EANgj_ zH2urxdlUcpj6;J$7{HLDGf7P3HcjceX4l$iw zBkqSEP1*UyYvM=qpYA^W#eMoq{A%A#NpZjY*;^`q{PlddMf+Kg;kD{J`$*3-;q8yR zFaBpe%B`L#`?-T~z7J>7&+wbZsd$7dzW9y)k~@B5KUKJ{AI>x0Ll<9K zdz5eSbBiY~I9_*szq#?U_s_)r%=49h9B_7i*|Vw#*Uf*WH;#MGVONgT(`)-zKJ8w( z^@sGe{}>1N_*UOo)raR+yB=3iPu#Qfo8lGxaW(BZ<=?*YuJ~W! zQXEISn}4;J@7XI4{!Lfj>FHQH*9}vo!@>S-9Ev*R=MJn?r*=G{fTtihrVj% z)E_J7PoJtC3LpQ}Z@A6-(`!8{-_d%wTCjlcJ=A0F2AyIVW+pUNk<`TCmv$xrqX ztDmWQtA6hG6Y`aR{X#tA*Ut3wM?K}9{bu=DKJ-)9sd)Zj{#X8$r|@_Fw|LdRekI=e zSI-CS)_C4Lm)*PaHUB#A+x|WG)!t8h&ifk2`|ih=&*$mv0Qdes97#9?rSaK0Un8sU z!+rkHIMw^yZ{PX&RrsHE-8kO$yzZxucE6vWmA>`d(cMQs#{EwG#mBw#xxUXKo%F;O-C?u!pz!;Kdn{#U-=bGz?X=YN&cKEQpm``i2f+V40AtUbScvoG--5cTk#hsy7_ zAN$eDmt7zps9mZ3>{m}WPRt)C>OFs7J$WDAV?RvC`+6VN51;!wyrT7XYF*p^%bVxU zIz>Mox4?zsFo*vcNBGoLjbHA~d!ECMi{kYhGH)8kl)LdkTMr*Cp05Asc^!AGA6o~+ zBRkiAfBwfC<1Dz(7tiP9_@erpUE%rv!@Mb9)BZP^eRTG4zxJs2_?YidG(I~gI}UjG zA1;Dl^u1c#EpBr(u5sMb?>h%+W$qWyFqq*#tYs? z+4mi7ysMvYJg)ctLh*e52=6%xO`R5d%o9f9LUdqeZ-?4vrqNjLG7~d?Ogk( z`{ie<-#Mpy6o)b2(YPP}r{4eIF+ZAxalff>KYhCKHS;X~AiVt$yFlya5BXpGVw~$2 z&vyFl$9(#SpZvd{+|1iqKY8O+@xO6E`Sm=&)7ZIL_Z_Vqaj!U^b2QwaJ@2FAUE@pR zdvPS|54^|vBM!9dG`qK>`rZ9}F3zGn(xcL!+jB~Oud04}ex=r%*Xwu|H=co;e))*+ zX#3E@k0+L{b<>sq*)Qe($wRMPt@>H`aXjVnTpQn`c*^Yj=8u2I!wSFqr~U`-dgrC% zfBH%Gllqx@j{ntv{NLw0-`9K^U&2|Js(<^N+_T#p$6Y(F{qF6#cBR*RjYG<>c#n=7 z#?$cAINRLgfvNVbo@T#y=byM==}zz0-S0Y;59yU39P-o0sJQC2pH@!XweZ!)>Yv8L z4*%oU9`ut(JH&}zIZ%AadfmE4{}wK{`{Pqbzn=eT$MTVS?kVrlam!RXu1}56>hHbx zJ=T9}pTj{b=eXkR0Y6mhee+rC{_(*$jD1np$LsF?`laj2L9KfVPaAJ>w(RfhbF1&_ z%YEF+SGej~Kgd1aw{W}feXjai&vQ$s`k2Or^_$Xp{a(%LW8ChQ?^WKF`?a3rzj_!S z9VaVZ@1L!{w!hms?9@1Iy_zZqx92tGZoSdEL%s9=hg5!xXT0y&$1PrJ-jzT0FKPM5 zb+})zo4@&gOjjS*>*^i9Nyn+zzUwEm*L>}VrT1RE@?l(3^MCHUy^M83)Lmy$JTcr({ZzLvhkzw+*EyNN8|kKRC(k_d8qy-yzw{pRj>W0ep3AWx!o`S z?x*VUs`ABsv~pVK@qaD$$gPphw$fAz;L-_y0rbo_6+aN4u-PTSv}eQx{T?Gudm*7IBc z$Nkhp`+(Um&i?W6JLS~BDsQ|Gm*qB|srBJiwMXIK=T+KYx>UaYVZHM`UZ}r^!mAE~xsD64?>k97a_#dsm&VFzDUO)DH-1{!i z_j&41`yXik58cPV{f~L`==UCO>y*Cli}!W?J8#duqpdr>d|Q9uU*bveA#VTlQ>5c? zuz1wm(z7D{xY|dvr?X$#_cBiS#q*xN^1r*=zBnFd#XSD!90>P&8uzo0-}gGyN1QAj z7mPb9*Wq=Q!+B)o`B1G-KeSi0ZWT}8^$=ei@!Y@buUb04I{%aYm%rqG-bc@U_+RD3 z{bm=apTzy*fB1uaFa67BzJL5njr;xhX~)8@uJ^J3HTW^ z4ukJ%#52zMT=nd|d(~_FuJ`bz*&w`!)aUFMFQgcEyjobuL-|+W&s5$KG2xE}Fey;l$f{;@Z1@ znH`~U_?~Xot8U9rwF(K>W{nV(X0TD^I_e9pLN&#{;uVbRPG! z$MY)w_nkNWC(r)vym0;eJ^nWiXdK{wY2(Cu2<7j*pD_N%PBD&Vp2O4r@^K%|_irEh z@SR=rq;=}_XOH@D?(t`jaK2Z;&ED^4&;FS`p!vvrY97M>tn=_c`I`OTIS<^rJAUOn zuy*plO7qIT6B55;uP2{-FQD_b_$fZ9f5f{|`RY9Gmk-Y5e&=ea^Luwj~_a>`^Wt{r)wRloYqfQmEP5Dp5~q|y!_y$-cRVd zeFgpO%{|5C)ZboD@%utJ ziI;oaFYYE^tLNn_^_-AT&!O6d9bo5#iU;?Kg9>LIe^k8V$9Im)zj%CKS^4TG-rHEc zq^lSEFX7^Gjf>;%In1rT)yL7jKk{z>I6KJMNlvx1^%l-v{P*+EcOEF6%5`-7@95gA z^=uqhy|=DS#|PPOwqCw-KKrKp$0y=Z$~phy%MQ{!z-`@g*ZHS7P4zVn_*#GCc-8;- z=5*~sE9bcD;i&wLv#w_sID5CL`;|leQ{i*R@2mr?m)Jw_XBSqu+0os(oO#dnt+yz* z`j~(2g)5%rL%(x<`I&lN@t=yfdcUi6#e4pzUDghJ|DyDam+b$RzWlVFoW8%Fl#kYl zcRr;a-7o+5cyjAk{Hgo(%e!`N*1XQ&K9tUGZ|iLHL+hm3eYGxr<$&+4m&Nz$Klf|? zJwN0ZC!p%-sw?NKn#T+Gq2Akh<0;-}zi@BwJ9qvt-f`B{_>}HceQ;0p$I5@_d}~kX zyRN^bTbJJL8iaq3heQN{W@*k8=o>Sy}H|fj9(oN zwRWq#Yp26otDm*Qch13Dxy@gDSB^VZp8v!m(TSv?q{9sc=8^TW^LYj_<#_u=<7p& z^D)#u(D`)lDRkfFW$VY{J^v3HhrUPpA0GF8@u(MEDDKC<{91=KpN!Aoe|n|=VJgQs zApXbx@2cA2zdZ88F0=EC?3k*b*YB*3!^Qn@!0LCp>sQ5t4*xScfB5Fc8LRiWA8wL; zW8ptM-+TBUzQN9~c?Vzd{o=~m`{#PkobqO`7JsTf)Q|Qx|Lu7<-dlb1|Mh2on&w}A z51-R->u-3Q_M+@RkDaG>bzlGE7XEr){nj{WzWwTXKQ8z0ALYW~{{53v{qP-)o8rUz z@AB32A^X2O2Q2*h{dnJpTDn(GXng8t>ft?APt~V>seW5O;DpD2<4!(2SG_;a|D0E4 z_g+5#)01b3C*GTCH|-zS$GP0kK56$kH;gCK`bGAK`ib`e9_@P{-b3j7AGjfVzj&bW zAYFE-({DZ7_wOI?VN|dAdp~i!O}y3(SCzlcF=v;H8)WaC{a$u_hwGW|@Vzwd!mYl3 z_NZ6o%>CO>PH4XTi?{Lmm(O}|?pJ<)<4u3_F`shN<{k66>+!4~KGl4Jt9cKf`4$hM zIOS2_EyAs)#>x0zYF!u4iEq8St=CfA+i@|GV1(O8qF1Co%>Y|*FSrtPvwiU+shpXR3GvueQF)5Tr1~z z+3Ll5t#wnp%Ke`6IBy(f9B_7Pxn~df5A(miyE1-r)!HdLMf(|U<7z5j`W@9DYcIUE z{!u$!`JeL64s!Nz)O-;C>$}j^oBQK{`nm5lS8o2+r==f!Wd}>7DmgfB5R`{8lgV%=MS`Q~9hth0`8)4rts| zzjywpJuAm}S1Nq|l~;MJiTI=BDx{SShhnFm)7SGA7fp6bus>LbNV>qphk&S~$v zF~^?N_0{84e0TqQdf}_e*CYXJpN}mZsTJ0QazZzw_d!e__?R*liPU7 z|5Xp4YQ1^qecGA7cBkVhQ|0RV)~mVaFCVTiKOa-`qWmqt=40;Z{Pnk$L;Y-=tUpyx ztH0^B{_0ojXX-_JaMO*S@!ctZ>CHVooOvAiRX1)^SwdVxbwej|0=#aU%r;Fe4cjT);{gi#%b^Nit^L? z_pb8CUwci(qaN>C{hWGQIa2$e>L;~-<(`_a%J;@=^(S5a`eET$|HuBNe8<;}@A7%K zhcpiD2d3(C?ko2@9B@1^bzk9j->bdb+}T5Z$m>r1l|P)X=MuO2{Kx2f@hgw|s$3@@ zSN^AduH0{K^?wb=U3_<~ep~O$ulc8Z-}{q#_ zv&XzoU-{qq$L1^hyyneu!0*02-wyX{eKhX(<=c8PW#`wrczWf3_QlSfrsGgY^FRD= z?)UX@Kb-92_Jmgsh-1w@@9@7*ALArDJ3T9Y_VwIv_JDCeb|&l_akz26*#X|a+aaH) zeD?K+*S+S)I!wN<>i%(3^~OCrK;d%V_0(_a&8;28KaKZ&>#^U-e;WV$)-O5Wo&SCJ z!TIDP#hJKM{q3tK|HC_c7xQpH`_ab1RKFVcvoF^V@rCAXe1!YVgZlUQPXA}bN$>-F zz&wFR)&Ju?;=^z7i*)nv=KY>yd)}EZq@OnL^t?aoH*U`>dR^Cc-*x>a-OcYkw{R@n z5dXu2;(+3d8?AiQykea)Z9Y2o$@m!lceHlMUh3DM+(Nzhek-2T`P$xFhFiVwj_2W5 zaX;T_*!_C%51xGFi${F8qI00a_5G2q<1Jm6zv9ylukqn3alc1F9^vGhotE>S&UI%0 z_0^Mqia*YmeO`8H)$jU6^J4sN&r6)J=jHU*-_{Sba`pZJ-~H2Hedq6ED!l!S{$^bl z|N7gv?|AT69{$Qh*f=AWUr(*C(~Z_&(L&aLoEc{e`_D4(Ppu^_#iZzowJhKp^sKB`AtP5r0iQt_JN8?U+6yLhGVxm5ez`JeTu@ULn=#NR%;`^I}y z`Qty8AM2507dZRClpSOF_~U1N$(MRN`7521-u-=q_ObG#ovHP4?%63i_pF`v{g~=) z^(S7}kNw}`r#;WbchXt>Dc)GR*LD#U;Pq-cLT1Bi>hg9e3s7zSmdz6Mr1h{c%6x@*h{+`vLEEkoL9J zLpsj#s`0A@qd`!@^jCx`TAb&+#mX{A5G(_>P!DOj@76BN8Nwb*ZNmJ z*Vo_bXRXua=Y0;?KE3?j?NODx`o8Nc|6Bd6eaEe){MEDcuj+dHmAeYxdNzFxxA@GH z;+vW;bI%TLeDJR7xBbxUMRz{^-d|QODqi(ZyZ=MCe0KeP)ql#L_{=xU*Wsk~+l`NO z_4wL<<)iTJ+mxSs>Uq`m%D3?PQ~9{tZEBy|+f$r`HmHJ=Q_W5s+C#qdHdEI|M})a?KeMvNA2&v`G_wa zC!8Mc)phGP;a@d=ckBeO?z_F;d-iqzc>edlKKHfXdDNTzCjBtpYr22)nSJV)k9-$S z{$DvC_iK5_`#!G4D`_Zm(zw7|N``~=` zk>9_l{_)lGe*8kb=0*E1^G^GVzCUR_rQeyKdS0jFe}~(cpRHdvA2**_2R06NuCsX( z&#u3-yON)HqWJ3nJ!i~6x$plwnIC%IZ@tob&V1B(**bIo|LvTC^+D_OsrZ-f$p;>! z7ss2Ze4czO4=xY~VNYc~v5tuY_CAN~q2eIy0`ZV3-iOEH7V7sy{`Y9!C;!ktt{gBf z)Op`4uM;i~DBfdVXkKyNa#}vv{Rx-%6G%&U)XY^V90V zb1}uU)Zh7^t9i5MqQF%iis8-@Xg`A?N$@ z(Vm{~-+JtGsCv>5D)%_x;eU-I`90h({ueK6JRI&l{yon3agF!I8QI@u=O_GE&w9k6 ztIyg0#nm_d)Em3R>;YeSUpyOM^d7-@-}f(?-Cdjy2mDp}U;Xs(zw7}2?or=gJo+%cDK?oB#Yv#rL>XeBX_Z^TqvokD>RaeEzs^?}z!5 zr~TirJH^#{*o`I`RX>1Mx{9ai59cHUO~rPc-9)N{mst9d%UWgi>Q$!#6QZCy+4E3FsC z8(#U}+|&4x@Y(%2C+&Ik<%1i^uX<~JasS?jbn^erUzRWTc%bhi%g@oS|L)V@`p9z) z-#e>)ckPyHNAbIV?O3_$2WzjX@^$~c-1Q&vocAHBH}T)KbL!bq z3LmE&xAa^t{n;_z``tM5cpolVzNh0}xlg$&=lbcZt{<BV>oB-CH-bo)B;D@s9V`7vo>*LwNNyl^^bOc6rnCE8o>iI=jD>bNXTX7ti{u z>(_p(-niXge&T=5qvu|E%dh^XKJ0Vf({UZ`c0H9UwPG6{#W_+*K59gH>rI8 z=*@rcooO8^ovz1KSHE}e=Q$)lQ{`Iwe5jT8m0#RBhx%!qn4P3@yYJ|IJ*r>0e%00| z_jRrNi}%h)aE!ul{d?zr@?+hhK3X@$XY>d6N%v^$pvt-R@IAlU)%91^uja3P*AL{c zepG#$AFl4}c&c9%?u?gv|JeS*dRh3n{U4sY{$+j5ZC`%%Uq77wpRB#@4sFX>X19;` z=Q*|y2Ak%ifi^fcbOTA0POcWR5x3IB(Tl zYwdjy{p(T9S+hRhs#!JGTXSWPY4$x@yYBsrozQNiPrIhnk8nC%FF!8&f%#s(b02T| zhjf@G_w^6uazBwjVEYXBqx8G?8#jADVfXY0`Kj0X zcRrnQ?Yi3bYro1qk@|HmuIuhg*7h>q$^pN5tm@%G-#x7EPcHR{FJI4-#+N#Oy8GMF z&ho8$wH-_syCIxX&h`F;hx@JVRJ*0MAL(h|Dt17){%U-rysx;=`VYmfEr*J|SkCxo zTr!S3-%FGa-t$1)W9NO?#iQ$#ll)T3x0lEEXPsp|ujAQp_2NBGywSK{<5~XA`;c+L zKEv_h{Kx9@kUO`#$4;mg5=k8;;37@6FNfraMZy`2Rgq(_i@? z^`5Zhy8iFSJ^wQu`bF;Nb8uU}^LOQcaX^$W&F}i1!(QYX`W>>*a3AY>R6hj9N9!@? z@%dfXc`SZ2zjruJ6ConROZM0O>YvGkHCH4F)Q~WKJ|gKFn_#0<~Nk}i@dAZVF^SAO5*Gc|+#()J^bBBSJfY{@aiY1zo7j?J?JOr|NQ>qe{pc^!g%A)XFhN;^1~01 zbD*Pg!Tj*9d@j3NmGu_k-dFNJ?K2LTKOo`V|CVz6%JIC)x#!M5r}PWgQMn-NDLEX^ z!Qu1=MB|j-Jl;OMm%ljPI*bdi&;N_?T;CbQPtWtR{Le7$(f^A4zX$g-Y`OgIAm{D* z{vb*^e%}!F{4yN=&0#P7&(|NF??1kK#`h37_Xz*P4~p;j!IxHLJxQ2#ull{Ol<%y< z^L}=-bG|2tpXtw!{NRW`Kg#>|n19}%;om+~?mJ39{qAvH<-N*z#SceVzdy?3`Ct6E zJ{;-2KGy%k|G1yOSAKtTKGNmA#Cc-Y2dvBFG%IJ2gK%9=L;l8Ry<&Vc9y#1k4oJCo z{>Qw_`Xgmu{trigzCFsxb^1YG$9ZVurPLn|NBh7#xsG2V3XeotSDH@W5tJ{|PqZ8P z^1g&K5$2o*^%xyLG1pOr;Slk^l>Fi}DD9=c66KOt#N$-v8PZK@N5b_}{h%`b;$`wP z+RO6F)p%bKPN~1?J?4L`D}6rhC--C>&Gqi9dw{s(hCE+fVc__vufxa7ugAPx*1e`RJ$kU;6UMkMkgm58nUz zEq!)gCw>x%VISw12Jt z*je_l`(x7YeYfc`lv)i4#&E`WJQm5YKa+h~2v$l%o}fqqtriF2?hW z>$G&yI9cn@l=2fFB|V;BmHEK@y-z!`&Y=7#&#l_N8(p89^jrVBPI6sDI#UnIOF7o^ zQ*Xl5dsWt9w0lZEgi-DHIv-|d#cN-o!u#ki{P0PK^)$-5*mNJ;SNjvzJ;X~{51Edd z9TUI$*Q@7pVMwC_f=^Z;uSx|4lIv)Z-0}1cDpL|rCsTN+jpNoNZoYuD@9Ty4^S_+~M&&%5N8>yD_@&^lH9S!6F#M1H|K4d&sPFIp@Rj=h9qy++ zKA!IwKaSt44)^0d2RC8;t?u*c`d(rFao+8{(D>;0qty2aFcr@qeuN>-~SXa*aQt{SyDvKkK_kK9-a6;lG8SANf%a zc+&Wjv2M?wJ-<(QpX+$qlXZPcyE8AZ{ed0XkEopQUg3KBqtc(mPuVBh-`EHBffo)3 zglon3_`Z>0>hqoDy5od+^iQfCVBepo>A}gg5B(0;^S^LG zIU0U`ws#!x`rSeDbDhJi$ot85mizf$@7#L&^5lKA`*6SEf0WDbAg0uR_#YgObXWez zdz5;iwrA&xJ>LxHlrPTzir5a?JKqib;+Q@8KeIPSxv;nN-H{*R^xMZe3BNw#$Ne~O zPkQ*>raa&OdHwL@fBY}0|NHyH^L_W(!LfWF{@$sqM+tL248^a`@NXXK`J6Kh_67Km8lOf9U7OEDzt4H|tmby<3>?tjg8iAL+A>lZ(Om2&aAzQ2yt+-w#K7 zc%DO$w)QNcN|3K>FMC_I)n<9In&OYrlNsR-VpPldktWr+n4? z>(t_>_LuEsI`K~HeZ5aRPQ3klf7l)KhxV7>ALr6Z-}CAGF9grCe>9!zIRWaEy?I{T z_;F}C&KryuGM^4G7D@yY$qZvFG(Xh*{IpeIJjsYxdYUj`!_$Tsvfc*aPcU z#<}Ur0lm&Vw)_2J7nWE4$N8+aK9r9z?KA2)CVlK=)v1r)t7N{l94huhn0?-^mDh1u zd8-%iMdSbaEj`wwt{c|$Stk%CzV$$PFYo+s`bj=f|EJt{{U?{>y6X}(?w3+t@9#=` zV<+)4>a9JMe!BC&D}SM#S6)E7uKs1TJL`^=@(@lLr-p}Dt?R36{b+Z}$@8k~DY%5; z>-nGE-YIW(WPj}QBJDBuL_Rw|l>f;GRt^X^;5j&t&&LIK?Y`=Jn)q?R>cRV(`p_?H z{}Rt|`+@k)W4?#o(LdNXO1`VsfAkO6Y424ThlH88)VN!Ip!@y!z-YX#boX-5o}^3r zneQIXj%kNA|Lm~qd%2lsviJ67W5={>`>fXQv=7&5k5%vOE$%GuyY>(1toB=b)1Q=| z_>PC+cZBPQ;$IcJ==oK7j{MS<`&o|h&obWd8pFFk^>w^eF51iXcfag7*IxGe#KoSe zysdU1{p$ZnX-}`4FXea?Z_>$5kfKH+`lJmv2qFK_?r!FT*vXTizhN5hTeTFU|uPR-8X z7hfsmfCrM^r@7zCDb3I4hv&)t@Nd9^DIe)u56(%O&wl;gEgt@w)^GaF@IBA7{(jf* z?a5zh=lgK+R{i2U@5^@&<$zz_`s3S&%55kgen0Zg?|!AcH=Dmlul%ohxA{{gzT+a! zpXw*2pPk<^gUfKf68m3yo8y7`*L5e#`j+dguZ%z3&vf?R=^1B^AC-BGaPOz<`y}qC zV&Cu{xs&|Q_a}VE`6_=$`4;2Vc`BXXSD0sB9PRA<zrl(w+{cqPV)DYZ*lGy&gK6nGj9$L z(=KdB-lw!LBC-qazNWj?g#JF zpHUvj|Eb3VO61%lP>j&`|WCe!~Noa+C6@O*gw4N`h7pHYft2?e|~Vj58({H7ysbodVGIM{@4G4aNX~jkGhXoIiUW3+Ar@t&i(xT+1|f%sO_(x zJ^!Pw9moM!{>O9vuf=dbITq`K4@a}AjAuC)9EtZ6-zQ7qET0|epl~$#Ox&+<90o2G zpOI$~pLHDRG0&Q>|Le>8OFr5EZTMZj{Qvm=o%iK+%)2Z1W8Qs#mQQ6r#Cibp2wBr@~fdd5w2=_YFx2=Q=jvFN&NgE zYZv?*z23QBc^~7&_C&So!o+8OUX}Qz<8?V;{-pUoQa`y(yr=Wi>To|fVEiwo+&uqG z=}-E}{-oaWKh*cZz8;Xz)X&wzcI?4 zouu@W*J&5x!~ayqe{;2=X`wH{Ejn7Vfw1?~Oh3?nsKh`1a z|5l|v4aYxJuAAPjv^Vxdzi^-W8*k+bt#9ey^}1o!8C-Xr)IQqxJod}FqkSp;YS{g_ z`)k_Obvj|npRVPp{EnYEU3@LO-ur`gqCc4r)P5IG`yC{`_CM{*bEBmv?}b}wFKTwi zdXVdD{+8S4SWm9$Qh&mf(|Bq9p~C;{r+C%QZ(5h8#+!CC z?Y{rcKs}vjRO*}kHBQj{XK8P*&$zX{rk~dSpxp^u-m&{Q?~DW6jeKn1sqb12+Kq7g z3)<82rIxR9rrAsFmp!DD@4k;-?TLCY?^|CLyWx5|^Tf4ZZHKG97N7BCI&sM2X9qjy z%PzCi(VnyYuI&r|qx^Be`X@VNoj^HK?A`rhevZ5U9p!glo!{edKlj=C1M+@=19m$NO>Reb~{flLxBazjD9AalbU~=l@M`zWB2vz58-i&iL28T7Irm zzN@kx<+=+0BaE^?;=1~r|HT1K$92Q-Ksgxc;3uRXpGvxf)3{$6|4XUI%cJ~h*L}Wv z*B)u@cGY{{XZy}|+s*I&y*u}x@Sgq$IKMwR?6=N+7k*oQSN_Z6{ph*R)Oopi?V0-i zYhGzS@%Jv*X^!XKlb)|-{|;B<{}Wtq`@c4DH|NvzI^X+#X5Mgo?CUM&L9Rbj%IE#g zx9so7-jgc!!TnvS4}1ru9?l2wAL`rpV4v|oI1b|#mEVlYMTU>qKJW~<5PXCGeZb$2 zcJmzZs`9MPq1OD))nv($2IW<31e@$o~QJJ6ZpevU9-Uffx|}qHspu!#vmj z38S9>mGklc+Ml281n+~3{y*orU&aNTkai>;_~M%*9=y?Vj?xZ4IOapf?H`;P2TWOS z@V?~zjKWz~eSN&g33JYu_Z;<%`=xTf-#*f3KKQNUJxG3h4-h-xJAm}R{|C(fX)qt7 zyvN}b9}ew%e{Wv==kq=E`Z%Y|du~0~N<4T@%DN!#mr@_s3o4w`aR2`x7o@&iXTM5% zazM&0r$Xg!@;}Z?SKd+TE59SX_eVN%zGq5(IPd%VXy+d;YCU}ZcW&vZ*cs>}%|Qm2qzVzkVy9*Rf~I>vPPn zhWpNBevIW)zVe>oUikysFZutaj92&V_7~+R{7h*l*Dd-1(!Tan>V52!_rc`&IKD&cM2o@xPvzW_;29JZC?w{-~5^c&Pp6|NCIq)O)yJ{8YP( z>#;5}UVJ3~JFkA79Iuga->J`Nbi+ZC>8IpQ|8i}A2W@9*}&KGN$d?*+qh zC+w5(sN7G^YI}RX`cogyTYG*VKVCM_47LO4)?E0ew6FE?)Jj-#80o! z(Z1S2`-$BSc#i%_d7g0U`p59vZ}bmg(*L-|?^NbB;-`#P(@o`m%%7&aKTo-gA4l5v zH`GIWYX72r&@W!kuSuA5Kez%c#C^;K<`+OzRxnD%g-6)v9RF%H6m=lp2gi2Vj{gcRP#4kg9E4<7g57A5{)9`UH@ zU*4X-D)EVz<|p_!x9cffkn~fyAmQPHhKE<};VbWQzclBI3sYapGhA)uYp;&$?2lg^ z?WE56VENm8ug`Sied+K;c*mPF9d-o&aPk!Lg{PqGFJGPemd9%T`acp+?w7*jNT2

X}q2M=2d&S?l4$td6 zE{cC2{(~zAgy+GJQ2Yx=Dd&2g*f4&Ga4GmB_EEl+i~N~?sSip!$gleT9sCb_fQ!n# z#*fnWrTuE(>w1cQwcUMxwhl|P%anGuU)A2rzK7&&&bRCNUip+fn(MSX{(sg#eOB%` z->CJm-{YaYU+A}0Yd`yQ&hzp-?PvcF7xe!#@aLmH;db=*DCKQkCtqznkusjNSJZJ2 z_k)-5e<;|)za0K|`u!1xlM=@M<9;dp&+Df9=17O%$M_x}?`^*KN7(Nu;ulD|W8d*^ zug^JQxuJf2@MgpM{lWd-9QEcqljJ{&|0Lmm{fY;Ee$3MRF6jS;z}4RzepoC2V_yx= zHXh4mG#2#KgPjt-133@F%R;;!1Ooa_#fBhWGVb_3{eT?~V8hyw30Ec^Zh5rZT{R~Iry~nv+-gocLdivcn?z5isyClE&l@hP-{(bi1`^R(i%ltnG zVcL=Qp?y`$$@-9T!;Mn+kNJ^xt~CED!@Iv2<#wOWK7e_I{SVqcc~$qJ@)E8Sh7Xf( z8o#5RZP(5xtIxTg{YCkFZv4RPFS#P$vm>0w2}j$H$D7!XXGhe}{-&MDNB+lrogZMl zPyR={Tb{IY!fNTDlxyr#4uG9oewB7{U8}~qu8O@9kMxYMA0hQ5OuDOH(LAN0@X_`rmN&*$9-p(@^2V5UN%PUW6 zUCa8D-5Tp0$DiwtXZ!N@r|yrLuiTgJ{Ez(q%6i3o`rjk()Bg19bKQ9#>l5RvlwZ3@^8<|Q*dMJg z@AYaY@v+C6-8|R$(wuu`UZUNcpS;hwAdEd-6+6McP}&uZW6^Jh-N(3IBVOUSqMU;C ziJz7Z=~|x0N<8ccwSDcU!YS#j_pjq)#$}w){=ps`U)T0;-zHbeuG97pja#l$5ByD0 z?0r}Fi*fz*dHc`!C!PELslDcR#5KSC{zmuutmUU)_+8ij={puG?~!Z%#LFJ2C*k~= zUF<%t%*_4wAg zf5LwV?g{VU`^tW2SI(24l;1hKa)o|JTDc$NsqvD(QSX_!q2JYu)5L95^L@ns*q87- zJpZrDeAN7X)#hL371Ck7>ioq#{J+2WKVJM_w{Tq1_Xh75#^H57q&{;Udyt>R|KMHD zSNgfd`BLh|JhCh45a0UBjpSsW_mopT;%l9=#a}EAxAVWg$A`jK_#a+5&v3pg_bbdi z_K5$@{gd2(MrYd7ZO`)|KbI$ig9_@4C~ zjSE`Oxo*0R1C{bs55^1jUzl_o7mb(sy~y{G?;YaRUZbQVKeZh#*ZkiM9JX`6`0ZJb z)N(t{YQNq~wPWvFRW3K@oaKM=KE|mWaMb_*#UD_vuiqYAko@!?q`q&?c_8iwuY~(~ zuGsGht{iZ9;LZW#f&Y5rh~w|4pP&Elfxn+&&PAKd6w_D@qg%V4qoJW z-M$AH|NGsO>#@#Zo`q+@`{IDSzX`Lhl>`3AbDqT?P`(KNqd(z&*opk_#j#%SecgFj zziSu&gZId_;%%I(m0L1zzdZK;_-pTq9l!y(4p)l*F`vni;!LbJJ{;v9t`HYY<9_OA z$McjYmG}9)*YorH{_%dJo$%AUY8=pZe1GQ8cM>gkx}F23KEz`_Hy<_rH!8pS6#rY# zmGZk5Jk@=#eqpVj^E+VNIB%eG1>(Cuw%^&u5JuPijr&^nx9|A25% zcK3tvzw37a{SF}K_K6oSiuqXS&5l-9N_b;(oJ#^1ghK{xH1r8}?INr@z&m z53(Mi94n`yp6nym_Mkk3>qq+8_K^4SJAn6x*RS=jUaVK(WBI>bc@2IJJQu&&?e(6Q zVfW_KKAru1Jk4=UKQhiy)>pe`Z*m^ev)<|0pY^+PVfm=MNbW~G+Ru9AXZB1TkJa;W zeXyhakFGkL!Tw+8fsZ{`I-ll$rt3PT^+|gDz5Kc!rQEJJ<9+T^u}7}o>+Y`;#~~i` zTXsBleYIc1?33-UxL^Kx^{d)E%zmADg!u=Zu<^)mw~MatcEfn8|Ix-*%6zoiEAM;5 zUr%ZG`s0z-FDd&3-wW#F_l0&sJo?Xe-nkRy_j>!8QOZGktx7vuzI*;>dAz>%E7uwS z=F@)1a+g2zr|U+!1^Eyre|7AHbh4l91#U&T2s=Imo=Mq9(_bj<#=eQ?cD?@Zi~FqhTkOk?zia+Gv`^eGWnSg_s@OH*=Hu#J zJJde(xAm3(ac+okI{no8WM6MkUhVAHZu9RKxBUUi{sJB*pNjjXaliDx9r5_0(O-O} zKL69(^XZ=->oZpDpXPt22M2`n#r@Jp{Ezbbz4ZA%5%yPHkNXuK9%lVK$7+46HzO+! z=(*OH$G(Ab&AHqB0M$3g`$+!g_XGQmVCRYTD})o)zNzWL@#1$X`$%~u`s&;Vl0W-O z`~ZqUh<$5oVu=TDzesC|=0-2J^R) zH^CXO?RV_(tG3_r|I1$uo(acf{*+^-{ttrnU%46S3|EV<+1~k!cOQQ=^BpyP z?238b`L_3-+I8)3o~N9hL(eWJ-D|n%7t-_k)WhrAMcgktncs(K56ZDB{L^+qZC`jF z<8azB4yYd{nm^|(L$@0-W382F#QJ7!7vcf3%3y?%F) zbss!%*SE*7A^*eizVQ2QKR@pCKemM59{X*$9qSJH-S3_ACg*LLKUL=O`n9oMcz@NdApc_sl-yfY}c$oVs?+<^v^1s6V-){U5e=Of0{Vzux)BpFNJ*bz;+nW0E zc7qdgef9sdec^_F4=|-(kNF?%O8%^~s9*ceop0I>zc_gG+vEK7FOK~2|71NyJzQ7$ zyDRnay^!CZ%DT??Ox$PoWpEcc2fNjPmmPz3pcI7EW2$b04K%*yAH* z-N^Nnb+h~A{0z;Pau6@2J$u<^X({lO$&9n<)+TZJYKa~&VGXE)` z{74=MSFhaJW9q(8{`ZYzoVq{koUlqe8LxA*?jspj#^05F4A=X8o$;kTWCw9S6}y`6 zLTb;%$F9wH&yRMZ{In1C^!#ti_52>=w(>pf(R%OvuXEnRN#k;Hy4|md|3{}>>FZ;@ zw4C2P6+0lDQclD9?Z|tWH@R*-oVV~B#qW8v>(_Yq*GmVxuzli$Dt2W3Rr-%G<@CDa zi+z~k{KfPSV?QQ`?77C{a3%c{;}h1G^_}gr`vWq+I6n+`Ak^>|1Og=N;o+pDWxvdR5XbKiZRVX1ivmmD}sIm;KuP zeVoAaxF7#}rqtJdP}@gP-rft3w0M-m=i7g@PienVKMZHHKlb+x{ixjy-!a|chK758 znXdb!**7tMjAuDW*Y)A9@eA%h&ZqZazk@iQNZ)p^{daBNN$F?%p?S#ojlYy}Fyq61 zqgF>W5uukAo?nX=YPF7;F69f=3Cb9-@L82Z*S!q zHQm2CuJiog9M7>snsE1by|z!`cw!p&ivv=hSBJkJ_2&OxS+~QBe6Pa)c(3MfI-HJi zAh&X!g+H)9;X30?yU)HG7d!WBo`!c|@1x{L{W#~InxErhpWj)pIDW40(cWi`tLD)? z9_Ji+p6`XBy`R(OBNWcV`rUIG)i1s?et)j74112!^qoK8G~^=}v>oL;-k1OQ`$POk zg{RRj;~!>!-Sa>B$M^&K-0(p5!R!Bs$W?~_`TU$4hO5W}@i)WokMG0vow`x;i3fI0 zb-0!JPB{KY{jeX;kH(4mU)@x`Mte_tVXwo#XxF%O9Jc;}Kk*!#F|}R)<=_GMNstch zo5uC-)#tGT`CsW>ReQ3(8z1w12;M8acTwLrK2Q6=KUH`c*H`{$zjwd#Ue)!^J|5vh zUQfS&3!~ zkMH{VzaO6W<@dceXM5`Z$M1jG6~E)5yw_9Cr~dvizcb5v?lcaC%JEdzcg&kF556$U zxL)rU=B)uQbbowR_@CU5e*c}5{}Ep<_@BN~-b;LEjNhB&e{sKe$6NnDAJ^enoWG6x zp`9az7s?^Zi*r{q%e#YE~yP1BRDgN7e?hAtiNoRp8vSUS5We2{(4-W zIGl>TTc0#;^D)(~tf%$Go=nI5na>F`4p(J+e;9dN&XvOVHM@c?*+@#*K8 zC$baw{c(V`ogTOEZhz(fd_V4b7jEl1Rev4UOYI-g_}_J(>UxK9)B212kT3moRqEsWB+l3VWcDMZ$8#w4RpVePygPP4xc;Rc+Lg+@ML3Q7q|E<3pJw-z$9(SjpY5)_T*v3NpX;}@ zewq2|p4*Zy@hq3)rTrz>txxq+xo`aXvGE@Nj`t7OH=mvVO}+PdpmwR9o+<52y3cg_ zDZ7XRXCJLw*7p?slU?lPt)0@^q40fv`}5R8J65xcXF7KOc>j$(kRIc7Pj@&r^Bd`_ z`A_IyMEdTppDI z-!8R7x^vX*iRZM>QRgZ7ALV6S@!dbxZKLu(I3S!1?w0=5u}*`}rF`cPkE5R+%1&eW zAN$YOFMe`7kN(+3e{!S)pX&bbKl6(xj$fhq4*xSA9FTPW`dIhLxyRn_c{OT`|`_UJW`(d{vP8m?x(WfV_lJAPpm6kFA<;h zjpMd+wZj1&@B4h6e=FnimuEXNuU8Josn7LYx9j}TxZ*u#IhxZUN-*}T83a-dJlE(c|I1A@?;ahx9FYZEo&%xH-aw^VIzCGrf&VTB+ zy#9a4m6!P4Mz{#?`Qdcb!~f?c|M{Mu<>`M#{Qp$^{NOHM-kyj1v46&2n)v;1$*-K; zg?hqYP|tVH|Hl@F?{N-!xRBfre#CodR1OqZ;yKz0d(+>|deB~Szgg|da2n@ z<<{B-M%e$`&A(3$$b8`c?cQttfNu`Fz@F_tzb8oh zXrJlz{4aKmoq0Z(|09<3jdEYRQ%!H~H%_#7uH#ofO1V}J`0n`XCH(Kz@fOwpjCF{7 z4rTu6I-HJn|Na@D|5-2|ToAj%-%oxqO25PPcIL zjqo$Y4vio8o9E?za4Xgi@w43@jd3;pNOCE|@<001^NaDo*3Isd`d?T4BOM>UPi8$g z`?l+T!1w09FKwU8^R}zyCTx3Nb#Gtn!S;;<*6!DM6E+|FP5&EK1N!x`&*1*>Km7N6 zPd@73{18WXPFVTq@3owTyC469^N~OHpR$gX|547}|BvTg=c;o~UB9@(^Zm*=nu5jjO<=*Xq`G@Oid@qgrrCm>HH=nQk z@tL^Q&i`1CSdaYucHV&}c%A>)K=ALuH=edcS`# zUl^}+vTO5)=aOGM^O1d7p6Yqk_)z?-@@q%gP1-nRp0wX)KCVA4ujPcp7{2~)(Y!X? zk8-wud#2c_{UiUQ9M9v2Z+%9`ai~mf^pLU@fwA075_$lu-;-{Y-{ZBaUddfU# z`YP>Ye6{WlNe3f$D{qe{7AMxaU`T@rO zs2|r;>c4V9`hoN*ry5^Wn@3aPJD1R=eDDRQjX#UiCT-oNvE*TQ8@> z|L_BY|E2l;{nbl2)aU1S|5&l(x5vq+INp`_{rE_SmDw|0@cS8~e)F^b_Qqt-MY3dxGS1e=gVj<7mV2%wK;# z{VRF?Z;y7BV|qV6Hyls?N0{m8{~zu9_&eu( ztKSdz{T~iEiFSVdUfS?H?lbS9%!`KmowD`EmG>EDp4aZz`J8gX0cnrssX70?&LcBl z`QCK?;5o({=`bGYAC&9NJ8~q`@%%6If#sIlkPhL|>v-S!4(kV>f2{D$xo`dCHO3#V zwDP567#+{SdEj;F_|e%<@)LNReo}K@*!Jr@uH26Q=a47iCrJOw`Sk1K{I7mja6NgQ z&l9E`@ENa|nQZ?PTx2xK=v-%y`JIdatNl=RKpEUObQMd%f(}sXrW6 z{wGJapW(@#Q_1dA>LdSq{2qswFrH7fb) zAISM$InEy)ia+0fIp=fE^*XQnKOM&JIkfK!u6}%6m*=p5;Caf8vL0C#KJ)&#p0Z9O zoYF4d@B4ncVvoaFZExd`zn{Oy=@%&XV_mWDBiVOZ&(62P4S3J8&t^V?`|;NOH2-rw z%>TQ(?{EFe_14Fz>oNCN)YJV;`%?J`eiycvoDE(?nCGcyik%X!y=a$fcy0Ikfp+G4 z%JYO(-uC+Usq|yz*}3EF$LD$Shx@IHof1aPC%c&ImV4~NavMK8ivJP*aHN;Yw{aQ}eKZLJJ zeYrj=_hFr7{Q3Q$F!dGiT;ZyWE1#=he4ct(j#1iyep+MRVr`_r`RkM^rR@4htq zAU^rCPF~B&y2o~t{}Hxd)1Ch{ugv_cpEmvC{GnZOpLA9wAHu8FztgYvugZPfEuH?A zR~v4eQhwv7J3nW=zV-v{$$Nly@_mpWR$Of7BG{?#k9+k!({sbkxE?q_kCWx_FMheICS1&UU>YR{l&Vc z@pAng!~UxtDgA5tcD_Y=wu|j?wHwNJy>B}E_-;Jc&e$u@QLnV;R;9j#$;ay-_d_h+ zRe3M+JZgS^@0RzX;jXKVYt($R`*gR*wSSF2{Y{wquS&g*x7#yz%=PRB#m`e(OrT<@Oyna+=I z>8z2<;~x5 zcpK+x@eGK=4JY(E9FO~R-SmwA`aGAL-{P*d^RDqsmGW`_S({XW-I{Q|LDI0WS@o#uDuQQs5n-*$gL+J*RB=Xtr0=~T~^&yoJe z`5*Z^KRs6J`}{uTfhVSxH~%f3qu#0W)9|kR0IwWy^$Xm2iTxP|{MTFkhyQt>@AuK~ z_xz9RUmpBV9q#8jO!y6)&+Bl%EB_-7<)qr2X{IFMsz~75?dI*VG4ohd<*Z`~U2C4|5%UvcH$OKHSf7g8`CG>i_)0 z{~X6x|3Lba_^SPkz0%*S(mwR7oG*pbVGr67@$dUv|47HN&(WTik8|97=gR!(Z#m#7 z`O&WNK+@rVIH))O!%;Y;edTxQi-W(x@A&@#Ri4NCi!l3jzrUg4$HVVRoU=ta&ny3f z`!P@D4;Tl`udsMOIC%^F@cog#95BVs;eyz2oRE0(LE@7?DhDJU91w2&qeG1+pOODj zPvYbMhQc#VPd~r-4eJx`$Nf^;!RO;Yk9Z%?bzT2RIjj6{ZCClA@hJy(dsXVOazVf2 z3t!>=il3S4x~Y9o+)ls0*3s0T_l+tC@x8?QRlE4*IX>Bsu}UBv6~9Y(ANg^e|6Sqy zmHzc|RMx??H)^};56SzFc9Z*&PVG19ep%i|d++_$_ZNrXc^}Tls*C*n-{rYZKMyxG z{o#U?C;s=@VW))ISD@G-@o6`o%U^TKTYU4|?T7X3hvWH``w?b;>pngHChx*txK6u_ zQXb=DKR%aVVE`Fl zYs13~KE@%}X*cg<$E@D5Lw>!d{QjPyKVtjWb)T#qP|vu+y3Zh8`Xi-WwEM0r z2b4QB6e^=r;?w#+NXS&XO$NjW^A|B~qmGqwVr+fR;e~qg&|F@lsU{}63W?xS~4A*eKLp^=p3@@>N zLaDva02eYwq=`erWZ#9*w76>+iL_*5{^O|xS zm%!dES6n#1cGo$T^S&PI`@wn3a+go_8l`;MH}kUP&E6~buFQjbz2f2d1**hjoQ(RN za?0<%%zY8<$G+&Q*bng(?Vw43$Z+mCgf?d$udejT0p%JJd%|Kd1(|F84Eyz%2e@uHOP|Lr`^aGWmv@h#q` zmG$wPlmDS{zqIt?esRDn_bdFI|H0?p92`)Ek5LcxWBgC9_czBnm>pSq<$M!1-rs%| z-+bbL`t9L=XgT6=wQsufzt=bZcmIFM^~a~xc8=$kZ`$|&#{Vz=M>#(~_o1l!Rk`0c zzB>Pl|DXIoJN)uykDdqSe;?onD)T_!&12v1{QpR2Tr^Jh`I-C954*xkxSlf3jHmM6 zww$}_Pbg>c{4nuJ$aBSVjrgCu$Z~hCI1ae;OXkn!p+`zRxc*#+2hxsm7V9_RuJ3y9 zpJqSEhu~whKm2QybxhxhyK0;;-d8x4qj`SU|Cyz|;%oAoo$JW={3JmP$(wrTH@EXY+Ii)Gw6Euh(fsD*vE#3|_NUyBe7Fyn#7>Tk zZ_n>)`aEwul;`Z%dp=k?rK|tja6j4!`%KvnfBOi3ag1Kq`QJD=sqYp3zuSCvWqidk zxKCLACD(wT+phN-|9f@RgYgbWqde-B;|~Ahdw}#)dgXsS5ATcLVHflZ*Et`JUDR&$ z)3obH}L{PIs<{NFGB&qMKA{o>SLJ$~2Ve~ICN{tpTLWO}Lm75-;?@c$pYXMcW_ zlkb_q1z#NgbED+@hew!x{L!iK2f``)Lir#6C(L#DAN};BbKZ^r@t)^7_Vug6=?JTw z_y5tsTV5aS_rpWwW24vy+$ANy@89CV?QDm1WE4?k1*T-e?iKD{~-Cw|5EZ8~$Xe z_dgtVMLov4_QyV`k2+j1|2%mf>tXth^=Qg- zgi+SLYq;z2zDH_0amefddm-JCIT?K|yidw(k2yi~vO-Z7oj`IdQ;>-9VQg?u^Zg0c@lEB94NpYpHQ zjc@ysZ_lrK-`~Yc<8J+)==IuVeV+U)N6LJBZCB&P&+NY`U-_olfy#T4@~7Dm-%DNV zMLQ5)%jf;lO^5q=|FOMi_vE*hpK=raI_kdV%Kth?D1W28?Z;OBM}5{X@!Stz&kN^Q zvB$>_i%pR#|S|7mJm)gJNBeSV;yXrGkvZF|+P*Y+QOWXDPW|B?UJ z`2YRvNS6_F&;Qu(;Ah7EVD-l{9H&cve2e$*)hh=q{jaP14>9Hb^OMJUZrSi&kKu=` z|6ktx1@X7z`Bw*j+jY+08eg9G>c;h69sYyG=RW){HQ)GN?RnKJ$LxQVE9a{CPwMBm z{x3865jH>WQ*X+F#{JUH9oO%1K+ikBJN6Z(r(!pRv!5@Ic^3ZntA`!Rmqxv=-`x8D zz}Q*ma(52L`&D~Z87G9(bzWe8Y2Hk)?`Qal@tW^-``{PI^YA~O|1|%L^vu&$_3#-_zmh026rq!`R%_P z<)%G`Z_;kn8;(@Htsn7iCvNn=6!fd@JbM2gz;4G5OlNo@>B$jO)+cZ<*7Nd3?8S4o z^PJ_q=ZIJSN4@dy^Sbu*t#(3d-L%%%w1AYb84^Nf*Q7*V2Zz25uuvg-z_yg)sh(DDahmPr3+lT$&RQ&}huRKZqhkwua&-?I__eZk$x1p?8Q1?3TtiAaCNZN%k`$X(TKFD)&(-i+S z>;W!py4uTUr+pGXJNf;yKX{MQFDd1*pLT^0!WZMLl*f4X`)9ZQkL%&*%6<6TuEp0L zj3<|KpD#Zq9eF|igDUG_uCMyx7G5=86#q*ZN5muFHGS@zznrS)`5#^S4Zh8Dw6FQZ z5mnli>-2-^$1Qh%DBcgoi~sFBxDD)+kX=h*LX|Ej}@Q6aP>?x)H?)!V^y|nxLBVNk$gyVgMSJkdQ&iyJ!etut9 zDTnRWAGmGWsny+5wJakuZvF`8YKIVVp|EFIU-*p@Q!+I2dx0H1&{K)XipNRL9b6wm2 zd%V1T_YakOJy+BF6esL|gyVr%{mHFdl%w*X!~f!d=9eE~T7BebEB_6CBWFRh=i{V)If;@m&HIQ{>q z=Og}y-Q)Kc|I_bFPR4$JuCrbkzUF&WduANaKkzl|xpTb5Z=K?}nfXyWzs{f6d9?V= z|Ez}`C#`!(zx-1QLV4aCRzUguej1#F@26Q``3hmVAG|Jp!@S@;!+OAZq43W6cpo)C ztV($aryu8kaw2#S?_1LuJ_)Ci16uz4qK0?T?r^Zjiocwk@3Hb6b}$NO7{9;qOXIrd zc=h)q{H>#XP&f?yNPn!?2VaH1ygJeueS26n*WVrO>vcFF_ji>Ok)GwCU8tWr{LlWj z-0&vqffk?r`f#P4FEQ`)yz@VH*!+)Tcca9M?-7p%h5u1L`ahLxaW0ng3u9MZPi@EX z?<;)O;eX8g+Ql~y`@N1^?IXK(JTNZg6^_%+pY+~xyn4<)?w98O*ZE(@5#xpOW0%CU z-|SzwZFWKbS`T?HTsD6{)3<;4U9NVOv&c#92kd$HEb}mSl`>x5o#lCb%y0Z}$*Z$m zspY4C>?h{G-#&QDyJNP6%aJeqZWPW3ulwxyp5EUd<(2=bazFh2=nwt<@Y|F3>F?*c zU;MmChx!sP#hyC<3%4QOAD{Cxyio4vIb+Ws(|&LjRsIN1TEnDA*!1K=*dgg*pQ}G3 z^O@;5%A1J)_k$<857l1ff4_d@ zZ`gh9&i`1~QC}3^cU9UiE?B%(U!DCm{O{$-p(%IVc+QVc``G^PkNj9qqVhiYs+`a8 z#EbuR{x{wEpXb@hhxRjF)p&A0>=n)}|B=hZ=ddTQul{4Ka^y%WkD@=X;VUmAU*e%_ zew|m=KB#B>NuI|(is!JeRZB0fSiCqO_CS2z3+5|7;r&jS_lNiM3)L>^XYcR+W~DnC zr&7s>{aX9BwEVBiI>-Di5B5rURoV&ufKor(EzU0Ar#$qp< zAJ!4}w~Af4UsvOWoQLFk+V!{y&pB_gPR3ukegDj;r8irCf4nyJKT+RSI<*U?q9iIVeH2KkK@Gs^owPF(jIpI)OdB=C!KoN zj+HlUAN5=<&tqPD?Z4*1>-7om=`?Ciu3-+3Fq^Kv~NM8BGz`YHa$IMqI~qw2qN!0LZrFU!MvfP8s> zn!nepC(pT`$j|K=@AEp(xnG&E`Q?&t9C9l?R;uHDgDVy*0ubP2m7j5$2nek*kkS&7hE|Z>)*oH{|$M0I~Sa; z|1V5Fgukwm&-_m@yb!LL^1mjOBmL>EKF_$|_55&tg82K-i`F-u7l$NY$}>uP zets(t|F>d0&wcAtI#;cK(tG}Aek=cjBfNmv9~_YOS@|FPSp5IgUmWFwv#?&^ zy7qik`~b06RnA8}R_<4LSLcy^er!HTn}^fpW9QTLz3sf}``qz}-v)e!^7|e}@fVcm zIUezIBtGS@eBOs=@c#;~yDq?P0N zowxh)uuftA8csQUlI!x5Rr3?P*WruyujgI)exG&`&l%NE&oKUI#QWlGKRHeJ<3wpZ zFb-Ha{`dCiAHN%jJr4h~T*LRM*Itj#0ju_}d}+@879Q?LJm+`p(Ej#))V!~np8biv z*H7|1{N=F6xvu?XXSNUgjCR^N8ui5PRQa0eaITk*WE?gwQ`%$Y_K)}<<+R+|f9sHV z`N{|BFXCH1^QW9|&g=aDFT9p8oObwM{rviPd)Qxo_tEr*|6RkjyBrYS$2i3QKMu%! z-s_HM?lW#zeR;DtHSU*MZn!e_qQ5y0_V>p*;m;4A^!G=9y*)V}^Fe-me|%i09slG| zxZ!^}=FRvYVvkK;bqjV}kpzwq@j|Dfg*4}5>- z1LvXNSKi0?!EccMg6m;FaG?~t`8xd1dcd97x9^%C-l*k?2mbaE-*)9W);+84ywCH4 z#E19zJ|aHvCDZY{fXs8Y58TgoK;u{D2WR3tj+_g|PfyO!cc|bV=EHipbC9f`38(Ns z-%EX0-TQK&&iRh=Ug3LxX!%k;<`3I#=YOp0v=jBp{|dA2H=dl3ejp5=Lh(~WUmgAH z^*=n7a@yW-IP8}2sD737EB$xhPh5Y0q?^M1NN<#O=RWr5|2>n={dX+&bHuJmFa8!6 z8eRFH{o^_5_+R(qUvd*U-f+dzr~dZ4`IbK_Uy4KJZ)kk_|HDzv{O~$|``Pgvc7xq{ zUk*fihC4@E`Q&T7AGp8nU!R37@9?lSUg@N)3(R-+?}p=xd;aae*{9I1{r?Q<*&gy8 z%4xq3zsrv7@9fHP&wj=0qdZT)t{QJm$>*By9v=S3b;bkrOKVTw%eBL*-5=d~8+L7e z&s2L@?TGXp|ET2|y-(lrT)E)mc$8<2&wicoXxvtAJ171^}e3+E!vTIDfaAhD)R{8v~;doe#N`$HQhB#{}NWm9_{!1|N32W=WEO} zKBw~Dp}eCz503N3{jS>m)<2A2)7#sz`cJtl|EKuW&i&wq+Pg}6gj4cqJUmk7N8_hE zf5VR0pQYFr;j3bo?&BV7@fqhn-#NWFq)NY2o|JSgpGrCGSGD$I{BoW3ulKL*SlD(Z zed491Lw;OGwcBss#?O~G{rB>}mp6X)>TB>n`Jh}d-gnh2|66$<>*NVP=8HVf@A>_& z2x0kPeum>eNO}0~pz-CG@<8&*fAFWb`|&`|8h1Eq}c4C&&7Ve6Bj> zW1m3z;;Z_r#4CHQ^u9j-GhNRue}4O4lXqWnzxW^fSoojcP5R=d@IUJL?L*~(@ISa9 z+-%iHykY$M^6y)f_JAKyKE_Atb;rSVyjY~Nw`)3$562<-kUsemFZH_P z_)&T3AI87uga7GxPJcl1gLg3B_?@hm zG5=J*#Ap1E_JISYJ1?_ehKCUkzLLTl#*a%5M|zg;pAUblx2IpE{3jj+ACd#XCGrbI zbd0CbAq2Ic%4&UQGcJ=mb@6oQS!~Y7${YVckh+V+3pP%2~%aPrs*tLAn^S|2J zaA)#;#Q*G{`kU|T$@}=qs{WksPP^cHcKoj9xH29bP7XMJesUbfAM3Vwx!h8o%DUzL ze6sTx^=CfQ&zE+OpX#^Bb>;`IzdiQ-e|Oj+-~U2i9egi!zJ&iV4-Ws!50LBlU5)Y< zS$W?zOh2)Yj{h-_<*xIE01UHt#v7sop7{aOB<|FQm*Poet#8TP#EexLM+r&`ZB zFMA)>&yRLu|0RcFf9m^z_ZjIQBLwjXJ7w}|IB`$eJbl!_p9uCu@_W3 zr9J#VnUwg}pYq|qn|LYpdw&bdT{;JPe;$|n>`PW0datc1k%2 zn{NBy$NOsLFV{c2f7Jc+rei+kN4d3Q_7}EG{BQWL{b;{aZ^GE4c5wY&VEXy}*)DOw z>A&(p*L>IOkNDi$zC1@bWn6hbecTT#XCpuQ!+duRxY~p9?C0i*{6^E#O{br;)8?74 zSH9+@`~mUjqkiL$w{t+&an@hOE(kx@@%JMh>qP7M-J8nec;5CIUQ55y-uAD4fbl=x z(_Vkf{jj(7`AMgI_VTl?w;qiH*Zk{IrydUI#U8f!P z{Y4xkZQq{m`*+42&!?;-*K$#Q(;uarQ?Iz!WBvyhCw__@T2Hlf$e-)+o|N|h*GJoD z#n-O=qJ6PHTJ4Pf(2k}*wI8q3pM=w~FRxQh@9+N$)4bofC=6#M|G1p>a~}1ayzNFk ziP!%VHLgg9de=Uq&8yb`o~PT6^_GXJ)SK{gea!zFFU+UZ8@onnZ};u_56a!J zE3TvL7x)feVHEp(q}UQi|HEG43#04vj*tEQ*n2)@Txs_oSH>~#0sJu1dw)Q=k@@n!C-DxI zdF1+kC-J}0elOUy`6NC_z2g|^@C^5lzc{%7e4p>8(GGHvUmSKVx6$9}m*;)vv-|Ry zFYiJ9)|f|EjOFr9_i>8 zNWJh6OyMHLha+~Ll=Gd`J6-=zg#M-cv>)er*^hI6l=1ZF`+vMY)_O884&SU_Qu~Mb zUpt!qB7NRBeLqq=8ooz);el}{+6O-ODbkrg8}*<);bic-c(e7v4yYGuxkmN(qrW-NO~1nbxc}xB_J4^R zU*<=A&qd2q46|=_bPuO;09QFU0tnYZv=RF6^_>%v*AD8?6 z(ZO5D&-1&U|JCm=|3CZ%UmpLr>^WcfAJ4CfU3LDKbHj6A|266__iJArw^_g6=KkAw zazWGedRz}KXnEy)gy~P!?-YJ^)Ehs-Lr(5TJ9{2@|NbEBpZ58?RzCI_rh}3$oJf6t z&L_LSAM0J}kAENh@7<~7^BYH)`DazqF+Mu^Q0{m`Tq=!Qm9P6u=Dp#6@<8_|?!((h zz=b}X?XvT~{J_S~CvG(RmAD_gk#Qssr5y1{{S#e(t^7}p3fF_jjZ)6bw1!!i5+2?8AsmeK^TW)akahZ_{HO=lDZln1U!q)u zQ+SHu_JO;ykF)>eb#N%d{crW}pU=Z-NJq||-B8}H%c&?A&tq3`MD7#DuW^*?{4b8m z`nvxYi33u8?B^K|q8+)PvJc{XI=?rN4|XcYl(WQRST|UXtGXZOJ#KljXW9!pT($Ha zXQsFNU$LK{y%>jkziS87i|g2_<2XC)e)ds6cYXTP^e3OnfwG@MZ5P|g`@`kd_9MRG z>U~w)``Rzmg-fzMS8%3+^}W;(N5e<10VF=35mz%AO{k z?^mynpR4USylAb*)N9JWuKT%9_^Ry>Xeam4kN4#~=l#z64i`0_{2}Ee)XV(hARkxk zne=JDRcS}_ZJ$#)Drfv<^0QsCAMHfWJo8HPOLj*7JeS?D9=2X8*9l*FQCusf-lh{r z+j%tel;zv)DEp#6oZp(ydw<&Rq^})jZ;mUKR&P4UbHXQugbVsuhaf(nE3R2N__1g?xRvKuA@B9JeC@N_y1#l zG9Q(Bj_~L{KVpCOXZ6$$=DPvbcgEGVzHz^2y7NEkD|buB|26Km>+m+)YtM&%Grmf{ z5{7Gfy>q!cAEZ9qmpAa9+&M)1^x|Q+rMK#%`q(dxYsYc(OS}&Iv_9ANoG|y-{xANj z*?G$Tj{f8vly)xvW1sDM@!hGz|6blW;L95?g8Rw2((!NO`pW;}YpM6|`5)~&etqNr zwqGBvXL`@W<}-Zo8o&Fd|KoEVbe})GZLN>I&hx>n$ak(c=Z1X_zev-6rq#3juiE`l z_HA%K`CU9Po(PZRejKoKzbWT`;e2phmHNT|)Sn&c%Kr@OR}uG1Kj#0(^TYp!1CpK` z5Prh=P$};^&Khr{dwkZ_@CjA>-`|VPL%!E(f9EUw>YVpb*5%A+@`Hc8aRa~4#Q5Sl z?(fe#uHXjcFV87F^|F5QGSB_`y)&-w{(f>k#a4x42SDIpJ8I>xCP^_w>)=dv(~+7l+CP)8T|yz9c{6KKu&qM>)p-Q2s}lb#ok3 zzrH!|>p5sSp#0DNuYc0%r$_xpJKGO(I@-Z<{aaMNH|-?%ivwDJ)2H3E2RWnsZXG{k zuW@Yuf8+kS`lo(OdoGnD!tvyGaldr$56%PQ{|Uc+ciIu>=LyrkaKPHR@npNwpS;IM z<>8du_dE8;yg+`em&u>^toFB#i>@1w_^h)=9`hXcsUPVuzTkh%;_|{*H$N@>?XEnBeRk(8;Vg2aRVfc#k9O%? zuYQ8?#yKzCeajE8$q#V%{~Hb|*P-0{`&5p!>-m$(<9P3|-%n`={N3E|QGWVwRo2ng z`+K+gsr1`CCm*5RUVhaMa0k+bGpv4y@&?vr@{713`&8cx?~ihjK1w|I8!Gi9oWlLw zcckN2W;*O|Ntb+RSGeEk$}jCdxgYr&{*Q-USP$$&{>Q2W&PTfPzqlXkd*T(QeA<`) zHv=!WJ>h@&ZK9pa#s1d+72)fc|LM3-eqHZ-gHyiBsdf%orQf-p4kxT1cGXU3cR3N| zi6_~f`4i=THk`=*+QYOL*HizmhV=D|jZ=@7Z|7HsSCJ0oGavXQ^Aj8~bv$SeG>wSNmA5H#PyE3nRIPD?-n|1%J9m)Z<_v}7pKjJufrZbLqJHT$S z!%^-Jm)1VAH{y{G`!(8kbodbM!9Lh_*~jIKQ`>Xr8_qAZLmVK@zo&3Y{%bzhe3`en zf6w>g{&7Fkxu!>XDbJ^MuMhe0Tv~ZYSAQ$#v$g*p*@O4p=hNSNczB`hp}mm~VfcXU zV82if|w5=Zm-QC&y>LXE;BsIcFDeW z`?=a%?M41;dy>BGm_2D1*%|h{=My)I7Y+Z@KH_-KII=vDeCuEI8pb}op55*IkNJdh zU6uL8`c!Vqcdb9|Z9MDy@%CapNIb?_?Gz_f>;JE-*~z2$+C`i&d(yt>5A2J2qs$N5 zP5(PC2Ykl=i0^ZIJJlYj_PdWK*4gIk{rht7JdSypa*ghsljqr&&<-g5vnt%peM{qT z=i#NBA0X{vyQRZRxqhF%Jc99VIn2-fEbR+_;JG-4@vzgioTOX&t5QG0DbIO7dwD#6 zOuO#>x?QKeNGI(&WPkpY{3tT&MB>h`z`D4jgYz{}1-n?VRZK|1k24 z8hSl)gz^U^G||%(GUC{mtz0E-=8Vt&H0LP zLA#)G1H;U#Tu)1{`DW#R@(IWDeR=hx>$`vIe!kcDoAGuoCmH!a-aL_wePfh=Qeqdk-i*|dCuQm{;X84j_zx2h@#22=i(HKB~rOQ*cbe7Rlggk-=O>pE@T+)L%XZP{p3M&e%JOL4v0O#1La4f+8_1L z4*mWj>G7T-KHQ0RU|zr1dtM7Kx4e&(_K`=SZ;tlC?!P$t3A>P!$`v2^|K%5Ic`Xm) z#eTv*;P0eQea#>H&VH!RVFaKVj_J-wl52 zcpu8i(KiQQ;<`lze`;gsGqWFW$%hgfQQ}dGS9T`uec;|LqLFd-1=V z`u4^bRmP!yTX7sXoA2vqN__J5e@FCFWL&}p`(9xDkM@%f#tS(o%6q_b!}K>?BxOE{ zkEn35DG&L|k5t~CawNGQ^9;O?d1w6nvFN*Wk@6L9x zA0~gxXZ_C$@^xINd zz0qE*GU~Vd5+CtDepljrG5w%D#{E*(rSc?IKS1;KdVZTK>vyiRKe0WZ^C9jt|L!Vp zU|-<#{Es#9;(z(oa-LnDN`9SN<^Q4$>yL=N^ZanY@88l(<$K&`pSr6Y8attV(+@|y z{BuzEzxj))e9xTg@<09c4gczSo%fv2xsTQ_5Wg1oxhc=*Cli;N{WkSteT1_AQJ--? zuVbI~+r2$tceHz|-Dz)eKzI<>DVO~$FJixGc}A_@&Wo_8k6mBe)pmCOf6p=UE394i zblF!u&S&qZ`VY1JtPj5{5oSIi9o7r>f6vDyc3u;=kZ1Tk1nLq0i^Ieh=|9u|x++Jp zJlLz{OS^vME^~cvC(3F5jkjGJ$7{Uequ2wQox;Psp2mNMOVS?LtNlA1lXd?6{`bl+ z+IPFoZ-0QcFHcR+c;x54dVjwBQreMtY1e5#pWijkLcO_PIIVo;KlPSBF&=D>G@f(s zUuwJC|CEa`>Dm6Z^KM5IulRfaXBVT_-xcnEpRgP=53S`Wzez7X7iZLOamGRQeWtd{ zj2G)c`&#c^ncpm5`HX#OZ~DhF-x6m1i}F3ly&v}eU|!tqLVh>grtr>tC=bsSZ|o`# zX#98{?=kIc|L$KLka^g3Eqo9vASYy<_SpV*d#yZa^;*^a@s;}-W}I_>RXLg*5PKv% zDvx77%D$iVn$PP8#C&Nu-nT3L&i#~rC;ha17-!}?ypeDmFpWpLKXzXCIm<&ok>6G6 zH_I{ejQzCFPxW(3{fw7pC(robK3{PTQ9IrJ|JY~q9+v;HKH(fF;n!d3-<<2!moNH% zTlMwLA8@quvT#6lHu0%@?S9I-cz9O+ZTZiQ-yrK|I2(N6&B^_C_5Qz~|4}ag&t%n| z|9$NIuJwxFQ69@_JwH{xo*SiJ?+*T#?(LP|Uy9!!oY3>h@6P{kCfvE-zdrUQ@L$e% zbDe$0s>A=}Fq~h4tMuJJ)-Nv(yP5O9lxyXG#{b3bITY>($9Q{;Yxu*PQ<*p6YwrIY zFYpY;&2Tk&7JNefV7%{~1M`^I zRp(cEo&7?;#qF;DgY5O4!;((dQ~kRrH-27Ie(EJ>g8#v7`2HWy!~0UXAAY3T8SSAz zTq>`U!*zZZUd46Pe&#vmdpQ*TmU16>6z}g*xY2rk_2{s}4&YC6&MWtObEL~W>~-6N z`Q3c2FZGs>86N%zXQDp#ALr_AmtBALxNbQaN1U6T_Okw@TYFOeHDBz^``9({Q0r4Z zjMJXqRr~Y)aCq8Rzs__xAnP{2tB1dy?IVw+{jm%9tn-57gYQy04~*Tf;{Yx_=X^Q0 z&NyQnjs1B(7*6``Tt{<0obhb=M&*LT|Liy0B`(NwUHAPC@8g^>-$~&AIPjb1T@5Ke>IGtL>)o~vJ=*Y!*D9B}7>cmF^76<$I+!n2rH;C|^5Jh+DYe7TX_kMXXb znY@m6^gDN~gN!dfVEj-|)%6`=?3Q+u`=!Qn-Qu}m_{{LWDNp5!JFqVHx%|)M59AXE zyq*W<{fEEYDEZ_6Mftve>Z@D$<=H;mhhMQ;i94?6mzjrt>!=s}70xGDCJYb7o>+&c zuE&1wT#vDSCrmwTuSZJzVVA`F!I_Sn8at8`#%oj7?e@oT8N#g3YcIp{z}i)f_txKq z?FY(1`m6Gs~LU7T>|j+KXXG4Zn_<{LOt%6-H2@0^dfKJs+^YaJ&m2c(_l zTPo!xtXe<)|2i+c^G53X{wxnX$o@=ON729SFWvXXgB~mIW%sG=)8&8sF64EU^%UoZ zKR@#4d(H2T{xkjAuUjtp8vAU*jJvK|@BeV?k6meB`zh{+9n-&8jZ7`TlSqv{r*VL`_(JIE!%_sqdqC~8DZ3NTy^jN>>#Cn*Y+Wu`k{KF z=F>U#&d2Zmka54~8gH>5@&C3y>2N9AA-}Y^Oq?YiBCnu5*az@C=OgXBChgRI!S(UJ zKYzBL=sDWW=gk-UA)L~lgp23zkMvj1ng4{1-*aitqqal!&o0tw58}~pXm(xyrqs{= z-gWFKKBk?;(HK`e7q4YJYY$g@8+-KrZeNunrGCWAp3$|wtRvQXVTXnv>pK3|@^T(@ z4Ojl^HP1EP@(+ynWryPjXgRL^GySpJ1^uF3?8-Rd`fwlbQ=awtv9IjDc>DjAv0mZ1 zl=tl#W_?CD{uhT%=@;&&v^U|8sr$;u{EvBVy&snw%?~9%z&VF|9iMwT!~Lw^wH+-t z?Z|Wd?x4mI^Y{IF%J{H6^1jkdr#{#AlTR@2uovbblz9r}Ij?Ky{qB>pp5=Z#H#PT=!$3OF9?KYm|8o7eL5^FH|vKlJ%uT=E;PNB%4Sdlufy zXFJ1(xc*G1KE{K`%JW9+r^;!&!R_=fW1q|XDDN4CBanU?&%*9Lc8=Wp`3a6{Z~C9X zr{p&I<;j!aMee)dO!UA0Wc**#r}-Zok@)h&(mxvTte;#FF30yotUvFQuFIde4`;OA zEC2IcuY4*FxN=nOnQHGUgv*-;WnSW z_~TQ*ah&rd{_7Y2^SKXxefs_J{>2}VeExJ(_?`Rc6u(2tq2JZJBY*hc7e~HwK>fZb zr+!)aXQ7-&<~xLxC$6|F-!~(j*C#iO>(Ebd8s-_eR!Ta<-{4lngJ;42EH|8scya>P z?`xQLw|!9iSI$M4_JspFo_G$sSe5)uZ^~i4DKG6LUyA>+ZleA#j&*4K!S#>+d2n9* zB>64^|M&dvY^To6@*Nq|Q~7F&Jn7ZV?=kMjI-YVd9!B-M{n_cqieKrQ<1GzWrry>U zE(sQS;t#G$}5i`-1V!j&l}Hk$#7qI=G$Yx zLI30b_$Zw#4`MxQyf|`vI33<(KN)77O_+Tg%6_Ki!FDcrIMw^J{S0HTgi-gk?tj}iU;UpLC&U}w{rg^@+>iNV<$k0e4|KoH zeqzm!{jKF%xu4^W>#UQk*M9Dv@o77*9DBy$Zr|Fib`N0<|1n?K zo+{&?F!iy#acavQcVgYb{j_yF?fBvB5Bb-1zf60t_uF4zdEay1=01XaNhdA;wCmV| z@!G$a|CL)+-gQ6Xxa0Y2x)Y8Q#u4lPbhUTw*79_J%0+wDzoX6cM!k zT&71kXwOmmum9bdetK*#P zAOAnhe(}{!;f9v`5q~4zGcLIM1$HiY`~y8dJm;D3(=T6n=zQnTcCj7a-TsFJWgq+Q z^zWme#^29=yFc%1Kj!Z@=YDC=&yRjjjfY*pft~+QTFd{B{>H%r;ePnpl@>J#_#w+c|d(!o6;2-3R(*N+YxY6(nxGQ`Dzqz>4hr{mSXOtT* zI7<8L_d7bjKUgorw&SDttH0%14*b$6zw=}q7JjRpz)`c8RJ){CYaw~Wz{KxaI zAv5l|M(wi>aCVuYWoidw48)jzdh0?eC1u(iR)Gj z7QXGcA|9O2=SIiQ%lBSwAJf(Ek9OvNHE4JG&vxg#XSTZ>9J_(*dHy`5U;7^AJWo0P zf70Hr_p;o&)2r@!>y~9%?&=q{WXq$m#)BCLc>^++$z?u3kc%MK`8X5U0|y!*LL@|( z1PN?Jh6D)~#!x}R4DzwEpYxoj7P-$kRn^MX?@w-Sa&d8yT>SkP_n{tnR^lz4C+KO9 z*LA-9?r5Li#~E~do6qRM|F=1w=Fk5Jv}^WvzY`7rhrcTi_`L;@_b)DdAiNsuE5G+E zZ}rbF)@_*hJWghXId(QBQ*dgV}ryT1yadhO%ubDP~_#oCp&;9tl z!v`4uV!8OhFD`n(KT<#6x3IC5cLHfaZsJ{IE zCi?_w-gg|Ecf)6MKH$44u6Ot5F{gp}>zxmudUyU0{WuRr#$Wx%JDvHcv)(+nV|S|_ zi?@@1bH2}W=UeI5N58Q%kaY%(|0|7td=AftofPjEpRoV_ZG1^s{84pI4{i1Eg+)E=}8)?3o(55(Uw-MpXQ+aW*xFNF7deR+T9|KNS%{X+hq z&kinc1ac04as7@Q$o~K0a?f<-{eE_olh@;%#qU#)_IrVNxblJgZZ7@}`Qk0_XZyvw zc@K8(0T2IYxm&)keC3wsTlqiReSiLs{th4bZvM~uhX+(&w>+Tv!~dBkeiEL~`_=Em z|IuH*^S5KXUpyfGI`w+r_oIt{MH;)n4!o~I{2zV|_kRb8=Zn|T&f$mTE1cgGKjw3I zD(n@+Zzj$tG~f5&b>J6_7aW{8q&e@SpPjdgzhYj|Uh}JUSY$lj#s9I6>udA}$SiM0q9j48PR-y%*a4E&msPB>y+O-|$E9f1EEw+BtuJ zclT@ZN8D#^pZyjdQ$J8EM=yfwbfI63~$1g{2iUMHT9H2Z;ZezmvrM)Y6( ztvnMv=k!+|leBzo;}#nC>im*Fm4~KY#x0&sp6fpxzoWr@dgIj?r|JnUZ@zMz$4`5% z-W~trwY|qYV7y9?8v_G zq|TpN7qUy_U_6*7*lWDtd3@6AitO926Rabg&*lBTeL;An;Q`s-;Qd0ruSc98^^woI z@t1E9-sb7S_pSKi!vDeF8UOd}dhgf#508BB3%|I2H_$ZacJBv2yYd*K--{y7@8uz< z=lS>%_%QS>|Hplhi3gmxKzTsc4S7W40qIA4;TrG7IK=baBK^eAm9LV|;@n4Cbbd~{ z{6XfQ&*2yRzbkwM<0~%_k0>98e7JhjW4Q!S7*5pB<=u4ey5_uP*(u7{WuSh=Ks9v1AX4ppXHI? z^7rHWh%=D4l*_6v;n z3*#qP2Pj_}`=S1`K5p~vSA0$K;ZNJ|Ggdx*kG|AzaeeZDqxbZ`BkPLq?fegVH$NWD z^zcTWZ_m6RcEJ4L{)PIIzl)b)zLEb3X;*#U$Ik7Kko5?;L+s0bi06Fl$LBlG)w*!| zJYG}&2RlLDko}BwNc;9Toc^!v)*k&bfAp>$HQp1)Xa4;(^MmL2>}hQ`dktInN{?Kv zW7(6dFmt!}~56&rI zcHaMo&i+B`XLvi`&-Pc`U-&luk8>$;fbvK0&;Q}y4iEVAi@*Egau1c02=`KXev9}K z+#?nzj*#|=Bb2x6`-0)$9ex<~#tX(9#t*`y(VocfcTnEnDTcp0^LFxcefRGiuSZ-T z_VwYL_h^rL29clN1HOlIANu@#!}I-U`iI=;K}v@|=7TeammLkHxnP!mCifI6NQY!~ZGz z4q5yi_1@$CkYnZlY}fkWrKk_y$=~fIZ9JH~&cu(Mc|iCZ__xq{-~*|zeVG2P>l*p` z9q6h5x5XRo{2zSL=;L_ts;6-0|K#_6d+-i?-_P&g$fG_#((mT`h9{FJJlmW7iU<6U zN5AF&&}aWA@;j;Q|D#`?-{b%254>$yIk9#^^nm|4NIC3hP`+H=l5+BX;k)BCIX@21 znEl27y|~y{@qV}bALZ3I<1*tGFJ^s{FaI~`o);$=4o|4Qqx zzl)w^Uhvt$^LgGTj*wl8 zG^JdQj<_eyvE4?ov_ zi_}j#L~hdc1D=oiZtIOF8y*Td**6AV2ju@&K2W=}+~-$&5Lt)gPk0{hhaau|$)hm7 zmLu)_p?rK)WSSJH?J2r$O5#jXbs!kMHmOpbzCr zkLs0iLBEVM$oQgH<^{-l24a_?`jT%$pX7(s=X=9v`JOxm=U>x%d?MrLIL8Ctmy2^I z@5fVet|J}B|Ir`vE8qD~Ud#9CNBP5(?7S0pNKQ(#dTvqu z#^;HhOBt7Y&(VA10%rg5P^BMXdI-;Y!auNHvH5lne|K$vMdUMmkB`@$@5!IM*meC{ z$93#=ACK&#ew_7?z8GKXO|K#Lt~}w+JI*?jUw`KBcK(ZgD0g@+zo)aCM|j)5>s)%e z?ceB+el^Y^dbGd0{a4S5Yd>87u(w_QbDH;gFFeZ+f8#jpcwUc7*U#)@mCt^h=Y!+e z_%@%y+wng0O?#U6wCD2o?+f&t`!$q9zPDrbWN+_});sT$#?M+2J&_*d9PYTO_vS%% z;Qt?phvRvA3e$JDu4c{rWYy z>kGa?`8>CCZ*$_e&<|<)1rNx%>f<*!@nG^r#0S7b$sh5%Ao6k(56J#Mae%+P_yNz4 z_%r+gz8CoWqV;yaSibA|mG_$O4#pdX!yhX5&#t_mJR)(2)Vm_`5r>E!et3OOyrOdN z`S;%I{d2vgt7pgVNhkLixyOtC!qKDSQheX=eCBgbC6Yvc3pC$x<34wMpZSh2zXOB5 ziU)=N(@sLyQQ`rqU;aX_@iT-LhOk31bgIMAYWD5@yyQ+Ke>)`_>DK?ZoPbG zNPY!`_ai^FeaDS>1LFDynQi`_4EK0>U%4%Zp84)1{SnPaUh1)3c&vCW`!)O+{bfB2 zdv3pP$H{)o{a43>G~;4<`D66xxOhL;|1VRo{|A!y!(YK3nZ4LuIH$KpB+ht|R@Q67<~7IQV^H`E}$`@9~qnoX!X4Z~AOLAH#Y*M~m9YZ!f$Z=N0N@ zKMy_M|LW)uzt7;hYCIrvn~nzrivtYlU-y8yCrtas1%mQ2;?p<0-(Otv`RQgm&V=l4nKw!MPdvO;QxKh9Z{qkk*j8!zQ)J|Lg`tr%~a zyrTVu_fsBt2;0dnjQga2d;a}?jU8ww%umJ({%=L+4gKf$QLx*1+~P*%#n6xQ58^D5E8Y!WgY@t~l^=WY9OyWsAJWtZ(l6~od#OH<_Um8r&<^>xJYn%qwIBa; zKR-FpXYDJO=X>~z-(BRCA7FfZZh7P)T|M>ZeKDSF^p?D@uJb4VRpcCio|}KnPtvpx z*6!LL%MYJyT0Nt8)4RUX|Hu{Zy4!8z5u%U#_3!#!P$Abzd&?>uaJ4$u8L+XMR4PHyepe#HardTM-V2RXvVKb(Hu z+QU8hS=ZFNSRD4C|Bpd0mfOc;ov%DE&H6!_b!f$zH|KF~J~_|Wmzi(x!gXF!{+z}h zowtv8t!YR3<=yc2Nb}v19Y^ka^40#Jd=~S^^25JT@2nf@i~rl%-rM=V^qjq=@AAWS zzNiQJKI}z#ZhzH3cAg#V^MQJizjm|B!TbP`@xdWe2S z?k_a{4<1ndk9(i;LihMT;>_@0Mb6>tePGT{!}rBY!T%9gHoTSP-ks*W{$hF0_Pz@L zXWX3i4F5+x-8ViX_m3Gz_`P=_{aE?J(zLhogQe~F@QJ2}|5MI)^M96u50!7Vp5g!C zQ9i!JseEvt{#W?&>Sr;I=z-t+Sh0KGeFyRzSHEQtdn4Wtgg17+{lQ`PXk-08AkT*% zbY4unpgh9*`v%z6nm+S=r7dTD*)@nB;8~DQ9*}j{a(f)C`NIRiBf<~xzUO}SNB9Eb z)I!^pr-3(#&yjzD=U{)5_gncP<&n?u`-Sj{@_^iDmX`o&-}l4nG2WSe^&I`}{GaiE zuMhr$_`2c!lv`eoeHaCSw8uUdx-a4nvQBY+L7qX!6aEgq_VtyovYkJ^)=PczJw7L2 zer|X_?5*{N|2NPN)}fW><9n0D3Cdr^15!>tCzS7UedAosI_x+M?}z?br|l>AKe->` zc)?FGkI*l2gX-tqIOCeVo%v}0{}TTfPd9dB{G{Kf`|WX0mfxve`6}(vakyvSdwb1` zFdkUDpkC(JEy^4I_TYIwy0*{v6XOS+r)!*N-_v70&hOxizE(YAzvxpt#vfrG#PgAs z{|=4+$8T`Ha4*5{&HaZ%zK<`zUuL`w^I+xi=YB8!A9+Wgjx+0(d|#-3DaUu(hX12} z{GO0~_FKog>OJLiyp{i7f#1Ns>r-zB4{Kcs|bG z{muySOP-tI0a^9=y#>D$0>b}+tV^Ni{E4fP?=p?w#(wbh$;$uH|2^*SgUfwk^!GUa z54jj$@8HJogw%sxXh(g; z7m4tkKL6gO9lpOpKR!D2L%Ywfa*2~aag4?P!C%GuX@}See9<7|)xF3yu8;o9^Wo=V zCn4*!b`!5M@m9#k^A*o}!e8C>C(qV<=kkq97_SQ|#~I@%cixYBnHTYwrsdH0SNL9C{&5e_vmocTNYHPn>5%^+&l!=XvU>zO_Btr60&)f8ycb`>1c_ z|42Jd@P&*6&mE65-*--Dr#t^g`?llv1ksOrH=TUU59GuC@k`*R>4$0LkXH%QAE^G+ zZ+f0_XuR%^U*#Y1f9OMf#`DE1?$|kw^2ihaG8lj4^C@RO@9S@ep7ZDj`OI6NSI_Vr z_vBmcA^ogKeQ!&n7oJbM=X38Z|M$B~zlWz#-gp7~Q+=ZQ2IbED&tA^w$U`~hig&ut z|E1r?Wq7*uIQ>x%#b+94%D!Pc@q*deeZ(#+&v;~~gJUn2v!2fR*s=QBk#QvdjE&Er z>qq^Le-79F+u!W2b&2x;cH4UO$tBJFw?B{3{x}|#uYTli93S;>_!Ik$KGefKdzt#s zhwbe1GP`Hoofq-<=l|2RE`+mQTkr6H_K$NB`r+Jz9QCtu%FB4H@|SM>>hHVwKm2Ix ziT^v}=!4KMvwQK$;V;o|5WTXWs^9Nk$6@{-V}A3& zc|`lX53;^VM(I1HbsKIH%48`pZMx99Lr@`Lb|!vkus%E!7B|0f@ap5^;okK}RIcsA-^KiZlPY&ewC;t4vkB`;kdk6A6seJdgc`i=;^IbZS{<;3k3o<_YIh%Mr z`9I=+K0M^*yp2C6KVW+9QNoYWAAe7RxK7^hzOKB?=z)1DU$FC5_%rrjz6gHFa>P;k zySwTw9(BJDjQ^vaKzSPUP@G=(cH{lRi3@wg|H*Gso_hWLg7D1$O*;M${|&kD=Xjs> zHl%;V-GKPF_BWmnzKnL_k>&mHUo9sxexyU}nfKU-Z1?T_->x_6S@k$+$B}--=Z1}g zyk9(E*f>5$`+>i0KX$&4|6|+Vc)^JmBcJ!|=lk)0*sbMv{;xPd&K=AL(fRKEa(QvT zlV^TB6v((ZPvqCoqyE#5>__ac%!Bat<$ceWj3e(^PW`+8c3#=f3+Tu9_j76IhcJEv zeXVlU4(R;ucRsv-%RYm?LhYD!#BquL3n$J`-jDYjCy{nY&wQWprk#Dhke>BP`P4J| zCC&K{ME~kdj1R28VfqbO4|(qqrWeuu0RNbM!FIv1hvW+P_vw%R)IDSz$zL)4AZ#3G zT+iprbNbBR#A9S{>TA^x?ISlxzVcXa?S{z%vY(>&6`A+HyYy>C*5`PJ&dc!&`f0Tv zFB(5poMicx3p*Ew$faGx>&Q=y{`dK`*0c7T@g&WjDh z*OB&yx7f!Qeecg_yva`w;aMN(llH>q&CI8<7w6k2*Lf#$j^cg%dl0^1P4^sB9`((7 zK^i;4UPAP&UzR;&A3I`~lw%%;)JNKS%yjE+b|RkF1>~gsp!{C* zGu|&Ozj>W~h0U)sVh8qPj|0WN?B~vRWrrdAH04(NU>-8AJMR2E@AEvQyyLU$zxi;M z=a&DA2b34QH$V3N)bG~u#_Rt7A=duc-}}7$=;f@>eLmH%#v^-L?JRo(v%@o1Pk64c z@xR@__xYQ>(mr-aeLK3&Jh|FS>u`9>|Ly#SaevrF_wwNVIG4u*!vAp&=l5YbhZ8U6 zxn17q`NiMIQ`N8C5k89i-w!!=y;$m%|1-YAxI>O%VDL*KW6H?Fq`x&LTW zdlPqtoxvN*zYMQodFwNNk@rgv&!arfQ+Qi=G{(vN72!ch-$&&g{tvnFpUCGu`+r9D z1usl{*o%6ca>>DX^M8aDSzk!6=z1g1h<))s>yx|{{UeUee#tA+?j8qm_5<=~^{>(6 z%4ePx9Vy5Bm1Y`;lqq;oN>?&wWsb$ulB|BJ&hdn-*^pwr-J@6K4;u{DdSU( z57bUZ4)rZ>2rsL?ZqfdzXXJ34i67-29^*uus`DNF8YejQFu&H{2TDKjZ}NW1(RVNA z|Bvw7oCCt&9o;7G&-o4S_u^Q+LF|F^0_QCMFVDWIKH&G%U;N{YkM_LlEq*UVkIcV# zzUn2vctCkQem|Jsbr{|cJ^jg%hA)NxIP-wsQ)XQ@&WYUw{_6R$oBEwVc|iJQn&0td zoql$W>kIjvU-nVID~O&fZ<_c>_`hezXjty$mFJN6V|K~Yz%#*b(BGB!!_QzpkiUCz zl;@tLahLf09~^Rv#Q}yAa}eUehKIQ!T6nc9eFPN9LmAlp+ERVd4uA} z;-9*gy7E8sojG`9`3vI*Ils~Geh(Kv+w|NUcAty~i{DCrwu|41Jn%%x#e4YO${mjf zuT}rGGt%q}_$}OHAN!d1@mH;9$Mgc~=Maxdedw=x!|JErU9Z;j!Le|lXXY33W~U+V zC7=DQzx6YoZ}86!d03A`-uM5&_5=T)ew`8j)&9owiDM_(&CYkyFZI5Tzx{O_9XI5& z+|K_Ik83`t-Ns*o@O|>z@J*(f2iUdqVR%2%`1v4m4KL*QvyRI9SM^mdE%pb4W`^i(?d!PDh zAGu72@+$O)eAbl}@9`Us!+kz*=CyXm{>-{i+*9|m*{^NKap67E#YKh5jUIVUdbfj} z4?WxeE#IX+$=BZhc*75l^BwhncsXy}!{G<@&l|^hK>0iUIqX%QiT+_9t39lCRsM?f z_dFk1hs#&a;WJIQUe?bY9S`+PdE{K*%YFu(r}2H*pY4l{&l#CFlw0LZ?)SmoJM&@j z$NfH#`gMOtpOjax+IKwJV7%#>cXHpLKKF~z?`AMBSpUNOE#`;*)+5vpWBh%8N80oK z+VlTE)a!b^f6tlu>v-MDPyTtnHXlRm%W{qT%qPdic~-gR+atU!x9`)~(QaSUo^qV~ zG3!e5FrLi|cxcC2;u$+2T8r z`!@$q!SBHS=HMCpznpv!yczLcgA5ewO{hHZKJtG4-U#zv9@u`LdA-rwxqkJ(zW;Xq zkN1rO9EATPUzGP-`9Jxs`~P3`oZR~#bJN=7wFIUInGboH@~0Eyyf@6n8(Ef`2R=p<^4E6$WJtnhR;(^ zj2HSElt(2^Jf8d@=Mw92JwYz?7SG3X`VE%vJ#p^?+YjRD+$Z2&=pV@ME`R4h_(6CM z>+zf`k7YS_8~BiCM>+Tr@OuZ6FVFSz;PF`RKe~J;kaGZhpvXDdct7-Z%l~i_yX|402k z?>y3Z+H*+!Uwqd2yxRF=`cuC|&L7I({a^V$&avvbxKeTD|9FnS0hZ4>*m3uMF!h^W zc|h#b`jFpsMNI$cm2(;Loe{fT^|JPp{L!2IM|v4O#RI6{_>S5YnOBUf`%3(-^16<8 zK1DwAkptv?QT|UqhUaJhdQYGEzcZge{jaa>fV3N~`k4Oj=h^hsbL>-|CcbNryP_;e{Lw%N8`T1&E~G!aXTMy(87KPx2pK>1CNlrjpLp-Rx7p((`?($8 zeLX^sbsjMPoIjk8&gak0tDYM@&%x*5PZtNs_W(%~pTqw5{IJK6eE2}o{};js`uz7n zc)sDMcAn}{efV+60sm#ZU|7DW-+jv$;-B+=IQ$!S@a$q|BITZ5{cDitAKt;eob^6^ zQ-AH8ar&V=rPqGn*Uze_uO0ex{KT(c_4x-^{P^^IzW2v|10SZH-{=2Y=R^2B?QMQX z#&sN?@8!Yrv93QqtO@%=TWdMwB>vBMHP89P3z|Q?pZo%8`9DShp7C6c`FW53)9!8G z=kgzxM}GO4=7D@pykESUd=WfQ{L0iT&&asZUopO7NBBIRbFWmiyz_H?A9=l>SiQ&z z-xTkN9P*mQ-5IYX&pB~__UC@wANv;#wU6O{7WYLx#ec&4+V81X{%F$ZkMi+T9dClzr4x? z-$#7VAaQ{B9rAzY_^jb^Sij_Ph=U-1;;M*qHFT z75+|$KaXECsGozsLO%W{_Z|5?Q}!L>0m=7%EbZwRdEfWk9^QYqrn08V4G(UggJzE5E1S=|A;~mZM(%6nH=TF>$H(gZ7grR4()` z-^}{WL|6E^0(AyS|0fM zF^?GE?3DZWK9|?!`;OY{%p2^Reu$j|Jn!uG8b~tLM!4zmRjS^^5E$*57yjk~g#*>n!~T)z{AZ4PO^8==TA+ z??!p{+umawX;<9iH<6Qkcpl2bd(dv^dNg|GT!#E%{6ukkq}5aWXlb!?)tvY1Z+eOc z4dd-Z<}31rjHl_H=ff`7{L=6zy>{LLJ$R1X&-tAbk?)?}Fu&G( zKgSxAcIW zA@B36ee*jL+PN5yMmh4a$9u^Cxy^5W%sHR>v!{45zro~eoX+ES9_OA@p86i4>rv|x^U(PfHowBLThED{qp1JcVaMu=dpXo+ zoQQrm>G;1HPwmS8Ut~w<0lUDD0BILQ9HdGdlg-$y^l4;dHBjlbl+V!Nz|q(k&Un)lt0cBCBn z)Em+-^6lTO~r$>eQoU2@jS;1vtBx%MB`29ALmf| zO&mz*x!m&+=W@%Co-cG<`3^e# z%OKM8d%w&NctHGQ*7ZSnDxPC6+OO-n{9osO5j%q4<2+rw-}A%1us@OZj1QCtEM0ki z@4@ej!7JSId-P-C273+Xid`B9p7cHW11Gxs@% z*T4?gxAgnX&rf>SeBAd(_&?+woO_zc#rO=;9_vXc9|Dg9PXfZ53|fvj1^o_rI>#A* zlyrV6`@H=hl*i(I{epNn)ACv9v3$pG_#?hk$odn)lff_XK0G0~@>ivie*PkL$ZUrN5V=UT*Cu{qX!8pUL>j zr~T#{Z)O_5f$@A7ABcSMdtX1aihYERue_hUCw7qitm}aDqJAZB=|STbY;WcL$`Zy&%xtRAN+{*mT&#|BgjWP@Im-LApYW{ zjf>)URNxumQ~5m&{5t$l{k?cDc`x+l`|?cjSjPXQ*D(ICd%)~3%E@~pw{}Uq{F94+ z$hhMVYHxi%kbU`l|9HmB{&H@i-<^aE3)_G!3{;%^VXt}o|=Lz@8IhW8r`SrtjQe2+=9OoMK9gi2U zH@Losocs7pxwRh7_q=CZviBd613Oh7c@x$Zl{PjKBx1IRD z#<6rf-_HMWuH(JOs6Nx{ng5GV35lOXuF~-)gFByx9`rLj|DDf+=%42z>lo?Kb=mhl zSDx$Rz1J6g8CQtj@N0?R#;-R`{rR_N{;#;c_r*Q_553YpsGRbl@k(d@kN?-Izs@W7 zFdQ*Tv_tj#fFE;zi&frD0yLdzGGdsopsh{-{TzM_^(R$f>kp9%$dH%2-^InMjq!|zE>;39o z=i6$xmK!^Ml-9nG!*SYi>~7x=8qaX-I(|-^eX9LRL{F}_vktNzGyWjs4^n^Yxqbon z4baCImwS=ykKB(0e|{i(Tao;qU7w3zUejM*es7if`Q6o!dP#$nNB$Mp`uGkTdZWF; z&#&^_B7P?8U3_Aw-=e>Y9QBWWul*;De!}#G9+{V+!qUq4T797w;GD{2zW~ykEHUfACG7-#@w_JfG+5;Q=R&AG>}p5P#@i zIrHT);1}_aUR?TPd&ot*BK4D=cJ9}!-*p?0_=sma#}7W@>27&M%?0N*Go zC;P1JJAZaQP~P@v;4+TX!@3e;x2z||E&bzhK677J-;6)}+aUI(-H7s8^PcIscU;=~ zu#=r1lkX+Y&fhDseR)6n#rrG&$8+q@eC%?U$8mGtjIWgUgcll~u>OVeSHoi}H+o^b z=%4%qkpO8NsWF3*u!jI9flJ|@M>-T>@yzqOJhwmGN=VRZA zpW^pvNyDeX2Y&5>_!<6x7XMK{g?p}ij}RV&^~ks{{6O9#Kc0&Ej9X*Am>(KP#=2{} z#qr%kzPmx((=U(ldU>=r==ad@zwqyNq#W{n_dxk0^v!n^(X;KKkN7j=;^4*56aLZ2 zZ+ZPP`j36!zlDyM`@4Q!acg0GReYKHqW!hK+EuRP;65|`#vY6tJ==%x@!Ysb^{W4w zozQQ}g~bJi@O6!szneq*_~9$opRniHq4kG5|EE5alm5y7#Zyub?}zJi^vu2Yu`kCJ zxzguazxkav{Jd6hnnNRxZ@=oXnKMLMezux=smFwKZ z`1_uG4|4Jzd<*%k$3CyzeME1R3+a#Po!6qjoda0cTHofJAivkSBJ6xoxzfr@J>9$A zoobu;rimav2lT4@OeD0JRtrD`JFS2u=$Xa|35Mf?r> zTeUYLD8DyoLMrZ9VRvV_($w`e-lAZ-q}IpMLv1UdA{- zYiR-1s-%XWZ={yT*=zxh7%Vt=ps<2-OYmD~A0^TBnC zd8J({PkKM|f7r8jb)Wy!9&L|u$Qd&J=zT@xCmr^@H2vrKp!S0wK|bSW{rY{zM^IiK zkN)#~(D*vuC!g`!F`iFMe)MCx_?P?haX&_S;nx_4__k0!?@urM9Q!G}9sByzi{PjHg!7(oJ ze&O5szn$NMFZlS7R~~AxeA>N@AC$Kk-p_O2+OG9^Uh^I@{1)kW!h7|~a}3{zKSsHC zVZ0qkJ1g@3`rNc~JgRq>wHhXMt#5w$^UWwhySDh#`D=OY2%h`hxyUHWwGaHtbF-<8oM)|OMb+(JYM_I_(A$h z>@Vm8|Bmu}pAUR~ZD;;RePu6<4?NM1@-^~l@>BC2I_tB1!-_xR5AU^~P6Grx%g){gz12mDUte|1?O;k8}QOv6L-ocafq zLw*!HyKR5xCzIRn^U;6oJEXt*QQ5op$vx$dF8-K&?C^cmH~b&{lb7_qHasWu@E@<= z=YtRZ=MU^LxOg^LB)9qCfF=VdGhU!+1U8 z5!d(j-~YIMzw?KB%kDal#0Q1UEA=ez$NnWhiy!W}*XP6k?c?G&DL3Al@taYK>NG=2mT1_d;BDJNjqmu{~_lV^c%(lc8;tZ^{+f_`M2nKiuq6boa=U!M`2x} z|LAE&^k90j^Q_~2m4bW`+7O!)Ob}6`%|A|ucJ@&L4Ejt*89y1 z;=gg8V81ON`S3rK^UPxcJKbgM4cuo3mzT<}7l8!G3&-taXhxPq)eLS}x z>bG>59NCY4vi8dOl3wv_AIQOT<{gM$LG+GYoRR0`hv(45^Z7SV|KRZU z`#sut%6Pj_JB|Mf8F%}YU2Es)+kS-lm+^+p!;pDI`R3ECOZ$4Bz0)tpL;EUCeddq- zuzpal>&VXgl@G4_CF9?Egkny{^6-)DSMrj^6=ENxLFNB^L-b=mKfUsa zJJKHd0MQSK{*YTgFTYOz1iiI?GESsJ*NfJ*eVv_2h8V?cC#<>9{)%A;*R8F z;6vn9;{C!~9*%PwCymf^B|MV(@Llj#_Yerwyy zt}DEs&$++J``8Kdg6Gz^qIPHg>&tWEr1XcV*YDZ!e7%QidE_>Jsq{VUy+=s@?!8x> z8Ydemus?Sug$|^$-sTdQTNQ!#_Kx<*gV$ctHElK9(Gm#~%nO zhrbhApZ3l^FF#d1*a>_J-~aOe(%97>9_ce`C+?mT7uSA3qln*GF2Joih!6TR%bXKD2kAE_{We_ZP%}@IENK1-uXZpZ*(s7|(aakJT>`dk&9b`S>;XA><;T`A%G(Y2x-c zkHgEsFX{J?X8seWCr-b3pXZDNd>?vKfA~MeQ&J!LCeH7pquud$uK9gRa||0d3}@ipEL9uVFcJ9v2=5By5x z=3FxNq1{nG{wxR&hhE^>23I|&C&!KcpijpOJux0(_4GdLgwH{FQ{-e`fVNMX_VHWE z50z6Mams%+{x80HaQBltpU5Za$J0Lk{EFRadk=c_#e(dEfrA|FW*#L-ezrC-^^0 z=YH0AdB2eQ?#XNY=!VY0_FKH>{! z-H1mHXZ=u)bN`&j{C^nzgy-)cuJhe;@`TuddY$#)oTgpuRowNFzE{2aethy{#17*B z2DOXg^v--6dgr|my=hM(`X(JR9;Ct72gWm^kKa7~)c3`c|9wH8ljeO8 zJ&5M>ocG8Nt?$cAy}U=7_GmwZ$0UvY{htdmj`57~i1L)5UirjNul*fF56qKL{R|%% zFIe0moTOW)Mf^X`ts>{0Cztpw z(eu%M-`6-Z{NZ>V;?9uY`@m})+U@(Co9^*`Z_h_A-c!Dnk3`P77d-8mFAp;OU+Lld z7!P>A!4Ho5T=zu!g}?Ol=1 z^D8_i{a^Jf&&U01$IJ9r;s4}$8 z>Fb{E%4<>XefT@;aUR6$o!=wBa-njdALc_yf8ap|n=kS;lW)1#mwxX2AM>65!8iEa zdlKxUybs^!__42GAIx*}k;C*M)@8rn<+GphPhjtblwbKj((*m{4f1^WgDY>d@_&y1 z@MMlR^M`R4*LczNDbgQ#o%9(07k2*_`}FsH<@vl148Ifax1#n8FA4AUHguejlW`rC z$D{x9V76~Rjf=B?ywC6F$U89)@XOT~_g<}+e!7nOynDBeuo%|2+OFZY^uK9i^nf{TMcVitkO@GOU_gJy#B61Dy z_lqMAlY6(nIO1MkT=*#JllK#`Grr@8{^2jV4=(TZM zU|f+KUb69y_oaM%)-7KJug3pt1}QIJi(gB7_|@2(JgfJ4R~~THKXS;+hVV?-iTarL zurv5X<|pGN+TLS6kMlkR`4X(VYbUqoO!DKu z9^*a_)RX=Z?Wf1Eeuk8v{+|0!`|2aUhIP#H;m-H0`lJ0-zv^R;_s!0RFCIHpFRoXd zx9+FEd9~B_S>yij18i@{c$gW-osX%%>{Iaw`rGjo!`Ja#Kk|(Ei|SLqa_1>HPnwT^ z`rSyJtk$3;ynfO)w0m`2dxyTQZ z!+LkSfsev&vZK+n`Ru1W&rZX${a`Q3@pv99kL$=PkMB8e<2S>2xbz;T_rb+{b0WlyYYtk2jdi2gvviFF4%3h|@J7rPJp*&E)^@Ab+5 zF)r{{Ap9TwgV&;eAoeZab)Wx>2L$8OR{jmS;{8D6`so!{{*Q8|zkQ(o0%_)%JmBzt zypLRKz1VH(z5UOwe4zXvdWQ!DmG{$YeBz*Sgv0yEdk*in@_)=5^(RuV{NH--19{sY zW*=qzklXcOaJQTInUHKjOInD*@lXf2WfBK6Y^tXPg@APT8so!#(mpKW_+pTe#ytndy?~{h#k%yr_ zdwgJN^s@er2=mE!zxUz)#Lm(|E>Pf*UIb3C(09h-<9XX zKNgRuoY;rY9mkdTWSl4MJ_G-!JS*=f|EGPKk3X%whWG6U{AK|zxaz|eC02ZcjEozmxjNb_&@nHe&<6! zG^Bp`K=pRZ2c}Qvjs6nyk3Q+2d{uFf-bZD<@LsiPKFe2J{5n~`>cM~PX3^CgmFcj>s;?e&IA3QhxX*{ zkbihT?P1O-q@9Pih&@}+JxnjogDJP?D_?ToN7`S@mF|2TVi%MP(WCE$*1wO>s`uRN-JcvirzjXh@-u0tbbLak^`}On}JtOCgTXr1o_I%bKyoKX0 zPk4Tw-KbytLwm>x#>b4FooCpW<+P*hEu47Zv9EjfI{mU9<~QZSOqL`^Y$ASA%E1E}lcg z9$p{i!Sy}n8EM8-J2j0yOpEb<={sJO`q0C(OMC+IaDJej8IN7B@~qey;~&z#>qGmd z`y2WCartv1{Vv`tG>*^j_3>ODuix1i9!p;9lWUyYCvW23;J=u!@?d^{54)8w`|`q{ zk(O`!&KvycrN5s)`N@H_3)24|FG#)r+vWLZPkwYQw<7hDzK6c|#pQk04bq_X53cQF zccwqP@{2nnpK=e$Q5x@p1US z!{2fKe_MMzU-?MSiMR27=ltRSte^8La;ZnY@5i|Moj>}+d6#zZlT3^Ec?0-D&O6+z zwchDR{Rw;isNePPG2YXkyb^pT=NS0Dka}+Uzv)Ljisj@v`<`R(!F%u=#D3)cLhMI7 z?D@*KX>Yz4Z?*Du@+Y(l|G;=)pO3L}@E^U=?HY5mca|5MJ#`PvnF z)gRXGop0W!u6+^x5ucZw+MDxA9@pO&D&8-<&F)F#7qL!q4$7Xh+ZRVZ^925ldGz8y z{LAp=@f^M{gcszTRQinA&z~H6XI;?m!~b-=ysr%3L>wIVZMml^{}RGK;+KWQUCAGD zK8M#aj;nYq;^@A2;nm>tesR1f&sUrm(dU1DyeIzRc%R?(z^@~I=r)bt_$Qa=&ktS` zp3ZnZ{_8|L`eDB~bZ?)cIMc(!P zu;VPxXFlUz99?{2NV~>;4(@#K@%UJG@#7w$eqKCXs6LUK=PTmhnU4Px*L?JZeK~%O zCuo1k$1bp=r-%K}599xsM_-NqTlqfxROGma@@dMYKg&7Bbi9>*mfyFF@9Mn6`I+}t zzRP;#VeXYz@5MhDN9lM^J=GT`fAV6#_NRNf;$!~v%vXBPRUQqywI7VD^`fuQOFU-% zIrD(YcTZmQM;sdd%wX|4#z~#|j&mA+f_gyZJ7c_+h#c}*op5jtC z=a6Py21hUI?W`a4ggoSfyuV`4L)LSjhw*xkaL!ZfdyUT-(|>rD7x~nONdMG_h#pMG z1Iquw7u?tP&SxQy{wnCYH)-@5|B_#M>rdi$GQJ`2?|$T@87J#6{>b|2C;5-C_ZlzK z=$CyPL=U3+ho>f8xp}Yr9n(90hjyerVbAH&`sDc@^M1QMWk1;y{1)|`aphxtzQ^@p z|K=+<{YI{{J>90?9=DuaVZ2g^9XT#D?v9`NjSF^3e%Ltn9K?V3y8yT4Djzm(>BajY zGheNb^vJcIe|mn#S;zWb;-K&EydUc&`K+I!{0Dxce%l`3xBmbA-gER!e#khQw!Zkj zbH5q~{9W}Ne(h@KA77C7Ry$3Pvo8971oYav>i(}E!2Zj=4iaa^dK}6#`CUHdi*b8j zT=+cZpWngr`*`T5`>kQ|Z((t9#?Kiy$9$0wD~_*wxnEv+wLiHa^2Nvf=pyguS03-v zCqKNTMf(45k2Ls$Yq=HapXo2R=Zp{eD^d^rw*JpIq}-Z6>5=1qy|n-78#$Hx(`!El ze|#)ywdK@q*}`{>i%*M>+9hr z#?O6Q|LmM*y}$Q=+sZNC_-UbWbn;j1NANJ{H;hLKqgStc<^D`Mcq9hxfBSd3*NXb6WZ5dAuS0^d78nfACk-j~>;V z@q_V@=xvR|lV@XI!nYx>>nZ1N)5ZtZAK$0{)I)jigUhc`5B#!r0$*mm@L}?6jc@#4 z&qex&9E0i;{{y{Fe&v)`{{$Yja>`qrNH}(u{UuijKeyh`MW3X7PJirQ$oz4?(x0MU z&LJx@KWY!&kLQE>r^W%2@BRoMD1Ru%`+a=m8xIKo1WyTnhkWon=pBE;`HLS2?+0&1 zeefwD@o%&P|8z#|4E_&$@jGkrFd}h4@Oj1^!qYrG(!>>cjsN%MXeF zf!B*4jQ_*0FrRbm&KJS^`Mtg213d>&591*Z$32Gl!Vte;<^SY0>kst7 zhM&6S{}?aYWt>9%BE|tk{vFr&H{LUTa=xFq-)BYM;?surQ@**!%lgT=eMiP&y$|g@ zW%!TEX{W{o77x_9Uw@wd{p#AkwO{p*eoy}JoIUUV{_rm80X;dc>dEn9oc+CB#^d9Q zUYN(;8~@;vX8jOzecrFe|0x&eVB}*x!Jl_sG0nM+H1-L`|It6* zqu*;B9raY7&yADg9H^XcN80DTaILR??%40F#0Pp`cj6y+{*U#D`XAxi9_8ZyK-xtg z;P8O=cm(Z&_qq3l-Uj0zZut@WEnk8kaX&3z7k{0-KEn7v&h5zEJ+%10^uW4Id!+~C zMb#tu+JQV#JWM=8=`cH4`C{Hb+gbK^i^B&h-{@OAV1BbN(m(a?_%yGL<3R42x7ho{ zb&x;v+I-G?)<5xprqxsWI?Ky^(BJhu7#|ZduIyJK`>6X^JmK&~)N}SH>4){dKmWIm zYjVeD!1M9^jEv{{-q^#;AM^qL0%BLDTUXC|%D&`P>9_Sy+~587cAoKUfAN&rTXB8Z z-Tn2-{to}wJWM{*Gyd5@Xg~dbgm$Cc*`@Pic$|H$7j+b9nEUbED^r z;{J>iL_g$*@qZ!x^}XbFz7_Wu|JS+Hcm(uG90IuC?_c%DI5RHTIqhrj{ok+u1G2AE z&zIMDGI>Du<%#q2|BCQU@qQ~3$2a_+JRo|L_w)BQNc(*}zu(8Y(>>a^@qg@JKRN0L zjn9+!qrD$p+WqXp!(snFyrjRl@PDkAKRD8?+bfojJmjOVdq{oof9Q>R(PQ<4)UzV> ztpIqYsU%f&3KkrfVemo$&AMb_kAC5ok z&aaN=?W5SA^VRu)o=BHZInwlN$CY>R+$0}lyby6q&KJ&?=t;gNK8D|KAYcCPgJXR5 z_&)eL&T;Trp2z)O9_8YZXwUa7H+)p-kaIdbB7XM0IKIja!naNR^l#qtoH*a(EA9E! z_&!cDuH*86eAmzQ?w0T4y_E-aJp3*o`mz6m_G7;uIs_97p@!1>3w~F*OhUD-=h83SN#vFZ+>3^yZr6NuGa5MTEF}4 z@W{?P`{Ezga zU6IdtJOA-Bv@hnh>vX(Yd>`LqV|@KyBI7JC7@v1WpVPmc7qq@#A8~OXU+v-f!AD|m z@R!s}8olr51=cC-ZqW9V1HGXi(koBw`0V?R`w#n}`wjjp`oLesu4t!p=)GR-oc(?H zzIeYge(l&@_}%s8w;)+2Z@&zJah++)?hgJ)UA^*X=%ah>mcwprzjL9;Jf$7%2#jZ8T{d6jTtu4nd(izFewF__O}^#S z$1XqpB!A>F&eHfl@@;3%EvE5{s6R~Z(kp5w`Zvg}Jq%LM^zZh59OWk-%ebug8tl~i zMfzbnImP$gX;wSa{lt3>r?5@@1Z;){k^Z>ohQ1L_Z7y7+25f zz;hm$e+lmUEb>>6{1E-o&l*40_vDQjzn(K5jc1rWhLgYBW%=v)XD8@~_gBO}A`PzX z_I~w+N=akdm*1kw*f7qMPv!DKtG4`^`v$kJ<&d=|U|JW7fXC5WDa*W)K zTey#x{+az?yh_v0#&1RJLVXp7I{GtzPt#BJBCh8b>rJlEc6o1Ym;RW}zT^G+{p5cC zoA0$?uVMFs!+5!PM*T_b+jF+O-@Euf^h9~|PkZnz`lb1U^<(B0dVv3PoW0ji+<@aK z(r(YSx}z({?@mz{@9;fzsvWXYkc3IT@e4K@A850Lx219Pmf*ezq;n$_KJO{rHMMx|ILUl|TE=g-@e?edi|R#{+k1l8>C(kI{{e-)-?9ArYT1~?a$|Hd7jf>uyvk!zVjCHGH1Sq_%7d*zh3z<&t)sW#yRJf|D#-dAUo2$C(q@% z4*m@uCLVFh4X=fNEk7vYw@kUIr+mxTp8SctAMdHp`^X7`b29DBd+2ZYLG{w_f)och zyeIP9<0p;tS>yd|hkJg0A5gtazwHlcdDJj{%=29zXFbHj|02IfKI0>gIQjifTKwPs{}lZn-s9e|I6R_!26oK(1XK@x zA8z8l;(z2jk)Qs?Q^u1wUqIW{9@@u5c{;|SefvKD=e%S**BL2--U&;+H2k-h% z4@BP}`hyodBl@O1>*~bc$(!NNVYl#dgYZ@IY#{sopWURr=keX^|9kZZ;SVgoBfJIq z@EE*@-@GDzf%UD3e!slr<|1;lmbFbC$ zai4X*V(0o>#{1C@=`&ALIvx=Fvs~x(oo}Qb&r@&b|Ar4VzUIv9ls@x+*p>ZH55?yw z2lI#av14)Px!AvXKa4*L8BgmEtzRC{b<p8;n1L2jsuT@rQf6oLiA2zK?T|`Vm>D zm2*YcTk=JiWH(@uI6<+qvdXZg_+e&b;Krv3x|sP|<2g8OMh_Ke{~s_66Cmet3Cr5Z(`YhX2#A{K4hD?)A#cQ4T&YL=P*!ha5ha_e1`3 z`fo1p%m4BGe)>KSNPF+Y|6wooQ{InpCvFh?xzGRgyTXGj|Hu3Cw)goz^nu-g*dKC+ z*(HcSt$m*HygtYm(2x7)xt*^mj%(twR{jgW_m=OX-uwCZ&pSW3^Hn^D&)d=S^~Cj& zzR&;3pK(6sKd97$XNo*{q@EYgxblI%$N87{IX|EIKfc7I{^P(2fAoQ!4Bw}{#OsEArvQBWIIi!Ddo|XUm?8^Urb3u6}_&(~9_k#~qzrVeV%Y1)8{*3?E<+pk+k)I$P*497~dBkSeki3|3dl6#((B@{oy_OgFfKL z)YtHPFt3;Ub?!-LNJ;#}$erl0COah=9LjrS87Km47L zbr7B@o)4ao{d7m3lW#fWm6enC;$K!4MALlInV$aX$jWq3w@~S%z z$aDEUc|POI^tb084Qb9*@L=$r@^Sd%$jLcX`x=~fM~?X(kAA%Ii1Z)%i2EC4-zFWp zzWdyBGImEg;nUj(U+Zx$!fLlM9D8gJ`w{ir!+9RRXPg%Oq`bVJd`@ZV?;IRr2g+d_+A6Pp^UC+(NBNyP zcw6{1v3&J0yr=!59`vbxs&DwW;pOP>t7|!t{haqg=9~4%{~&Mr7l%JG9WSuP1q}ZO zKVg0H8|!(2eA13f*nV+~tDMQpIm&wCPsC|==l>dy5Ic5!#MN(6uHk1$Gw&Ghc$fSl z^y>4@L&;4^F!LxZ@Q1P%k!^-_4giP-`Y*6 z{a_dBZ|u=>@%H#TXpTAd&+{6EU@5#S7*2RDK^j|&sua9!xPyOQy|Hr+rmH%VC`N^eT zf3Jge_{YaMaqfWEBCZ@{{`_b`)*;g14^J5X_k$xJy8)5!Zx$r~KJWL%lfOR7A;*f? zJLxl`NAg3S|JAkJinLF9@Uy$+s-JSU|E+8Nudecba^VXZcX&h4{=d5DiFCZ_Pp@)> zeOECaFl2mbm-UQ(h;uInyCOey-Z&3uJt!Sd==w#y*=LAdciw+;IpGSmT++VhdGg)y zfA7-ABRPyKfwzmt3(-IKt3}?IM^$gbp{Dv^>b=Bq_?3AUJoOPkJe3EwAcQb~U>wACl+1&d@o>vF27uv7*z29B!W%xhi z!AQerxgYm?8KvVT(SN*@;~PJPz3%aUJKv{0&-VZscgmwbcrV9c&PA5T9vc50nZNRV zq4KCF?*$jf=lxyQ8+bDH67QE@?T7rW{9pF9qVbyYe(Fnm!@u`;bmi5#Jv%hw#LW7AN~DhJrMDqNXPGm@qA(VA^AT$^z-7VAOGR$lYeDJivtYD&$RtXQy>1%AoIj~C-~|5E8yhQuk!O>K>R$A^^0>K>(|Ny$_v_F z?|F`1o>^{cAi8(JclCHg<>|!1ww-{YD=ldewfqr<-1if8$*5c*-Mtp5y-$ z##jFFbzDBV=>3*2`hEC6+hcr&hl_uR9~)Hf=oNeD|3>Z)?h}l&=hS$=5dTCw=yxmR zG3W>R%&!&EJMG1f#0zw8pEl3=fTdmVxQVW>xJ`^_tyDZn*NX<7WW5lXZhAM5uTF#cq!If?M*M)854E$}AKdjsd&oEF zJdeK*Ss&MOw72#P`y*Z4E2um>|96(3`teuqA?FJ6cfQZKKjbxk=l|CFoiFk$>_5sg zagO$9UoTnju#=GWRJ-ZBZ?nHMKj=5{U?FnF4}q+I@Oz*<(l_7W`a2!y6Ta`+alVJ= z3;DnMk1y#zx*+99v;M{J$@hJENwYo~-}c4zo~vorAHSC;@5j0X-?!oqjx_xM(W5+> z@ptI&Z!Y=X^JU-o>uVZh{{>l3z<5CP@mH5}JJJvG=?7SPE&o4X-}~3s=l78Eftbq^`c2Q&`_s$&pIygouyOv`@tks@>)Wiitvjp>=oi!< zGQH2E=2i2zeK+L%OMCb6cE4WvBKax&3V15cnecyu_*X0c^i|W;_cs3T{QT{_80SY$ z{Da7|@_}dhtZ#TU^d#R|9AJFf@Jhx9QZ62jbG>nR;_!cro4=dF4JFUngTw!+-+SqM zJZJ48_s+v2|IYux-)S!*&rQdZP@Z$|BR&v*gm#Fl(vC!oS=C(6q=4FA0I zb#t$n`qz3b*Z()g_>C}LBP4Ez_vD4NQ}|Boi2j0)`5yGj^KklGzr~qPXMdaVp8vm6 zuC#n0_ILXo9^{i33@ZmRuZ^p5+}3?NokI84t(B_vx=Zme1WM;pOb# zAbRFIfATHF^|5Zk>mfh)epzP*)o1a4d^Zq&3La6c{^aoe_}4-6Z|&pU&vl&Txp(_- zyhQmU`8MQf+*c%jctGBR9}Cr&{#ACq#%J12`h{UMoU_lI_nU*1ff%-Z#ezb9^?OheaOf6|9<`EUNAf$ zesB2lXov9$lQWe6`}?Cm_@m(SOI#i8!|yR(#Mhbr*`=KP+=mB`Fg)4tWz@qyAIj%Z z59Qg<`_7ByI0vrz{BH37bLi*eLk|4Lmk0mH^JhmKqUHYbf*&0D-ZS{#hWVNJ4}X8? z=j+EkX8J+e_dRdnzmdjIGhdz$Kka8nfBAmi^v`nmExfm){2%Lq_kLL)ycfL23F^mi zUZOpacEp|kiw_*^oGm{G--W+KJ^D?Y`@ElMdU&wm`;KXG*fZ^kuCpVL<7e96V`kiW zpZnW`{jQ4fT9n7$e9n2#b$e|WKap}Fa;ra)e!`y;_gB8<(~tLmi-$DskABFLs?Sw^ z^+G=D#~EqQeEGZX{f6;;A$IIObiX`2p!;T69Ldhx$oIwnh3c<;j&%?IE`)EB2Xvm2 zZv5l(u=lY8?Ofh&^sw7Yc9VYQ{I6c(#aCaFP>D%*!`xX7Md~pliw{stpFJOMf*U8iHp6w2AL%RH1965V$)g$whwDWZ4A@!tx z<{jyK$T+O|=!bO3xtTQQWYP0~JQ4P}+5z)P`C7;11*vD1yME$N(l7Qgk@4k}VE*lR zIv-YhS=*<)>G+DBuj9G{UqX(?6@AV;+UM8U!^}_W<$c@Tc}~ic9}fzTK{`ZFqJ-tXRiApeKGGv4UAanBy)|N1`MXQz4a>Kfno$%Q|n9(ll5*YEiGJH6=B z-|6_qHO?=L|NG?1`^Eoxzn67t<^Nch?iUUJ>q@2!~LRg1J8%5;SrX%xZvvce)y^BmNLHXY~vIAMaQddc%^Q~U+e+r^)cum$C-xv&|k45!ybTS^<$-g4;ee@E=ihQ`S6A(3ef0iCJ^4Rb`cL+A#zTLy z|5)$qynZatT29-?{J`g|=i+~BdE=J5{du!<^E-KrZ@3@r@aLVUd0qQK&r#nT*Ew$- zB|q?Wd121q=lnJGF7Hb{nP2B&+UFAgBVPF?&qd;6eDEKTTjTl3cLHyY=d&D;e#Uj$ zDf58yhHlQc;;-`EKX~7@!F^QD<>H3>(O=+VQUCM%?TG)@xR2+2c%CXhf}_EaxE?N; z>zuRf_wl{A-;enD56JJweYb`^qSt@4-!Bh*>Du3K+z)#-*Ow~mTkgZ&;M?o3jkh@D zi}~jLXa2;`_q@DseLqb&=9{wnBYoCytY=yG{Neh)yY}y|{m0FHZL|Y+kjx9zqx&HL zTU7Rd&S$QB;9B{vU2&`8f#D{zQg80-I^Q#2Xa2^QbXR3uWnZ8DqY4Le9nU#!Rui-G zoi_Yc*O58*cGL=&bszPZdO+C^a^H zFrGK?vr_K&J9V=X?)?9?;e=7{b6$#eUPM2P-3R`-v;XwD7k+`l+j#zI&u6))FUl2V zUyD1MaG*(zE^Shs-hYr!*B?1w>%N2ijqUzC&A!EU z=RVSlvfsuXr5-HLxiXHdhj7yLlW5hS<4Mj%{JLxZRc`w!?r<2r4Al=!WdMqtYY(1u4qOn`GKByPVBL}44`Am6axc0idk9a!&E4TcE_}m}M73pW*@AC*Z`C2vg3Xib8Qol8x7)Ru< z*XNnr@s@h2`%QP|f839MIA1jWlqdI9zp|g0&)AFSy-wz(;(m^cnm^@G;pX*TrTfE; zant`?H_hj5>8JV^Pjnu3Ji{*;$0+Gjzm7-e0m^5-?2nW)ZpZ)30lD7&xgU2l{I4td z<2h(K>ic}1`_aE$x6Vqu>|dgc-?$Aw+e=bT*1;(^?MVJglmEO2^1Tn^&i-_FpGQ>k zMf;+zlj?jg>!|c|@)z#ye|hu$xVJXW$Nl-=teh|BdEeQ2pWpE#T(}cTzO?i6d@4Nm ztGzrZ?`3t%{lfpE%sXF>a6C^@o|{p*U;gtkb3gX6o&V9#9*+Bo&-1_XKH`0_$B#0e zyHYP-Z2sE+#T}*oxE?p{8~2OwKkol*j~`_o>PmfnzFjX47#?UoJ)cba+5uXRltYes z?^%01+2e`Q&g|cq*P`hsK-PEg`?<%$a=Xxjn+%C!I%=>2h zrz)TMhmXWQuG@7||8eJfIAH7mqbm=T*Rjs@Iio!w{q4*RH)H)cPjz#k=F+L-Mmf!mEe-d&b>Ya3=J|8>(ldHtu4}LfEKl1a| zX73jzAJ6B1a=F+6hNqd2I)A-#s+8l8gRj63Z3p^$+8545`>Sw2`a`MZ4nKq^r9Q%y zd;1^xUwBy5ep>ln>(lnlIbh1u`!D4oJ@X@9#{GQ$N57yS$Oki@8y_6la+bnb8ISs> zT+!73Q4L@AfY{N&iREYVzqnb4b$|Hct&vaKlmF=ACLg%vf8?jet>fDF2sQ3K@11(H z-xSv-e<{~dO$U2FIdgHp@V{`sDEYx2k8z~kTR5M}b?o!F4)=>Y%2P%Ay(o5C@-zS6 z7W+T^Ss$|QMOnA2xG8V!0_Ae7hvk2tHYGi|-}PY+NIKUyPDp&%4Wi!9I?VNF@jUDb z<$!#D^22Ri!g_Dscabjr+VtU4+{gb*&9CRS_zolWg8dQsXa0wi(oZjG-xsltgOBij znRQUk&B6H$C+8v`uCK$rwELiZ`nzvq{iz#&>(lQOvOgzZ*h40NJg>9gExV0BZ1v~= zS4bB(>2#&OhzEX(VkcQDN09eoXUW?@+ne%If5ew|Ctk{p-RbSok8rd9>PkPs9c4X@ z8$B<-`&sIP^&|Q1O8$M*$d{sA+#6s5&hqJDc>7vwM=1|Vxw}%IxK|BNX1sAdT6Q<)M6`Ka%-fzCL?@`%zS>D;d_D6HQ z**^9w>zVzz<;Hzu#D{X;4rSl3JM+lQ{Yc00x6Tu~GhV~}!i5rV<|Xio#@@66jiAN)Th;hp#8bhHA6Lf_;hQ}M11qP#`pI4lTQ8bfc!B&qvW4@MwvHJI8N7;f7P^O zl!vp=;qfQ`XxxO)eX9AP-L3ah+oiq_Vt+XDTE{_gK*yIHk9kZ^mj7VO z%~;2{-*WzCo^%`W&VovnXUZ~1R*9}nF3%l-bxLy0d6-=n|D`LySwykBkMRN~cs z@9mvO#lCOmROE|r;eOP&{A&KrAJ@O!!*%`#SA4Yl!@&qA4|{*(e)P+S!=HW_g#*$L z!vnkWe15RU)0OhzM!z^w@_|477fwgGRX-p8)DuemcHT!jH0baNm3 zb+qi4UftYsug?9#0mGftnftN+DIUiDPW!;(Vc~bBa6PV{aX@g8vdvLwfxWUa=)|#`CvcldB@mo z%KgZv9JjQWgZd2L3-4Q%>-Gc6Az$e#{|mn>yS{VY$2vuB6+WoFSKSW>Ab#SNuh72Q z1<8G~{}1mR>fWqZo&FlUK2GQ#uM@N@s)8# z`PtvFKbHG2e)FE5a&tZF^l*Lp56@BhmFsKf584G@Vt<7*ny=FE68*z}s84v8d@Xi& z*mGIW{*MC=DF2cF-QDc>C`w6|I2@hGd}w`XS}Ap(k>|JMmg8ZdN2IX z_BMaCqu&eQ`pcs~;?MrtbG=bG7vZqiBR;;vM}BeBp71{AjeIw6)sOc5K&j7r`5EgZ z+;9k#^^xvyA@?2VWogGMq|$?nA=;x_ux0i2aGmx`cIh z)cfRr@C)2s^-3Rle+z)<4csbIVpXa%c z<&$UO?|$=W?@E0UZ|Y5M%D&xkSL(Wg?;-MED*Um(^!{)-_v?&D+sAezecY()jqKZJ zzQ=Qh>)Dr3FWwhBgE>6y%=IYyv*bsWKad~XjEAoD8|!6O_Ivmfuk%CNO^ux!{LgV# z_FB$c;e3u?_RD?zk}hugvEx@a{o8Qo@e$A5e>1N|Xa48BNWG^&RXNOOeOE7T(~sSr z{E2vcF1)*OJ>2pCgXW` z-!GSvAL>n>_}|3jdDEYGa?%P}w6E6VY5f7h!xC*kCs$(L^WUG7thUy={T zPn72@^Qq6cJ^S|Q1v@7iwrGFm#$J-PC=DOqH?VbCnluzzg=S{Km zBmS?3(yyX&yqWiL{mg&mf2{Am9PzOZR{Qy1>)-DHzO(=LH+F#GfgfxfkbW&6EB*%u zpx^gn{{MWtUVKk? zxL?%kiI02{FZm?DxUCPB_M;up$BR0T&F@nPNB^LGqs-&DzZ=T_1*Jbmdq2(dmH8I` zxTEp}@{{K;ntdhng69@d`}gbne1km`>srP$>)zWJ^wu8km7(m12*-W6xsU5A`_waD zR{q>~eas6{;`97&{EHiQ{%5@Kn`8XMhyNwTev$nT+>-i(e^Fm@K-|t>RgO#Lqnva4 z@=y2#+>&_Vfu^I~q;`DPS5MdUtKKRc?Lqh`oJp==`^%lepE$p3{%IG>RXVp%;tfw( zxtICIPKkO_;WFksdKLF0{hDu!^M#L4Kb|A@+;9A&GtZL$aekQcqt;7Qp2xXm%9-=a zD)mCR`F|4JU-o~+(e#hodZM27zpRv3zFykLpPYjGJ*Pu>uDec0eLwH|jQ%y-_cD$< z|FeGJTyVCiyj=S~?XAqW&%@$tf7$v6e9m~`fSunR?f>LZ^&b$+`_Fqk#s7>a@xc{m z{wM!2KjD5V^Ai53>jL^6qq*!a(@*6|#R31g*#Qzx{)C%(((|G8Q#qAx`ekvba~>HU z7`2{?TRE@VuX{P-Z@JSh$NqHeFYb$&S6G)>-_A3*^>==&|KM6K>_g>ZrD=Ej2mPON z9=V_QmEE8GusEOn7B_ZZazEa;#;(qKhOhbEPt|-ezQbKp-%uD z=Cio0`66ApU(Wp!KX!l#pY~hl4bp+<@wN%Rmvg*vb3b-_#3%pLO?>h^&Ox&OifWI? z_{DCI`AxgOvIC4gSnTw|>s0K#xDR!G@bRX^gZujU|8H0FgIlFM_jh;hm+!HE_-51- zob8)YFRWvXe^%CO#;3Bc_-2&Z~gE-za4Rqlt2k9nW=7VL}6Z{OEDp2#obE$5_5d5&-&WzC7+H&0p-cVrSR6jqPDM z=ku1d<6QongSH=#Z~NC7|C2XUPmBY@*&lhof}8!H{QqW;Mb`!#gsf4J>G?w6>4>*K}vAMx9NW+gxA zZ_EdNKf!s)c|-2E@;}mde99GZ6HnLPKi2lgP5$9EXy!-mx4)E{zq}VndYOmGhwDb> z73$CVMIILZNBOl&x_8kYsq;Vb^JLGLoI?IbJh++vyYe0gca(aa?|W}|zxzyypZ<^X z9FRxK{TL77fZ>+OfB1@SIUxC!x7GgI=iJe~-WQHXdenbc;x!+uYQIQ6xgRxOa#zOd z8UJIRO~0a@c^+rHJ06R_Gfu+)2$#lm*zWw{s)C}xNlIY58T+Zq0IkL*X4fCkNb2x z?_{3o>iCOYmd_*RG26-aowyxW(c;Z%_vqSRGL9Z^`OJCVxA*g-#gV=m*U7K^PWwLU zvAc7f_Qrozp3C?%o>1z^`wdV3!+m4te^J7HxrguEk97%d(tR|P{Gj1}tRuQTAnovQ z3xCf4$S>C!FEj5ucQcM2Z1ENMi~Eb+A0=P2J>bm$n2$c+!=tn(O8?dE|3Qd{_^7|A z`Lx`<9<0~!T9xZ*@7@nc-~LftF!QzNKwRI%PMvkO<4-$(@~L}P%7H)Y?^5?w<>vaG z?fT09;5)oWgflVDi~n^FhJSYxe&v2MH-un>lb!4J{W{A2?B$`v8~@JhSl^tTKW4t` z=X)=O3-^m!9(h99!I97Na<1hyo+?+|75|#w;(FnZ+UL#om$rlX>O7YII`cm6V}4z^ zU)<4zo7HwsI^im%v;sV(H2jJF!}Emx;Wy8^F4gXdh@xU-Jj<&jW_XEx%G$FVE;vbgqzqeui}8#htIokz|Q~V z9`tkLb-Wth=P1u3+^pYJIY0GEJ6QkG@TKTno|G#}`Kk9P{Ez-r>ixy>$S2?bqx^S= zk}huZo&W!G9j?lMf~nX4^DJKD>l~1Bhd-H*&dn-+;eXn<8h>%L;zIIG>XrWJcjt=# z#qKW}{#UB~oaLjQ{7zz5`m60#%JsP)+n?pQgu~u~{)3%VwOiUfYJD=_Qm@R@^1oHx z*E!D+uWr)0Hl9;mX)p6B_oUwx2Q%H&zvqAbuAg>(a&3p#bJ%cO z+W~IZ+efz?mgiM*Kl@Y0X=%oP+IwyX(v|at`^hb}|D)W+J>~qw$9zD))Na`Gn>WW( zjPL#N9YX&5K|A7xEB<)%|K8?LdWKWU_sjw1eXNt=g*=tygW4J5#$M3#w4Cql=WAUD z;|?r+LE z&iJ)kV4pyKNLc3ASLIy!UwBdHBJ@Xi9Q-SGez7x||38rPrs00k)gL$W z5&hTal<`u(%wuZOr5xE;%5C5gWpC$v2RDOXd2T!XK_z@IKl>Z)Cgph4m%OC7nfqzo z>}%wHa5n8NQR>C}!trvBG8}N_e*L=r$9!Mnf5k6NC;3$A7v?khC_5m-ciu<;*3Et4 ze(YQMK1gvt_`dZW?srLhySNUCoo7`3M|$!D&m*vp!Oe4;`=UGtjVIdIKlB561NXZx znbm$_e{nw^dkFiD<*s^Q{PgxCUdO+Dk9i3<>NwI)j(nWCsbBpauZ&0MW!==P%2cmIMYAc4JRFxczrI+-`Qi`D2IaYIiA>m(*AJ0u1~gj z>bzPw9d<|5V^q7Nw|0A@ySu&1_jkRsDeeE&NRRdDSKIyi6OZoP|IX&7-{DVt5fZjnwYQ(C=(^vaZBo-e#O3@c`8c#F)!IaYo4Ir6Q1$W$EV{j<1qZs|7ozU;5zYjCEt!m zwZ~`t#oHZk#lLiC+=T-=&%}>+aiB<^$J*^M6o? zAAiOtO1&Dc>?4h@%5A=C{;_;@zTSDb-tRb`Ydzz5ySuN8RLbXg%YQoF+xubqMR6ed z5Ba8_N4XzD|064FRAzkNzng8MM zyw3AV`yZbJt~0oP_MD7=xLR{jSEd}+9254iF@_#gWx{G)^q z7o7QD`Ey;nIPT-kYH>53Q*grL^_iC$&i(Hh2YlXj&CHQ&kq^L4Hd z`b)RhbAKuaao(JYz{)a#F zGXDiYi|gng{-?TrDE=4Dq89hFo^+q_zwGbLzt08u;T*r^j2$CtI`mI@UpP&<;Rp76 z>e+O*jgsKH2f@I1T?R4HwKh8Xjpm!Y513XUY+t2@it9P+xGm zoP);h4_;SFc{smYN;&>{<1Fw$%TpXsdoBJCa$~IfxUX}-a6dQ`@s@oV90l%2e!CKX z@kuxh@lg)da)blInfUI=IcK83b?#?4_!##`;YZdVyv+QR+Wv$mzenXd@p+&9Y5nd( z_Ccueu@8rX*10X_qrQJ*9&w$*^DW$u`{8fo7p2^;m!jrp&42Mf%TeuMzKi#9y`S?X zUhMoNrq>#FI$)t+hBnu-4i+zzgQ{^JOLbJ*MQKU@C8fnwKJN`K}55TiN9ddhvMc5C_H zFYB#u$Muy1>MuXZ_w`r@aL(6#fp&jzN7tR7?p*H2P01(zSefHbeDJ?0oDB}hyc`Y) z_mdA4|D(V89$Rjh`=hQK&4;{?e)7%e_w?IR`>pnc?33Y**u@b}u0?xUzwUQD|4O;# zJEZUWC-!~v)6{3|ETgO|sb7_KNZISb^WRq6$vcYC~5cINDbJT~Ur9VU|Kt9g@oBv!obH69K1e?r-Vpwm{*(UFd8G9u*V6va^x4-iZo7u7 zL`l!<>-od{XXW^PGWUzx|ItqHC-Or)@HjQ+R!iMig>MzF$vQVmJ2KzNW#KdS%i^=9 zLpaiNT-mSK_v#iUeEX-{lWEz_CEAi*M~WO=sulr zS=V{p?|p^)MOXgEbJO*ynte+&{V=-r+qg;pQvF!ZsYlxdK0*KC{6s0^Bi}739_aX= zc^>KF|F^0AjroIf{q#$?q5U&lKl9dXM@&EQ{Y&h}>c6?#r}QB3p^?Q4FcOIqE z?vMBOXJ3jtD%bP>0qhgyba(gtze;%a`RJpeJm*o`Rrj4uX@A}ESG~{Yg7MGi7wK>E z5IG?4VaPA@;FF=WJ4*k6t5NRG{b(QEN6miQdJ6w5B|h2(WnO^)kq+q-uX^Nt-JkX% zf0QF?KEof21H%0Xk1`MVT*-TlXwBQsx8ZK*yo`EcT!#BGuj#J;Zam%6jUC?16KF@% zDGug5p6^YXAL@m0%!^%_2faU6S7+ajW^RpZqWVk@~Vf)cJY)&D&dlC!FJN=70EqIpV*h zj0dhqDL3vY>lECqbM&w8{K@<7@7zyieT09Mb%yud-xc1-b(MTEAK*q=r!elr0r{?m z^MD%OcS-3Fo&Uv6dGybJM&y5t|A!+z6#f^bAL>5me}wyD4<9|}fA@C|cz+M?|3=6c z@l)@eOOmejac_FBK|L|gl5Xa$XrGt3?tGthwclmMpZXeJ4Yk@tu0=j(C&k8ws=j4eecT4I48?| z7KNBPzoBxyBUj}4bIuFpi>3otA&yUkdNDeab%Yk6XH(vyEom_Tl8G z`-f}AA3ni#c?n!YyB+E;c0ByQ*!EL7@0)Pem(K<5{$js4r3kN$}pZbQ0` z1MFl?r)$5@da!*-H|3mLOtiJU7XkDfBsK|@bbHE=a=-=^uL7b?r^KhQ0Ec)1>srOsq}Z;)C=oo)bD17bJIU#H(Odf*78~Z`Hyex0nxNi zxM18->$B|t!uc+7S?;5KQop*3tJ=<&`QOb^KJ6M=f5CtGPDWIFK>Tm);VgggL%;t= z`!SAD{%gVhk@uu3|NoVzX&?0C@%-gK4*zmf>;v)Vzq>q_;ZminSK)`mm;Zgt{Eu@M zJlC;1RQbN1oQ?e^@w48%KH_nGDffc|>Mr{~_7N`+`@d4t_ng!ZhX2j+wEA$U>*(L^ z{VaAND(hGK5#iv6Uyt%~-j{g!Pl)>!?G_kMwYWeqP1tt zK8*FI>wNr~pUpRX%XI=?EJ+UrES^rs2a98RdJ4#k7a#+>> zgODC>(q}!5h69ps$}K-;UX4AV{gw5;>%*L9El$FEZ{|Yg&voO>|BBzq19^Y%dhw|C z_c>kjLA~HlJ;~FlANif_OTEyZDCMHQP}bGffBlz0x99fiy6r}Oxz4)WaOd`w#BcwR z3*rthvK;69kLR%UI`co~W4T}W->P!GYa?Gtr__Gw{f0|^P}6%c{zrXK&&>PLYH!E0 z|0n71mFN#VSLFY!>$MBDJ$x?B`(^UQ`mHn^Z{~k1_ltX7&(Q9sqZ04jAB%ryXu0P%VQJxpNb6z<1ZqabN z*b~a>D8KQ)xsShd{zrO!9A0uW4hTnmWFA4OKa}Te*Z32k`@`aY^L#VUKcv&IhkHh; zU*n7Ya=w#l`r#(wD)e9L+y8msW_H{1s+F#p1IsR&p6@3{rZEZ z#Dkl9Mk%N6`_EMSLcdQ){)mV0DB;yg-+bQN%NKiR=Nr;{yxqTkU-hzGVAeyfU&>zH z{+jhk@oM~;f1}JBoWnV);lA6#!~fhb>V9n>$8sX<#~jCO2^TalX)u6Uqa5e~?Goh#~QUJK`o`h7mu!E!owYJ`&mvL3=6Wu0Ss=lqZRJon3g zd)arQavI~G)1BjUKYrEu=H!F*n0!*Z$IzWB?jtY6c+zNf!(zqnZk7#=$)`xW&Hm#}`}R>uFwz5kV#Kjm?s z4o9TEupi>O+|U2|T90xeIH3K{{XXIH|B&2IJ#^lPyW4A-U;ABgHtX+%e7A=;KNY|E(S6Bow|HUlS@pM;&-BATV)qy2JGpYesJyNCpY_K7K;UqG4-h*) z`5kWU{%p6z_vgKRJ7@-@DzCl5^f6?YB)gTKL3XXQW6 za3gu2_I~ox)VuAfeIDb~epfs&Zn#e8f3$n&g7z!Z@m#q7k9IzII{r_5Yil>w4RRBB zhtE~`9{xYtpMyW%^n1e&kmn=kaA*B^xLKd$&(i{4$a?69dwkdj!g+o)l&2Qg3CB5O z*6;a$hyM%aKA!v6hrjzk?fpm}_sb)msJsczM|gOh`OqJZ=e{9Y{LlXN+pXWg|KtJ2 z1IOZNCHK2A)`j>-S!a#pC8at zC>L(NZ|Hj5^S8XGF5bsDk^jM;u&0!p@jXZEDU*+IJ-+V<7i85Co+STcT`E^9h2O~m ziPv-0a6sw_{$5JG@_l{PdUF5H`Wd(NM}G(hgkRB4a;_u)lbfbq$e-)Mng6jqb=?>K z7yG+#zU<4*H8UF15HqO&!4`}-np8im3Kh+(( zK+~mv;7`7&&ozIHGpAK$iJ?k9X59K-J`GcI}V?6s@TKDg> zJx^cXywhTO2m^fLbrkV{7?yo%aav5!H4kUD`eT zk9L%^)cNhvL7vk6c zMK|?{JN~7y!_iKM`g^#=n|R&z~kD$I+?$+JJt9w0v zd~fF&@&ww8^iaxAdQtL6KSkjZU1>+_NuJ3(Wc?+d_1}h>2fn|xAM-36ko5X<0(a&s z<^jr``QW=fe3WrTc$9E)Ki&PK@mHVE|4cVrtlmeEF7=-D&y;#FT;`E{7j{%wlDCNaXyPzxoBYxszd{OSwdJa-fxJ=afB+rAICu+T8c=#Xlr5d}` z`j1CAAni^$!U64%NBched-~nX`!4Z6>e=yIyifQ2-GAnJ*yV-)nUDAP@o|6A_^agq ztG%7LpZQE4=s2YQ^;a1eUgvv*w6F0n-sg1JbUxUwv;H9*@uG~&uCy0!>YsGbFSl^k zEB(THke||D9&O<~M@)Ff?L0qG&W9r${e*cf8txY*KEfqD&l%!F$w%^oCZCVD_-6h` zIkX3??~L*sz~ARVy$5AJz~6Zx+%MYspU-ve6Z&&s|2+3giMQE}*SYe){0~H>oM-lb;e4w0JV$%RwcNd4!&&F@QZL0_ogdHnUwB{mVB9PB zdl7e~Be$bG@H_JhzoNcND?II$_ru|8+NsI^;dtI z6Tpq&4LP5=a=*Bf&nVo_@ss?CukIYL{Ad10f8jqnbzNRa|IT=+dZd52F1H>@ zcjiImKi9MOQLo(3^N{PQ*Wy0bKimiV!#{2H$GKeF^Us4H!Abry{+|I~;eWkwoKkrf zc72o+C7zrgu6PokT&H-_^W4UJ`@pODpY>S(+mPEb&RGA$A3f(EwI0a_*Qw{UQ)#!uywpCn zzxP*o%2Vf{`MxvxEACkQPk;F%?Zx*3U2kGn<$Blu&SGbW8})hkFSd4iX`KJ%ImbC$ z+wF&&@?ARJpA6+G@spu)K<>v*5WRkl^Te!cv>QZSZ-)P=>v`YrjdWRmzI^TPH@&f) z^CiAd_jSU@`#LoG;r@R5{#hBlcT@+{X*7J>~~f30kD)#q~38xz5qP%XPJOS(FPm?bVg})Nu7*o1@$3uJ^&6oR90=a@=xp zuc!WOm$Xlm=R$9{__P1OKT3XMk0}3RUqE^)>w)YCqRwlv_o?rFF^|#SDD|O+-$i|H z@t-HJ*ZWA_^LtD3jX&ifUE04Z?Qj3GK2k1}`efcg*$1NV&RN6z5>D<*y7oWqco=uO z?GMCnzmV4vUJf75-2ELt^egg%k{|mS;T=CH=Y9Ki!jn$jm-sWT<$v^N=ZnAF=MR;9 z%Zcu7+=%t;lP!J!yUTM`&Y;3O*{^f%*?sey`+oe*#{cZE?vp$J)Bk^r`{_6CYgf)E z-(!C(|MUNxv~PD)pASbqqtrKU`j!52HTKn{6Q%!=FVy|?{~P}!efQxi`H&mb{|rno z{H2t9(myXL`6i!_hVq<2DIf8p;eNJH&IzCMKl0^#X8*>`d>o}5-wk(H#ue^WS)bA# ztQX-gxXC9l6SvQSOZ>0+9^olxSJJ_ak`Dd)k|sZ0=~wJuqV#|FGb-iv zdbGZWXgo)|Kl2y6_PlS%d{XlVKyg+-9UN|30{l(rds=aC1`K`P!{f~au`^lp% zzT(Jz9MpL5zq-^T*HQ0VxnJBf|6?5`kBdEDxZcd)h?jh>O8L+DAMieVXxnS3ubw1esSX`QZN_lx6qO1d$w_P7}J3y}2dq2lR zp8v1!<2T&z_C9{kcpve|E!1!f_h-&4ukP^~4?7{}1Nfd?@3IoV;Y$vOsDH?A1L3@ zF4p>5+o9^Q>eKqpx*L8(KZjqq&Zj)=1J3v#<%W}JcW3_pwD*&;1El}ud@kPu3BjBga-Qd|`^+zH z@^5(V3r9@5lMmK|a?a9lKl`!u$hgV);khk02?xZ!kM(ct{N#R=AO6RB`qQnwuuHSu z{@{1NdZvyKuEPyHpH$}(vMwQA<{7yc@4sIj?hl^n z*P~wHe^LJ{B7cL^W&Ps5IeZ57{4e`w_@CG1hSanB>wE_>T#<9RriZ;D+$na4rL>#h zU8f#cPti|i)nATD_<29he?APa!U5d}pwt)kI$gC3nCmI^7PbFrmzndz`7U(vEbFVd znEMmHSLnHFIf(xgV4cspkAB>ha=9LqCoxazj-3PhA)@`;uURLfw13q6 z`rSb8$4&jr+PR(l({p1C0Vi=)5&2!Hw;?KZ39 zo%6wP`{IB4J1@!q>N%8s`_=r9=K=Fyalo1TFyIedT?zJN3Jt)VuRdI9}X!?$-XO8;++tcF?+uW5=G$>j}?yPMyC? zomV{%$~eh9{bcVCs^`bDe}vO`URACK|8t+|_xcD2AE3TeIUeC24u9Gu`rk+Wvc7k} zduN<`(_Kn`yt{w@KAP|9=X?2nKc9B?znkyv=jl}1;lY;fxiX&new*;-FZOh0$K$>} z=K!PGcNaIb-10caJ8m@h<0ikRQ}#UMlW@^5c6V2}FK(1@^k?!<`=j)yo<9Dx4=NXW ze^bgGe&qAS|45K8=dZJQ+Waxj3HRNWp8O9t<7`#(qkoNO?jxM@yqo|Is9U=t`j76i z|I?lCxUP2Ku~Up)uXg10Ytx%KAmvYfpYHiV>A&t5RpxW|YbxzyxMu9*& zs>WZu@5>RM`%#|1^gGrC@UyPWADnkViC-?IoBGln^_)EA_db>W6F2eW?s_Ra`J=u_ zw~vSTvtF@2%YOFpmS5e(>wV#^vwbhmKk|WwzgZ8?7xXXNBlBeOJL;G5(v|wK-kq1Y zZo6fks_zr7?Va?kPv>pw$@2I;1Nz%)2k3Lb_rvsmo;O`xztpT_ETSoUdu4gZ_tEBijyi${Au^Yc9Zw_fjVco}ZvKXNzy z+5eG#w8F8Tg6BnzuXr8nx1*h5gzptCeov70 zmJ`y>v}1JUP2`XEW#3#J(D}7Eqy2#Ea-wqEpKuqqs&!z+<9*4uyoLOeKIyo>f4b#E z`#b!L%NWk*g8%o`-j8y2JHUi1mHWw)e2&2VT<4UUf86;FW3R_5ukp~{#B0Bi`&kbC zDHqpMzJ#lKp6k2f@AcUEpX>MVp;Fq_?*v9!-&xMm*oFORZzs4P>psqL((azqeRcod z8wxkc|2p7;@;{XGzNO^%wc%F76G?}D_I!R9eiW4l72gZ@Nqfo%W5G^8=(68z5;eK#`cna+tJJ}i!_5=L0ZgIS1y%u}GDB)~x`5)^X z_j&TaviGB0>^Gx?Z)9j~=GslVLvcCK-BKtvBGLA?pCkNB<{1&PV%y55n_)L4U@l{n_^MJvZZo z=MCJ>=cWJg;GC)JMY-KeyS*RhZy9&r+qfU~AqSl8|E`Uv3ig3=K;q|ne(3dUa>aZv z5DrMX`1AZO{mEE=vOmV&4{P&(y*>Y5-uWN)gzOho^7F~g`{aP|Dc29tcei~d>zH4U z_;_#d>tWw}Yplb5HQMdQXy0Fr^q3FWe^M_|;$dEi9_`&2N7x%u-yaQ5hGHLwzu(LA zJh0qD9?1U2e7Mf`yV~q)akKu@-}N|L6Ze_A4>uj{_~7N(g(W@52l;`Y%iF^HJ$|M>|XMS1o7GSJ(M#{i!eZk;F?qn_l=qwD{jzKiR*~ zf0zed2YPOrexQ5iB&36XlySs+W9%_exD5R=ypMe=;iI${NNrV*PVHZu=Q-=4I7$sc>T3Bb@P)+FrDa;n()VZ906Xl>X!YN7&br zF8g=;S9o9XKg&`6v_tm&*&o#TIM?H=JM-u9`{T~1nOCFofb7H1l>Ual^RV2LeG&Cr z?G(EQ+pDh6^9AwP?z7UL@IO=gXWmaZ?&v@E&)DfYe=t7qXFNpdr?~B}#c`N7X&)30 z$Ucv7DBS4DP{!%wp}c2MKUntT?qlh<>@R7rsQXmU>GGVHKi%EA)SElU3b(tv^SL{d zvQF_k_;;>-zQzCjO?l6cn{+?h@^^37cQ&Q|^?z><_wIgQxsCVTJ^uQR{uf)k<$kcG z`*#yhW4?a4g)2_yK79SoSMApcPy2e`@&3eTJr&0!Ka4l|WpPc*|Mp%!m3G8GN_ydb zDDC=aQ8_@qV;GL{-qsID*Lkn>n{hw=&v8-8x&(jMCuI*fuP3vvjE4J_ez(OV7vniV zd{Nrl_~n4)FX^fBKgx}J9nbhDel%{Be8PRYQXbdS>dOBZ|L*(31;hPR`r*8;u5zYc z=KMRqkgoH$N;#=_(vLd+=l7som-|JFN72sIUsN8H^QhrS@9+JylzziHM7{q^?XUND z{&ZC1Kk`30oOX81H}I!b>8CSC3r}0M{sV6K=efO~`gA^T{5GV7`nxZ|2;8-YdMd*KaiKbX40T^U6^f_v9~X`&54*AM_vEgMJ;g zp0w|#eo}7V2XW5E`_dnsAL@T0^kd>>z0j5UBhUBJ*Z1-K+CF~6{osM}DD3BMY-9I+mz;!hg#U%}UDCOI zt#A1>cCxm6srjP4;VF(Mc&h7m`=Rz?%zIo%=?78ElX9uCgX3H+911%w_)76V^QC>) ztJ`(*?f2o}f#$Q@_c8wAd{OENch@7oO})co_+Hzsk&pbJ1N$-i0q02lz8n1#UaNn% z`_g`lg2TVM_Vd5C6C9HEN&IWRX!oo5ZC$6l@Vu_QeJmH8m-V>q2G5eSa3A|zl=V<= zx88on&wW0}U z^FPAD0j<}xpImO{t@F6CzgGFlUpQvxeAo%HUUWZBImutWKd`^Z2T6~1k=GN>`6~Ne z?4{rz@;U6ye4hMp8=uz)&*S;=z3qE|JZ0d1hIgL$Xd8$8rviVz{}&~l>m%MM@xlvv zKIK0l@Ijv6eD@E%G3*R^zTX=BkLP`qe7H~0{tr&cz7n3es{HPwjpNbJTt~3qkQc!H z+>i3~!Vb`NLbzY4{V&|`HzVJ049*Y3^?tLBOE?(q91e(G9Q6-JBYgN4_AvI>QrjDQ zJ-7<{aK=a9kHg!j2Y6d4?eWPLKi~TcZ_Ix<oJt|9`%PkQ{1G_xR>IsfB+>YZ|-#1rl5*nZ{%J2`k{)b;Uf*TZwxd98S#^HGI! zUM#z!?j}FD$=~en`9YrNUN3t>-NggU*U@fB&N18nr5;yJKaWzcwAZTCGyc(Bk2^~I z&Ns7C@99tdy#eC_f5r*QKH7d*{n&n*{#@Tx==_iSpKSS)|Ahm>#n~6eK8NR=``6g5 z)c-in_#gZMp2oa`(k@?YZup<`J)DdF5bhWKd9S*E>%m|N5)czt^Mnol*T~H}!`->V7`8n!*QXE%*@8f>sUBCA@+a;2Z^dIVn z_eD|4%k``mv!3+1Bp0OK=*KAY1>vLgbLM}>Zxp)-#w+$cj$2f2q}`u(fpQ*sf%~8D z@6UJb#N>bO@8lQjIpXj?RIb8%Ncf8L5BZQ|l~Rt|TYlj=<-V2fa1IvA?)E zl;^{ZruzGxWbFgxe}*G}=iD#;hLgW^4!HVLA1lw3E6N2a@7e!P^e29~VArw(Ebhnk z@VQkxZ=?Rou8;WPWnGQu#o}{5@9j!^!Tnf&(m$djdmGPN(_iZ+*TXHt-*m$P$bVF> zC+7GaQ*!uf?>UNLbU;NK_EM%aJKHn5@+UIF{iVdC{h;@U z`*}V!9MO4;e952Ej`m;qlbp}-WBTEFwnx722j@%sSiiYWJ2CGPAM0)Vaesg5eQCGi zSj0p4qk8UJj>GkS4!pRr{m}jfS5Lo6IWrET84q${c{p6p`Y0tF?UZ)#`+v6I%mJxy z$3^V#;BWSa%1`nYwY*&CdvwLU0N4xW159UeSsQ2M6uITfZ z{|vL=k^e>Eeb}$Pa_t|s{iXcx2gCaBKkWO=eCMyYpZkW7H~s{_#2tl`VBd#5){~*| zCDs+JPh4NrdsX(Qth)#gAN$oPFaM>L4`M&a^Uia`D&y$Gjcf5gT=*90zz4C%>-%Qb zZgs%u>+1Qxm)XzL zF3ywTe%a^G=KXTB^i?Mc2#&-|ynRgbg_*PpK$7ZslLZ1?ns*}ji{ zWB)j+`>Q(thnxA!epbBCetGP#&I``7+BohV5*!8 z`*yil{fFbhmaqKBGCWUSMSFZcuA`qV`iuQO_3pJ_Z1dflL&?{hJJ(Zb-#Pr-yIZ9{ z8~=OH)O6q5`Qp|5kNTk;wDW_J59})`C-uPoI(C3j!s8#M9d*CG^R`(jzwwuTvBfLr zqkMA8)z0zWR!;7}s{EvHdDWDsD_j7#T&Pq|F@H}k{S39=$1d$?56pNX+^UYp*zIN9 zmKr|e&G!qG!|^!3f5>|wxP;@h-bWZd=l3(ti~l))l)WNuo^Nyh%8rrs67_wiv=jc6 zx8Kh=(p~cvZtA<2v(Gb`pPe7_o+$Rd`3?u)-E_SoZ}NXT%(L*C(z5S*wB^6-zi4;T zjmr1J{VwVA?f*!Jb%uPYlzD{unR#Eh-BFo`sMlHVZf@*%@Q+en!>p7$Nf>( zleo{dIIHuh-#;avhF`VfP5i&y+l~A(pG6sOxKVhZ?O5&SJnVM_nAfOh)-`9!yzRK2 z?J|3NU&a3@kLj)a@7*oGj7OgvwO(}nINJjfF7pKan(-55d{SP<0sBvs_d1S`H+Gc= zvd?wgtsJlO9q#Wu$^A6@B>o$~{)qj$<5W&$yz-oIM$?b|;nCjDe7*?(lh3_4|1&)M zK=|NgH5~gqx!}tA%02Ts_Cx)9gK@LJ4HvBck+5I%{)CIW>(%@Z{`GWg*VygJ|Kzib zv)N5}_N`Gk8t%(VJKBD|U5U5)OWK|JQcfJZz`0*h&e`sbbIai)e~7R5GvlW{ z@Q0VcF;i~&o*b0)^jEdlGGF+gyX78onAqLr{4MJJqz^ADEzY97p5vkThUE?Si(+33 zhd-+IOnRI{wq4*$&X*|bdakn%h?{cZpYj#&w7hY99u~f)zyEQ?9?){+KMi&M)^fx3 zsJE`+fAj=(W7w5|H&-diC&*OO@Z#ydOeRi(begT)2UsOAhUwN(ZIuF|~Ij2f}(q8g3 zxpCa#W~lKL2ejRb`!PRp-XZGwY~0Ml)ersOE&Pq=0oP}{JL`x1$kD9tjE7Rs`C?CJ zx#WNFIN~i$IO{nau(%xKg7Lj->dpTc7YAJVALXDPli%1^rk%_`>A@?B2M*}`CHG_f z!E@;P;CenE`~Q0Jhu_^CvpGDE{`}EU^84Y4kAAG(pWKh*tHv zuk!z2X0v~_J+EIGc7Hs#vHxRT`tsnBUvF;g-0qFl-oM@UpEpK%*oWR6<#GQRJGAh> zA8qT_mxsNe>!~9ml`Ka^8*%x;{!@896 zFi(|+``PYwP8Yt-IbG|$l>56KAmd1ToZ><3&*cH`*RfNi{!z=1`&f>Ae`_rt{@!Q# z%ihoR=*RoIRK>p2aM66<%Y0A|rXM>%_<@{NP8eZte4}a9OVB@$xr^fQfj}VzPPWe z;q9OJhtpCY+z-#io|1k}{d-=R_>6~g7~lL}pLrI4)p4`hCB_cW{dzcW_W7O@;`!tL zU4BS>xM|O>eIM<*yzFRjS3L9iqxjR`%}37LrF^qpYU&H6{!#mPoqxBTX0Av6{t{q5LanFq+P^TGSOeM_mF$MbmXC%@Xl`<*Vv!=o)7mHLMh#14+< z+!tGTIaTcT(9bvjyU+9&TRd-F`}v8|&(Hj6r`(4U?z5qc8x(iHPJ8NB$*I~W!!W(@!;+%UpeQ0l!tUs(=YBv{!(7*qnGCEQ{?|y&wPyV?6-FE+MCrEzr=edLO zo;%^@a{0e1%4ItBKl)zIloxeA&ipcud)oi&Ej_=3%)AKKin4Az{^^O{!jLBQRm4!`+T`_z~Xy8|6h#% zk$>W6pZd%3d}Y5zey;*I!_n> zt9A+JwY~g)DgA-?O3OafdBF7PcXPY>oj}^t`pSC(?E&d;JdcRi{+j1n&e8b1&2ydo z8sioI=XiZ%*W!PUt8NcSea`%6=6}TJ|2|fQCslleOT0-he6K6q>-NZJl=N?H`Ho@_ z=)8kJ>!uq+<#eU-pEdS@a7gZpGOy6W#RH9x{hoG$D*OGJ*Rda5d0#jmx`t=p2&c+@ z(S%!->pi~JZT&wT`KP|snfHa$mCF0%f2^ww-+7?(ZQ8YXu=8uUZCB!vCo|3n$GAJT zzxl@wQ#(}CH{7dx_)_Ql&KZ;6@Il>Ge)s*wah$ig&NwjK@%*O#vE!Qg-;rNZA9AeX zE3sd)T;Y83jbrM!4e6FR@nddB}8@5x8635vr?{z)qso0MT*AwHI6us} z88{&PvHpXL8}5gl7gEO zd%XVt1m9QP-`1V%-{pU$EJd!T+2G<$mx&((`+R@D{%N z$J31O{b>h?!u@_XH0OQ!o*ny7l;?f^(~G)3`effX{9xBl_w~XLcQ@RRbi@BXYHs{L z*xf4Y=qDpz@Co-LrNzOhUpN@;#<^FXTjr1TYu_icKGB`;;`Q^cwkO<=@q@h>`w0Fk zqVl}pyl9m6^?WYnas8u~-QCRbI_Gm8B@ZRMZoY%ayoSCrO8sv(H~VkxAGM#vZW0bk zIpL-1kdYtU*bB;0e=wBxvR&Bk8-IQ89XIoy?MFMx-*ET(vV8UaH|sq4n)?^xr@ycs zMJbp2MV0oz9c4Y~_2^~ZMSSeP?2lPruKT5#zuIo(Lry}vmMbb>?d`&K_CeN1cxh?u zN%>DT_Jq_6{nUO{Jf`Z$dc@6h!1|H@F@IYg?NF(2ujf5_?GLk0ET#WpUm3Mt>$>jj zi@Q<}xJl3OYQ8fVrG5H!o*TH?x72qCeJ-!uk8tegm{%B2NpIGb|LKN*5RUy%SK85e ztL%H+Ka|}O;mP;&)cnnyl=!+a z!}4T)%73a#$v5M2%|G=@`l(;)oqiDYIj#K|{o(Owci!uN^-S$g;W&@>@wJ4SV7Q<5e)Yd;-Yd|*<$P+mUQ|9txbQkP9Pjq1sb60I zPuKp-wg0@$W1oy1GN0Yq{HaHIA4-3X65p8{f9jENQJ?p3?9cBzlTy#FdoC;Y6E5*| zg>$eDgGaaylMBiL*^goW7xlSHy)o`p{@3HYL%Y&WDD$@Ms$Jkqqd(Ce^sBTBO1tSk z{=dlk=l>GZUc`^4{i10{IjZNS2}gOO^xv|xL&-?JX{kKJB$>QPZKFueSfAzsdty?^9l$OU2iU-)QGXKHeA{%y_%P*^2iWFZO}NpYH~i zl7H;`Z1+|FxZUTuYvz00%r{lHFPZ$|uL<+^OX(HJ^s}yL7|{ z|6{!)2c#TwF*zXp#C8dHipq1~doK?zBllz9g+KiWWqr_p2&c|7mw8 zzouNp|7Z{T1?O_9->CUFKXAR(4v>AV?Zba7i2vs9R^@;hSI$qokFZ^scgQbxcgzPo zfB4U@Jmiz{oS+@}Zvx}wqj4YH6#G5K`-emEhX<;(d$^z1=_j+jU;g(i_anUj{kSpG zCB5r=`laE2KiSryFOPKx>(Lt{UDic6$NB=jHP#)jgUarV_0>y*XO>!yC&OR<$2{}# zwl1Qa`osM!4{kVE{I&c0Xp4{gi~kuO{s))z`+)Ko)<1RL)%|<+&2T*WfBg@`cA5Df z*Xchf^Cso*T0D?=;cs2Zzw4u;S}&dVQQp3P_dmphWB;QaB>c|(6-s{KqpIm!Z`3R2 zVc~x&@vv@0;d8pR6Jp)(x>f$iyk~nBFHOBgS?5tNDD#f{7yf%p{3`W9e~wZgIgg7! z_o1vC?f1n;yia>R*0tFe&074${LKIFpg!rZsQH$2vVXT-@}0zJwUhM}UYd5YeR6-a z$Dedam+P*F^PiWTm#K4IUJvh4Sx;L(o?nJLSU;E5eX+cdbi12zpnE+xr#&C(ah>O^ z_J4J*xBRKc{(lk1%lEhNs`D9KkomRWXT02RIy|?y9(VNUKilWg-<%gOEAi5wjKBB* z^;iAuGHTdl&M@xTl@n zpZOho#*KCy{!f$f?>R5+beIR^K-!IDzlg#CNWb$V+@J6Mzu3~NbE!Yy{KN6yy7u38 zcURgMcj-G5@1x%m59u4ho-HokfOC!RH(?(Ww!?tA(? zUtCvdCrtS6CjIW_I_osg)_0L@ zm#g_7{Uq&*QqD{KkNyBxQsvsL2khUuPo=zbymfwDPE_BMloyqKA8z(xzK@vg^j814 zZg2A(Jiv7he2wxQmFG9{tV(~z-}&>keO>U{R?qlb?{{{+d!nur6OQ?q z`<$06zPMdSyuQ!RrPKp_g7%EE56})UnsKSUF75K=2+uhyxofHIQs=wje$4lBz}R)? zKO@nZ|IyEgpZ*i>7p48UPQIgrvmT?qkIFnjd6+Ly$L*al-d#61?!*05_VbL#mE+(q z2a>;Vy>p@1`-KzfW?um3i&ngepYV?B`p%#E!tRgoD)Bj9XNB|W|H{7J&>jAVJs#zi z7lsF_IVbG@(fDtO954DJ{Ev9yEokvL_5*S?c<5~R1>fVk=YD5?sDG{-U*e61Bd+ll zuaiH72XXKA>t{e=7AsI;^5xb~ZbPe0N>;k#N-ysx6Z44?a|Kg6GY zLO<+U{jka@j|mTiGf-}|xQ%vO`iCPpE_!(TJ>~O%IB=10zS#YhT8^}Lx9jtKuh+fb z_R6^G>0Fin&Yzx+a>@PNN0aV3KXPBN{tqGcZl&~p?Che(Up&ov#7(`SomVE^DA%zAETz1-Ri6XJ|8k%8k#fK*<(k?F$}h14q&?t&QOm=4mba!qq<`?7 zw%_pn$ab2)SIqiZfB$br`NI2D?lWHbAO9=k{|o#FB;WCi%BAoRANBky?o0fyc%b%e zeushmVEV27lkq`3FQW23`Ca`#lErG%6VPw{IIJH@B7D{_eDGZ<3AccC&T~vE*1UZ{+OTSf2H)754Pt9 z*LiNdGI$U3)6K!voTo~e$KZh|+>hrQZWOoAu^;UGM!hl4?PA|`Yn%gSy@S0|l=V&c zAIds__*m~m;hC(@uxmu+evGI4`#R!-rZ12B`)IiRzXRdvm!;H$_JZ6`I*iX!#u@pD zGEUhad#v4|RaaJn#!_JHK4B@pa?CN(0`QD)GO3y#TyIdC~pV7)M z<%+!{<-pCpQh)3(;C#5@mhA84ms}_R;eMPif&Zx=4kdrRe&MXzU9!&iez_L=V(O25 zv-zL-pY=q(YF+2LRy!oF(;wIuxG$W)hX`kugM73rTu|<-J(YHX%v*-jO}%tC_2W7+ z=aF-MH|fXDQ@c;Nhxsh-M>&ZXZc2Tm-%uZfKhtWLv`@94_sav>FH?U}+L83JN1}eB z?9*|xZnnNu*3-Ice{K20Rdeoi=6~dy`65dCxQqYAUIz6!1fOF+%edz`wkq=g{%6Yb z6Mxm`h<1N)z@tCUy`<~BHh=e!a?k$q1o{*HjDO1$yU|=%8Q)xw(ob=7KlK;Izq{j4 zed#}I^~bq=s-5QctM**mFI+D=wzDmv)>xe z%>S5YKHK7#>rqbJt5QGYuPeL{_ZLHnCrbJ7?@GJlj#3YDknldw^Kzd&rT9pAN!0o) zJ3rji#~1rJBp>6c6WEBzHt-2E9v%dXYnQ8Gfns?@j3q#@5h~V*YqyA6aIOc`+0s+ z4xXQCzMq(a{!yP_`L0U-M^W6*cJeN|EBx3i|V{K^F8i6 z^JhPfKi7TU&&qY@%~I=G{>Sy-j{Bo44?J^o|MU1?^3^rvrXBHD@9ghuRO)?h*YH2j z1=GI1zpMzj4pJ5Bopoo9@p#93H5$kAt^iN5~HH#rYro3wuECi-yx3`5)&x)8i(KQfGEP0$TYT@>p4zvBuT{I!e)7Mg z7XMp$-e1T6=x3%={bufe$roJC{tRC!d%2naUBzRp?>Rj481<<>uRd*`BmYagMbjUQ zS6&2%32&mmY1bHK-X>i5liY>-!=toElc&)Sv>%)K7W*!Ejr9W`qn?WYk#6T}M>qM9 z$GsT;quvrf>0+nwbnDONLp#NAOZP{7$B*Ya>A)+xvfea()ctrV;d5Wv4Qjv0`CrqA z`(ZbBO3QNgO{-%l!Fj2=O=HBSs6};o#Ds(^M?PR+D~17=KQes zeBXO^p4k6-43ryN=5JaKi^s)?=lPTf#ApQTU|%PsMHwE=YUP9(>Q9{7}EQDT+Pc3^**S+<aUVbP zKk5U2@~O`Dp!8Gx!vT4|8qduA=&$(aI%>bkIi&ElS;P70$AstkHEZq1X(z^CSMq6?T7h3)4TirQKesC?-z}|AM-Bzef*ID)q+oqrS7>_wH^NDEFg&e!kt0eV_gLv+e$K z{zrJPU(NsM7nBcuaH?`o;`91B|ATwTLy7}ZkF-aW`*E+D^t%$y`kwh8_4tb|pT$+J z7wrJ4Z`^3YSr0h}9PXF@i&XyP0Pk)*fbwb=THgWG-pA(y`Ex#1Grp*YjF*f{=ZBfc zaew?14y8Y!Fo^HX=TUh%$J zx!-bDeyKm|(fJ_u!`3tNF!he|+@`)BPb&9=55s4O|I4A+zry{MmTJ>N?>=fCLf z-5rg8sn6+||B(;g1G67x-qlUL&-Q?EM@gUXU7fFA-`69rZ|f=IoAX&b)AgVHlX$JS zJI~HdYY&+3^7;RD`XlWe{)*Dhv^)PJ=X(IQv-W>EAI$u2JLX*QIsc=d8GpVHDu-ko zJ>JTzk`Mc3)aMlUTQ8meQBU*wfqMCNuRpbT+#h!T=*nH>dYzBZZt@{^CdK{SmuUxB z{~0mfO3(D?@B0yt<2ZJIo$pZ|`5xTNaQ!;#@tObOjy>R|@Bd*Z!ik+1vHv4ocn172 z+~=sZzvX*>Uhn+Re9D3FPkh#A@i*haEnkevmDvB{@BSXH7k4!KfA`^Xt*iK7_R-O_ zBlTYGMmrVzoESJ zf9eHZpw|CM&~^Qs&(4=D zpV#9LXTu+*9Z}Ck+HXB4O})wII5%wllp3#Y_?`QWGdKCiU!@(5cXlTqd{^(i5#Dp1 z`}I3ewhn|^@%+IW6&zns+kI{x5c z)>~JeuehT;uMHnNK>jOBJgWW8^z47tFO3I#LGz8u1EX>f`jh8e89B2 z;eL78?Gf+I@gHCA!#=Pp-xJ1-x_+K{4crR;cWeB2m~{=`#YAt7{B-_@of_*K)|XG3 zYVSw=`CU4{Q)hYLRHR$#KA-gv+)kC3v0o+LaKCePysg}ie95!ypT++i_t*tuxBO!K zk8`o6<2q9QNBQKRe(!L$d!+t;ve!$#!=*A#Xa46to_VPFAMHKcWq4h?UHKo^$(I~Z zbsl)U)u-u%tFm9AUf`g%TR32y`=xxWC!?-w&-ou5#r2;2k9pGljQ`uEpW=?vPp~V6 zN8(R@P}Zm3huePceX;kOxgP0|FXm(OCkMoze3P%J<&}fN)9Fv}Jp0vOXa7ff#7BOu zzob*&Q8YiR-PZH?UoXG$yT8spyVQN8|2c;1IDTjQKlatk54HcT^*8ea^K_}aT>C)w zxsDg^CmiwfJel>*aQl2m+~5a?EUJyU-qM%|8tx& zE}1u|pD5pv;<>x}R_Ew|6f0&Zgw|XPbXaOpcwI~_IY zn7`tXmS6iv(sdp9+E#D4O8Mp z<`O5;&ak*qc#j;9{zSf_gmc`!vgnP?eSNHC`}J_a&i`0Xb$9Fm^ButG@jNi=vYTT+ zxhnm&^SYV;gageQPFVcU>&8RA-S3tip4@akNA3RB^uOE2%`02}u%BVyT<1-THyN(; zEbj07<#JQ+hM##Z{#Umv{Ez)++Fg52zt3p>6!(ie{4W}R+n@etKanfxE{@pwAN`m1 zV}HN$X2TUfpnSyzzsEg|P>eXEMI!Sa3z_@#$8ta4z%V^>9PfeR;)a`nt8_qkM@6B^^}W zXnFc|!zX?C1OJPN65jt|M0s9%KOB&FXJvl%y2`q{+;W2Af86i?g!%q$@ju(m`1Ajp zZjTxMw$=yv4fl(}{oDtj=R7XwRSnlUp!|<|^gq6_n+xwdDjZw;sAGDT*Z!it+>yu8 z&;0+1+>L$-kE7p)2NHjGhX+Op&wb&GEB7n6^ONJ-_!&3EL%oOl>2_R@F8w9;<~4p9 zckFlNfAai3elu?5e{et6V|?e2{>J}4Y**$Z_^SNx$J=xB`rvKzcjn|I^e@(n^gGv$ zA3jr_Kkz@+(VW*sU%B=V+jEKkcyJxNKmFm0yk&y-$>DrH-`_coiaj9D@hIQ_!+mp% z3)VHPGf~#jPquLL_ruwLVs|EQ(OwOEH0(`T@5rO%K#zAf8ve)qgoD$-3Hh%DZuno^ zq#L_H*4eDHRL37~_+RV*qs0NW_r(ndEOkC3JlsC_b;bVA@9>3t=A82nwtT`*&Hu-{ zYTrlsC@1SO*U8bhcelzsIr$GS?aMr)roD>;+CR!ZkaaTs)b(`!7o)u%^Qr#nXNH6CdSC1cwVR`U44?Gm zdh`eK6VAu}#r!3|e%Fw3Vt)wll=s;$&1dho~S@9MJkDb({nq-6&OC6v zPJRtv-!1CyTu0}2OS-Z1n>Fb$UlL!G|1{v{yKSaZ+|PcW|0+5@iO2CN_hXzoo}C{U z-{Cl__CNHWM_WDn{r_-3`jh;rxZh`6IQbjtaekM0^WDCmZP%~nf8^_@BV3er$$cpP zDDmoF|NS6+(lsC2#o^BR)y~N%mwYQab3X2ae`}02$JYQ|^`_Ghd5bhUcoH{=8{lJ<3u`eY4uJ)VPcDv(J@<+JGlgjtl zPg|Z@+27mWF6qhxSMGOfn;%&LGfxuVtmpiXe7cS)yS?tt^-IdWlJHz-e4MHIkpB@L zH|qRdN`2w4<{a>y&AyW7E$xjuzsD}H&h0v$<$9UVQ0Kq*_V%6MXV4$h?osEvvJb@G zljlC^Mj1!8v;TL&j=}QyKNRw5eH`ro?f-o}Lb>=pU@7&0yKC{6*im?0|CQ^_=XvEg zgkQtS|M2hJPmV`;xF7qN+fDJ8|Ea9MajPruTiuuWpZBxBB);f(TfO)Hf>2MM)1B@A z#CpZB$#q(^ z589t|ceHQ#9`0`cXMPQbf5KVrN{4b|#}j27Xipkt+?&r!TKs@|oB3bd#TEEZ!a4Ul z^1$MLlt=D2#~=TkYYhLhJhr3vG2Y}Jv41*O_(zo^=Pb2nDmyXSyYoNFS^r77%>M`{ z4}_P&smNEU`7XEZfjj9LzWCyNKk>;YOXvS-V83MkKHk&CO}_5$nsc`DGWPX;M-Lvz zK8o|RjAOW>oCi1c7P~*kX)jlm)AGwDOc#!3z1Uv-X9IWa0B8F@=4r00atzuv=T+ea z@YHj4e@Ol~ziWH;^S{{H!M&n}D;{XRE5ErOWt`EkJQpjEg9p-oqFfLEi-rrTen&6g z*L!n}7xT@yIp>Z3ciH=RpFlia;fZo}xnH;A>;DnAJ^3%ktx^Bse9o7QPiF6XLupU{ z@4>#2`2?-!oc)340q14qO+OsZO~xynBMPU&-ih`KZ}I;V{6~ZJJHj)|EH6 z@At6||8!rcYlp>oU#`dQighFR!8u&VsPG!xsO$dNRn6azJLiAqvv{BRFL(H#`go*+ z9aEHb1nX9m^P0M`7c@V_r(E^bvTjNOX&yj8`__94ECd6J=0@+ z)EDu`o{aA|J{kE#$>&QOr)2z@Z`NUtH~;9&`xvLJr!FhunOER`a!cL3k9EG0|J~c) z!)s3n|1>}K-!}7^?+VHNSpU0D4F{C_u}`A?=`T_HMf#!Vgv0$VDgBOqRvd8UgW+HK zPG0Px@*fiVpY?5jl=o4uxVzd9W)8?chjK>=Z$0$yF4|8xx1R3=!U2h|_aEGyE8CAe z|3dqjzq|*p?>ITm!u#fOk{_?1^FPv`znhr%0NIDG`|G~GcHZy&54&ynpBnCmT`6{j ztZMW9J@>Pei+wYi^?TI)^_|^cKO6qk^G_#z>)LT|>Q9Mm)OUZ1Dz-+50_9FXx%d}m5MZ0DG4{v6U;+gFEw7~ z<-|X0%{#Mycx1TU-=@@$^I+_>kNKF(dwKp(JxBALlDGK2kn|k)rM6?f4_E*9k>}js z-vh`2X~*;f`}5tsU#sjNYvZ4 z>i*w$fYt7+pQ^gM9#2(QU46Qndf?~qo2JC)JKKK$#q|K?uJs6ZGyflieLVZ5DD71I z#eF^dsfsVZFXNBz^BV7Y*cD;yk9<(dvnuB?uFKD_IA3_*s^NXa!`D{jI6K5}z$o=2 zUcLQN!vVX>?bsjUe<#;FD*N5|b8#Mat-ly=CjDir@71PoGx=4t{O#Pw&ODHI@qCnW z;LmqS!~LT4oBWUVwj8SQj=xIZ^Apw%Vh`~f?flPn*WWK3u=733dGrTNy!pj0v>V>r zbH8r>GY^C>S-w~EKhG;3cnnjHBj zJ}3Ko&;MXkxF6xtZ|z}}aSK0;%DIZ0!56~O;F)XtowdhYf96Z`N6m*Y<+hyucbE4w z@oVEd5Ov~{9{yJ@Hf^q@Hg-0dCzg?DxCjf8yB6UU|;yD zMCDe$-t6*&!NHDxe{iAekq+;ta2&1{B^|=0oY&vyq+R7Slm{-y`*5_U@mHgL{C}_< z$MWR=Aha|8*)9Hu9l*h&j+d{uaf1IG?XKS+<#7EL?)QVe9v|-OBb9!e*YEDL*a!LE z%(Iuux|(tQ)u;#ait2NI_BRzT_xoy;3y$+|FO}=%izw~N{1LUhKCdO7{v*GxtQ&1d z`x}2v*0Jbn5Bj;mjcxA=+YhlLGzf$as{VVm#e}~=A!Z+6avSGgKtzD_b|CoQc-=XXi4A=X$ za0B)eH!1a$FT@{o-Y>()=IiI<*bnWyYTBLaJsyr%?<*Pqct4KXZpP=l;&hY)e$_Se zs*3&aoF!_zkY0Eqik)}GuHk{#dpt_J%4tgV%gMga_qnLI94X(utMBLO&-d-!ug~{z zDgS3%KJRUuk1)IseLj@*WVjE*Pa9IbK@x zANe>Ry8bX<%RztiFy(W;%)B}4dc49jC!`%n2kq%6Ka}!DX&>4zik%TgY45JNU&&j( zy{{{Z`-KD2kF0OB!*Iaz|JDBdJ{;wc|2Ym=2YCF+ZkLa?blCT4&&B=ZKo2(l$o^37 zS86#Q?(3olFO_<*-&bee7ybu_u)aq>K-(qUuXvyF6=ohKomtQM9Od!6`FP@^)N?*> z_4o6*=evLK`TfJKKZ#HIt)JYFeK6w;b-nx6Hs8a&Xh&4e8V>k)=WzM~(r@<9JpW^- z8Q+e3{r|Af9>&fL&;NPhK7>7RztNt|k9hqL^S=_``{uj!)C2xUJ)^`sPq;pS2Qoh3 z1CBeDeB^H`*AXTi{Ue?X^*Z&@9!A+8!1JQ^zvmSP{PT8wI8kvx&ZB>3{^$4nuuI~x zr&8vXs}W|s#QVSOpW%E_`(N&--=G|jc+&H_aK9+!e?9(ZI`WtP{;l~|yx*Vy%kA$D zFOeUPeKq%6xgR|9FI&B5{zrY`jP>4I=X|!4`&{E`H@Ou1X7=-{`|0efEidWP4$-?XB^(X)0hBNQd-!SLdUtCW=!KLW8 zBmeWb^(kIB=Mzo|pCf(W=VU*`bt>h$iT`n2e??Uu<$o;TioEA4|AXJ2@jvUG`q3_O zJ<_wha=$8{oRamA$NB$;>j~Ng&ScpCaVrV+YLWEz7u%lex7gqvvK@t{%6Q{DW$;Hh(}OWv^S&wViys^I&wpm4+$ZrHWFPhMwr{!YT3Mt(os!}|4c z-)H~Hdcb`se2?;l@A!Q?zSGD3Jp2bfOxSXGJ>{NxA7S24)862I)IWMX+W-E}`$+eC zD+j!f^i=k9hUIH=HtGupWL)D{7q#3kw(I4Ql#j5=T@PNUem&a%;l=|Kmj8Xd+t1gV zeY`!+*KV!fJ0qO>SZ~*D`Ho-yyZgOu-G;v#>*6Tw>^kmSo3cJ5OuM+As`oj5x#dH= zf25(N0ROAJJ%LC;X3b`LiwF?-dgMa)dc9*IK{Z7hab4+QK*F zZS-5X+pIY+I`cp3>ps};tP#G6|B+Aj<j>Wi#vZiK@N0P>@v+BQ_4i}_ zYW)1ZFZ+DgFEjTe-f}&7sn`wsc*{L2=ldKt{(!{+J^$WzU3lQC#RrS`aUUkW)crs6 zC%oaPme2FU6ITs~j2?NU>j&b^C(613&cpfMQrdez*=hkk5qwsW}cmlmq$wKkQTv^yU;V z2W0-~{Eu}y9ME{zU-}Iuop3+2{L(BJ<&*oF4*O336Kp)Zhj6sGnfArLo&7BP`uZLm zoKHJM@qqZt)}L~}OZ<=e$&0$bAMLJR8}&IJkDrX3NIu1RmMgr^FnlrPvi_8den83J zaQA29_#9?_ao-(3&YSq3`4s;%pW?aN&)nbh|EaO>aKET_hF>7{!TzW}et~I^)c;t1 z?45S;dtk25iziY((v9YL!pW}`{zf^}oTu7fatqqAxJH$)x972cDSz*G^R*x4nsQ0G zPVpDZO?q<3gypC?FZ~_0U&B?@aLg$4CD(@wulBKqJ>Pi*P7TMU{PX`@@yC**asRbE zD*VrKsm!B>J%8qO;h|R}eR!B0%WnG+5|J&<6aprVz%$55k9R3%6nR?(?_^naCXxfGJd5;|a5`O1< zyo@8x=lgy>SMWVwe#|4pGmp&Yd*9)H<2*qa z9_@X|af)5mc$L3$9)5q!GpuX*fA77q?)>9k-#-qncW*mRd;MrzC%iGf{|9H{{omq$ z;ePjred6avIX>Li-@c!#-yrL4|JOm7eWhWZPK5`;|Kw#HXB|u!eh0@;8Sioyl=Tz; zYbfQq_}lrNKlvYa<@=`CqyB$zKsi)+AnP1B==GL=-iMX<75B?=z86Tj;B2LE%3lv& zhhHD@r1xT^$GAjm9Zfj=kMrTE`nl@I1>e$631den_Fw$Z@)KrX!#an2x-vhw{`u~{ z4*u@gr!zmv0cmH}akMAOJ_vqCxn0lYJ50V`LHck%k5k?cwlM8b{(z3#uXb*E6aS+> zSWlwYLpukw-1R=N?U?q|?}L4V>t)}!jeQU=N12uK%QaLu9N}mGmVD>% z{5~G@E#+e#M9Dwu`hWG;JLiAo^Q!haKW_WRZn}M@-BIkru>A)I)UNbfU|e|oRqA`* z;fTx&lq(7+G3@@H@(_-4UCLp(%%A?EJhUJ7iMkKW`(S=|pYz=B=Y73rJO7F5KSzD# zXz%U+iIwva|Jg{N_SUaYe?RO=?)ROY_sIbh-}U)kpL5NBL-h9}zt8vlzStGsNB$`7 z0_Tg8&zE~R{%foLd>p60RsEW{o_#Fsdx^KPpJjY?r5tjPa6UN->4oz}X?M==O8x8) z`5@t(uRhzuM>5{k@*w+tvR#!~f)b^*`5eKdz@8ZI8UCT>t$bp8An* zFMsNx-Fcs*ov}yGbG+0%?0B4cJm)d)X(#3Z!mH-E>U;np>X&%awZ4`A+&;vo-J;G1$NLfO z&U@eVM>rs1dEEP(l7F{H(ocA{!*J`_4w<(-FaBk6C-zaUTOOYJ`LS=bT&34rIcM&- z^1zkr5!Sv+y^j|kBn%($dF<7&L;C$(&$*u*0Q+S>s~xZ0FX3>%*HP1T-F|;|V z<$qDj@4nRc)%A(T>Z;5)o@t#k)}>K^PTx4FZkNQ@6wgboMm#%XOwd5Bm&0|Gt>+>3(Fa2r!Z}{P;fBEfcKiX^ZMVVc{GtOh4lK-)OWd4x{ z+D`C5?x)1V{orCzxRK8TQQ8gO73I5xAB}ZI6nlpss@`{hwBLVK{zt+3QoT3&5&yn$ zF!%dhx9*==Cm0X+&~NX>Xt#%hKawB)DVJlPU_bwQq|5sA`lXH&NBw)4>j<;IxgLkv zhoI!A#{U4-PNTL1`FcGHSCs>1zaodE-Q%}cYI+r>UEx28XMXAY()a0of0^=GPs`)~ zdBZKUK8FXgK8n(=#r@>N@;>?>G*Q(iUS^Zw4hE`R@}>JP|z-*WtNvx|gX_fvlI zL+ks1hF!1Y59oYAd$V75{q27RnBTOgqiSC>52W8Z-=MyPqv0W4wa0Mg@+ZkY2xa`3 z-^?c|ujPx*`zEgQc)oww`5*mU_8P8R_CR~o{oWYzQ|{iZ#|e>DB3 z(q8l<&!NtE?vV>xKFVeNAJ%KhFs<$u`GXIr`S?_<2{-xuEZ{vQ5d(;P>ikLysbkJ7%gU*VDWeX*T?>HieP z`@Y=IbAK8?zWP6@+^YUtnXvob;(qK~u`@OA$z9T!hfpthi2m8wk^A5Lca`rln0{C6 z!FitVG}LkI(y;M8Y`Uh8{ZL-)hx$Z$-bOvUx?lIdF5FKEN9hlbhlkD_kouWky)Q~R zh*#_TwB8rIuV#E@T%p)C*Et`koLBP$$K&T0f5AHL_49my{d4`Qj0fVmUwZufxkB=f za)0u==2J6r&*`G%lln$U*Lk3n`H16D?;}~aRC`}< z=gt0p)lYeUVCBu>d@A=7>{)f**S??b@%4XS`(Hml_y=~2x}M2$$Gsex)azE>b{58;iFnoWo|TL8vd)7WTvFG) zcSm_ykHRmbmg{((?P)uuz3`*7Jk0lSF4`M)J}Gs+aQ^518a~H-!T3=1|6`o=c@#U$ zyfACx^F4%l9%USwFX}pi=iBTjwTt?mjCLG9K>g_1ufzYM{6E_9rC%WBhL=UTugTBU zJL7zhzqu*V$D4gi1NB+nDVSfMj&KL)r=YK=wU2sD7 zlgIqD6L=2xTw3LoUwXa!S@y4TW)&X7ad`sg!xL1~CCqp#O}zHcK9+IV75g{LK3V%L z)s8(5-{5%sbl`QAr*lBdTRhP6$xY;b)eW$Tgd(34Ji-t^h?SarGD~)DDyJysG2_4v7VMg;BO=cd3_BhvHYYj zPg^zlRQ#*>TKL^14Uc=3=K7ph;m&WWT<7IKJ6_z+_Qx*6|7icRC*pnImUe(&F)nWA zf6SxWE&g|2XBa+}aghA5hm4ETvKRVQZltC^^iz~m;TLx`%Gv*OLI1-0EPs_F;d3nx zSoMYAsc6}e$^WcDdpN{x@+x`iELHVEdOuMkYDkWdex8G>* z*&p&!IDGIp-r$eSfAVeHyXM7pJQ8Mph*BS(AE}Nv=U4e3{+sZ>M`Kpv{eL(h@AdlL zIpY!g@%e!N_h7v#|I2?h`9B-=A?<#;j5fnVQ?(QoiTcp`kJ{NfCAJ^dGDy@Ma3`NcmE z4#xcj)h@3$dkyz{dyB{KNPY$%lW(Ed+h7^T*o-Q-scjk-a#gaUn;fJ*a1t^m@I?*Kjxz{6_n-{PiBE_0yk>dD42${D*vq zM`@Q;v5UUnrTp1v`dnRqJols86YFd23Z=h``#Byu4=lew_q%sTeZAg&F8kE-YjK>z z`xx((gYk!A&s~YPpU;)^IZpb~v_n_wb=GbbKl57JhyJ-qwWDxjzk^Btc-^eDU;3Bh zv@7K))qZ2o%%dDH|JEaaoa7ArFW1lfv)7Mu5{}YtX+JdW>A07_Qa{%hxaj_V)iGbysjV0?~r`qCef7VlKMQF z^DPhSP0Eq-pIt}#)SL3qF8CqX@AW>l>&b9f{W0Nz&J*g@;1iBpzuQ>PgPa$+e>gwX z{F(V8{QnoDzVK_p*r)SozJm~d=*&}jKc&7uYdLS`f9%^k|D&9)FP?0QJ<9u{ui}3< z^BnpWK8UhUgU=OLo5RK9+z+1lht0gmev7|gxLzsy!bhV%?Em3_o*(5p`rq%b^zQ*` zH!Gi{-0nlw;(ywyVfY-!qwHUEe$Kn3wv(I$zZdw$s`548v!-79FO|w`l*e{` zRe6dFGB4_H1_umZoYi>GBmLrk#r>!+`+U>8sb48~=gHyAiHC=I{P9aQUHt-mFJ0ba zf8mE3KS0_y^@z$983&}p`l0L09jPDwi27k+&+v|;u6!`(QU5cJY5ZC*!}v9FJR1L6 zI0*IeyNK3X-j(>9+L3mx^SsXU*YO;#pMII!o&KG7lhlf&d07D~N zceKL~_x03AyViT8JQw7>&r;gAzK_TH;*FR8orUue<~`yl<>5Pm*d@oYTewd6-~Dly z^nGLO`pEydFTsOU)~WM8!1}q)IpcruVYnK8fpR-w(Nu3&)9H7GcNLi>)2y zHMAFD_DAb})O}R<_oIGtYQG=pzR&AY&*DF%%YARw>~rNx>_6SVb^hmd#KUJO_uWxW z_s1(wN__UO5vafzUMmkZ_0;Ke$qj+UtcxHv#;m6xjpAF<>|*0j&gnML6s9@Up>tJ*nW-QXmssw z!nP0RQ(pTuYI*o?knx7`(>EMD35S#)Gw=3#q}pS0-^{wr@XSZB6FE!1(^~#~ za**TxH~Zi-W&9BzrCy#lb41$3@`U4L{~ZokYWv9bXlL3lyl)LNUvV7eI@Ybx?Dxr+ z{)}ROw1fBO@F<^~5br#jc`);Op7+fBjrwvQC_U$Y+`l-FcIfA4p17oyZt_{@r#Zis z|AqH)zh}NnI7)eZ{t>PBd;9sU8wk^mQR^|^?_6hbUfQqx{%CLVi()6F7kiAxPSp6h zMpt{D!|Xe`j(NrO^4_oC7hqp)|3~lb_KM08SP#K5Sf{aGt}yqX;&`sxUMI}>xUOZK-EJ4lkm-)~l5Ixc)m+^L1T#=Z5nv ze{U!Av0V0ZIBWS^(hvC#;L88-FJgW}<@j&z`u0A)<$rzrJI~I3fsE(GJI~htLr6FC z0_VlvGJmOc|MLFkdWZX(_FwM-J6?Q0f$?#M;&kxSv@mc9N&bzGj9xj}XeO!1Q zVR&Gv{i1)y-EChMeu&+$Pm6z{s=X&Y{QT(0@V!5b^%eWY3VZ%BT-RZ@?hpB{V9FDn z^OJA&_nA2kSL)jR1HB$DKsiejul>nW`gaqlH~h4Y8;0A!SE8I(Tqxxz4re~S+>9r} zvpSB<@5uj%Pd@Z}&YSbe``_V4-LJ2B6X|qLWms-Q`@^;9U;ZyK@6*}0vo7rWciN}( zHTwZR$G9yXNc&r_;%eb*@;~ll)Q9w~AL)`F?HkSkuQ80`M+AQdfqySo3ZeC@yDfAYP`$9%*0j{GkiP?e|BZuGaj{O;C{31bhA8=nX1r!UuIo+E$e zKia|PMp4JHT7K{}Z0ocCvo>t&uM4jc9nE_Cz@u z-_}1m`wL>1*CU@O10muFHEqQPQ)&C^IFB&b%dzHt5B<8n7wh#i?_r%uJm+JN_@j|Oyv1^b`@w6?uM~bP zAEzCO$1c03o{R(HX?N1Sq?Ctpz@;4@`Wte-?NQIaZKua0UM|gX_FG+Pcf#~b+RJvx ze(+}g*Z0S)rzuCNd<8hxTxv9={#;>l~-w8J{Tk z8#Mec@vEl4qoi|Y7l|ib+b#Qy^h33)?QK8Vf0mp0HJpBo(jK0tnxFSo@;!3Da6bDl z`+MG_=6vo8mN#}?D*nf~ z?S6jo`$L~^<(l97Wqf}=;=BH253ByqmvsAk$k-LUkN)?2ek%6izO(#R+|Sm3DBXvK z@9D?KdXIVXOr1~jU9R-Bk-+$(R^b2+p&HkV9V|=OUhBMZGj=5hjPON{a_u=x_cRtR%A1yz( zejgyc@UX6w%lRbpN1lt!&lA>pqvn@X-bT2l5;s&!=)ftMw1|!S&I!KXyU z!>#}6FYJJQCG#Kq6X(nDzbD&#%6)=)HS;Uuh4H`62iPs~DCbA9H|O25JMGW;knx~> z)OtGiv#8_1_xYLc7&nxIbw`wO?Kc$)T5oR9qve2;x5 zet6-8?ib}3{s#oU=6U%pVEGpwxt{4Az-IAF?aekt$F`_B0v&rdm@^-b5bW7_5Xxc%k0f#++d zDD502UDNaYejavhIq|2R&&zey?rGQ9i}}zGqmHR#YLO)=?@V`~HTlkLq zB=d#W6_*VUn)^L=AU_KCFNFWm9&(%Fj^U3{?F=r5-Qm}0`nC`42j{XK<&tnD<2m2{ z;yS+jSA5U*l$TQ89ADd6UTAwTFHj!F2mOue@5j6fkF|Z72S}$s50d*C&vO|1i}_F` z40kO(8&7_>miwW0neYC+x7j)N<#!|A*}~W#VK|lggK>YC1M;3I-}mFb+WDVh-XA62 z_f1Rt`@)p(!)+ZT7o`4tN6_@@yL;Msai91D8Xpemb5+)<#LHb6C*dWo!{B)Gg;M=w ziw9nfa&X?=ad%<=5T#uB`(dYk=Q?3kJ7Rr@J((VUf7mH}k8~^_?HT?;eVIp5%3EqZ zQf|-lIQ>VMbr0p~%6bj{Q~rJ&_kCXc%F-{a0|~?VRO{vX4Gu^<;iqRimnPo!a9x-G z_I-Efe^K}!^^y;=Udz4!?L3ft*~doRf0qA=>uvo1%s=&aUnd9Df6n|~Z0VizKlWR^ zCrLZW`Qi^a^DNrgebLPQh-aS!uZxl&JcaT^sjvM^x$P&E_#S3IXL#0}7wz^;x`t!# z+O<4f|1pkJt|;qku46sx^>6L`NbW~G=SS%e+tK=`-o*oF{*~igN4q49+K%ux$4A0h zcl&=I_Se><;%ToupTAkjhwCc8*QDDDJdXVyO1VFqRR2B3r~ZEV@5j5hJ{{*V4p7Ri77u*B#n<(u z%lYP09B}4;{?C{6I{%|wl%M+fpNhwuW}gb*lmpK7CfFhj?bKfw1$8Y9o`#*l+D-W#q^W3l3|2;bQ zqy1Ojw}x%+`Mp1`vmJeIgxy%Ke8)EbpEz(k-fG~D~ zGCmE@-%nuN5YK$-@s&4*`$gCJYCfO(uIV`6<@v_S`}}?&^A!Vy(9I?_}+ac|Q zvOeTKOuJwwQRWxd73G(y-LC(a4i{H5f2@kVX;(EK?APLc32T?H!~eKX7WWJ1dVT(v z>lsIv_}?3&eK;?CuehJj!f)=!AMWwR0mJ`(KlV?w z2j4q^kI576H?{xVk6ms1FWSA%qa66}VK?<3UwK9R5=l?HA|0+bzpm~dFURM&TKOkz zy1g9oEJgwQ*(l}hd@TE4kIOyeWW3ia2Vj58@g63f;(+X988=-yPQG`?eUEs)i#3;{ zb5iON{^fhl;hOq8IjDKeTZF%K=^o!gj)ELH@#Bo>wEaDKO8?%$GnU`UXD{fj+2hZ zu^Y}mSH}tG%Y&k}_ZjE492}SLIuF_JX?M6D<;M>XdzAB`+Nb|-fPaL?*}ia`ltUh6 z`QrbJ(ogV9_>^Jhr$2053qMT9E9c>_MtJ5!?%Rl$Bhjzq8+F}C`uI~(FV@p2^J)(> zzY?b3sh9R;I;j`$wXzN?)y^1?-5*ijCbyISg#(5g$}8cBaLn*l(xHB~H+CM5XMc0v z{5-?s;e*MyH2##)`1|EKPR4QipY;2DM0p8E&7bs(uNQ~KjwpZHkM`t#XnXUYU-?JW z@xi#{x@SZ2^FwVH?LU5E`uoY1=%@VO&Hu)--gG_K`5*QB{^w8)3ft2N#snMUR}%a=Tuw{p$5*NB&2GaUn;FKNw{h>m>dD=r`AGsO31S{+KzBbr;vU{`&r=Z;X5l zhXbm09^a2o`pnzezm@iN8~ZEUb$-u_{T}@r|2g;{;c!6W-M19CVSm&4UpS!g@*nae z9(yU}I**61(B3b${PjD;jpiZL4}6~IJNg+K#_nzJ_{E{#H`3mGSCRWj zsr6$2%lIm_-lRvrpp?_}}Y(K^x)s!-^V+TQz`#vdp%U&_r?Bi;(yF{pN{Jo-|+{0zNJ&w`+dK6U;a;6 z?&tRg$@hyrU&=@LXG7_aDD|M+>_1iS&;LB^lJyz&WqpEjocXTn$}esTv#xYL)o+IV z!&#Vhz3uLIwaDLja#qU0eEBLRJ?B-Ga`bS&o_q)=Kgxl9Td$~oU5r2H|CRsMeqFvN z_oF`v!`V>A6^flkJO5+8lq1CNy!)+FF8N>9C8&Ib|C3RVOZSD$AH~C%XDA=axHK&H zW4<9weY;{$gpa!NJ-H(HMbA%qbN9{eBJ@s*eJ$jw~VuUkpw6~T26>su*@ue7hdusOgbz7Tf>#U+|Tu=etmprknzWtL>y=Nt{(q4peu{+HVhD&SR|i*f(nr#Q_=D z_z5!3+4s%r_anF;I}hmp$9Us9>@;e+`7S}8N0dLb?OFFx=K=0_)ZcN(dWG>oekk_a zmHjH?D9ZkrF#BdTVHFPMxI^VXzZ?0nzy9}w+Me=+`x}Rtc^&nAFyhHi?su-)r_OkSq+yg^?djT=gar-?{fV|Jn5sP ze^faP<<~FC>nu;bw`>0yCOz$_b3oHKKHM)l^FP{!^C&Oc(=(s)AB69*5AO;`k;{{= z>%64L^`xskai0BhN#$+Yp>{?;bzVz*=m)9)T*9U7n`kfQCHnz?IoiYbujPNtU;M9u z`s$y@d=~yw^$!2D+-3Lh3F?KP66L)b;qX6{>+*bo^W>sjFDJ5J9T)hGS&pMxFRzpP zh4ZP5D)<%iuRKt@^*Xs8*U9ZrIilZ*!j9RO*gkMO&a3ZFmj7S)pLSV(gZ2;S-5vA1 zetF@p*uU*pYCFpRJ+5CLJTZQL_OJe~av;CQN4)bi^%I|0&xv=*;!uUVYAN;?7{=?qrH|~GLv(JgWYe)EtVSmy0xAnp7KSp{V zZ1KF`$hsw}{~7IE-=A~6^TAl3)4uRP-ap4LFz@M>@;xxP7|bV z`kDMuxF_ugpS>Pojz?MVkv;IhZFzI~4LZIFGw$6Fhs)Ocs-$!5?|R-(c~b7wd)2f{ z+JW?FH~L@A``vOg?8SaSEoZ6uU61QY?@VJK(bX=nL$6cGkMNwY_DVTohgIH`f98F; z9(&_D?aux-eV?DOUSWKyq#q9EzK-=){N=*^qVPBF=btqtANXCA`iA>`x}7)s{ZS9% zsaI6~=YK-D{`r0#{Eu|WH;UbTu^lg!|H=I*|IfDL`uh=P-x+0nDZe->^Bl*c;TAV3 z_j~8t=*<1tFL-^a_up`j_&uqVlX((lo{ZA&gvrnO^PKzTIO=?RIep6!KgQ_Hd1!aq z3(Y<~O1siu?(2*HVLxy#6#j>@p4F~AkNbev*Z+cTcmGSwam&a0gnWEHiDJ)rPQ-cI zcl^Y|y@~^7J~~szDe5#gtZSf;|u%CIJ#3vP zp6%M}W4f-#uJ(0Vsq3h#eLZ#5OV_<_{7oE?cI9~IhwHpWKlXm5f7usnACI>2OxXG0 z%{?st!+sp^^}i+UDDz7F2iSb&e~dflv2egzXK|l%eU$YCx-r_qptA83ijZgZB~t_uzlk9zFkRC&nYZgZjq*65e4y z8Q=Xa9e>1Q?>SC+<$vZ^^-DPQw4XRmdHQ(?M~nZ_PL|X2Xa1M-FDdp|*HMm{KZRSS z{Hq^j(zQI=yL?6eEaq?PbM)6ryxbuEV)zp|-n19_9qSXqq=!94iPyg7?{X49kFy$g z*faGkr62UiO}eUlqt0``uARq!SLMD$Ig*aLo^L;e>&pds-{1JNu>N!G8|hLG{rKP#W#{t0-|yTH{s~{Qyz_Xs-ts?= zv;SnCfVGis{LHIk`Mm_p`ZA^BmKs{n(*uwOZh$=_j&Ty50LdV>lFL|x&Ommc>Z{Q zJ1z$-{zrQ7DE-h_SHW#qPr(b}WGeqD(H{^l3D1F3%Kd5|`m5VNy7ixL{kIX%IAK3c z`CX?HF8*h|;dAg}^22W9@AuX2_ZRLLb)72*WS#3eqV^H^)!p9q75XQd9_hlD;efV( zz5`h0(GGl%6`mQ+=Xfdpm-mvRv;$nw|F}>-_DQy5%Ber1oRap9pQi8qvfr^DDEY|& z;cyAN&V$E=^F=-XCLVZueBaUa*Z22*E!+=#f(Kf^S>=J`uN|?UDE`NOKk=^P!#A-T z?Tq$#u=$nJ9&$kRdbAJwqp0h>a1WLF^Tjytl5#!AqwGTo>p!KvlP>w8l$ZRXJ%9S2 zePUPaO1m(g{g+|wnE9OaROhvo|Ahm_uT+0P_@48r^?tmUPd_*AE2JAgGyJFtcfRCx zoo8vc#+N@EVdfc>`qg!oxBL?mp3^D6K=Y@4DTkW(SL0{tKArY0ze4A$eqHTjv#*a< zfA(@ye(Qg;rk&DmX)p5Q`nkWXr~TRIqaOcc>u>VcF8rTv!rdNX7nhX$Q;w7?ntnmC zALfyMey-!bWPHl|c(+IV%d{u=*9<=Z~=dcu#l!_w*(A`*fts zdg0UU{F(PrF5^||L%6HFaP=d6w)q)SpPy{$Mj!A0`6x|!^S*CX-sFCi^`HCC2RoN| z@RIZ0%qPl!$$4=N7r$`7U*FF%-1qImoxZ03C?FZ zeNGqd7rn&)n3q>BCm)-69ro#Yaz4u6!`NvLGjADA`txz}Wgg4@CYtgP4)=?maX-$R zx!>#YKl+LMyRP#ZcEoY*v;6hLUF`qxnBsgZ_cMIt=;40Rd3-ruuut>5*VKJ@aVYLb za5d&T`~sP0z6t-6%N6hQ`r?4E6Yl(v^uiI(_}^T^B)#QTEM*DOWTc(DC(XA7}diF~7@1Mg}ZsOsZl)t`j zcvj9{KKA>Rn|-K$dX`@fpdTN+(&Od7*pFjZ9LLVmUbe$IFHO5pPTGTVms)sLTF)k_ZqoLH} z&6oPy+j0`lr#xM`zNb&R*st-XqkR`o&Yvw=4JMBmN!`W!3&fAEOUnFXMqWbm0li(8iB{B}+f;Aqx{iod22mUD!3NN)B zJwNUT@V-^Kk97VAhrz$hc62_VTnWd&koJ*>p7THbt%|ehcU3%4{!$$9?$(Zf9Pg8| z|CIy6=W<@`ns%KzIsISbrjH-SqwQR3|C8^nai1zBUBADl(w<(AT7UY*c>9I%6TTM> z=ZmiKhKu_ptbI5y$(y-Wl1e()W_AME#g|N9DeVqJK9 z(eXE-K%Xcln(n-W%Zjd!yX$pWRP$ z|1Lkla6c7p2L~+f=li~{58-_J8@UgXkA<7Dzo>ZaobtmxzZ&1kOp>8ji>)OZa;QEKhH1!Kgz}NDE9T;5$@{u|KP*L{hSX7)4#0O*cWkKl>Lt7P>By0 zq}*J`^K*D{>gE1+_77wqL_F!qO^OFzk9fFW)ODczit`D>S5e+e<2>R~(lu;6?J8G+ zQ(HdrV|-oK^mptcTJg;1q{s7>sQJTbyl)w<|4YjQS=T!5;ez-dTV6Py{FpHHL*bbo zpS9{4f5zg0#UY(nynf|~j?3a%;YxBQ=0UEDrhQBC<8;0#rCsCSX?d}aUjCGuacjRu z!za^!mV^5%*E4UJj@*m;PUaQkkA8Q=b3ay#pCzo_Wqy+Hk)L)kw@=zBO1fS@YwW5Y zw|sMb!g-|#qnZ+65Ra)9y!v|RBA zT<;I_cLA9<7$@k9p_C6znEc=brSY2!_gl}e=M6o*N>|>79iJbcucsU{KV07*&UXaE z`||$~{Q$|A{Syk$AiXI0GY?b$sP`YvbDkoe{ztL*uC{yix8p^Q!}zzK-rW25(Mu)% zb;g_hD0gQ+O8#&H$6ax!;$|H8JzACdW#xaz@MXS7ecu@4hjid~=jqk;j3fA8DJy%g zyS=SvC{Mk=YkHJFoNwl7#{bK<-nx6j`EqTF_8K36}<@cwZ$^RHf=9B-+gi}ZBeHre9*mcx#{&*kXrH&6dAaturM{kb)Z%Ei+wX3(uY#jRu^Tv?$HUcbR^RKzf6o27+>dc0zv!BLOSw+o z;d{%u4&HXDycKW%k`MLnU~W9 z(Rp9uX=mOS?Ft{X{fqzE50y{yo0amD?_8gm`_V3SUiSHC?ZA1Kv($EyLv;ViHQsW_ z0ew%H`SqM%kdFBj_oH6%Pwc$WeFW$GJ}>!jobnehvHt1T@@HFlk@hk3KY1MW(Z4So zknoZJS#J5?!=3-Z+bw^MJKLA0OxZbuJ+ZxDcrBh1LwjoGD?3^j;QTc<@CK& z+55_uxsG)i`N8{$hX-;V`)uN|n^Nl2{VKI1j^lU6b?nDb_FwK>g4tIa&JMb4c+rwd3te<#KoP7%158n1*w3G4vFP3@` zhHJ83<+;4;F1VlX(-!B`PCY*JFxL6*cV?BJVdwBm{PW;Y_eZ%1WANmo!sQ6NF2qmI z@nP8VVi&~)DG%IeR?e4)!f*KgAa@&hDR&ikAoY}o!CfhLxSyKxl5VeO!i>k-C&}OB zfaxc$^ZPRJT*eXnFUt6h-yfWq^yGh0>goEG@5IY9<$(Ebn;h^`IoPk*A1d4;;c!0p zw^`@8-=q9;40#9XTyNzoW#7ZT2qj$yp@-u(m*Ta4Y&mN!8&vjAk$nr*Oe{XtTPyZOU{d|5vKJvf# z6H`yiKl8ZaaK$%MPsXYK#+0Au0Y`np6s0N=}_C_pLYFZ zFYhPgI@&S%PkVUPPxp9~{NR7+XN!J5!o~gMe~gEpZt<_j|5%r~zYPDoxBHpIuVwW| z`g`&}_ZOXKFw=LQ$Q{6Wx^q0*v41zL!ig{Sdui zuoL(7m-t`(&$s*eVb|H;6Hhn_k7azSAME^3WnSPs{P|3;cp&}8a~b>3`%3o*v>l5F zI)37Z?R=2=9euHtOMhhMcf<9+kZ`%gqs%|i%$qkU_2zh#d<}bFO1{*~eDdFJ|3k&` z@JTsE@j$|idzAYX%Kgo7xMk*HmHQ0yf$DlhJ|$ z7{0DP*!!(iJ9x0$!-Ivp*Z2!(Dt|M|cl=(R>$)T7yAjF4l)az&m>U~+i>G|jBUFLsDpZeb4${`2D{=@yE=ll=*;6L%~ zw@S;7%ARiKf80M@ca}QN<$u_}_tlJV?VS0A@x*=7ah&gyl;0oYg!wIc#{aPQ9?$$t zSalwSLok09H*>yCnEmg}{X8xQgsYiOotN{Y?9=3L%Wq zCme28##`|Q&M%Hfdd$;uO3tHPp1<;jdXJRjUS~b+SJqpG>$&nj{Q@6s=h5z*k2((F@^Y7?Tlrc3oLAh>cCa31>`#uNKV!tg)p3CA$Z_lV`7RUYh@{G+y8wLAM4c`f@e;@Q_k8Goc-YP%%t z`^<1s>WBItR>Rn(?NDm|v?un(xa5A++Y^2a=fr<8?HkTYI`G6&%UAtHxZa0myvQ4) zwxjWI!|=MO|1HLkllx(D%<#<4`QkSS-y zb@PNQxj&yde1?*3dJllj_6>R> zeIMh(3g{9$^S_9LA0DVN7roq5&DyO_6Zk7zhnw8n$& zV>>dRtl_irF`rn@@Luba^3(70b-h37Fa7euYrzi>qQo97iAciu7| z?X=Hl6;C^HoPILhS?PD;kL{UuRa2j6+Mz4y&~Cjvq|3PD{_FTFp5wm#>9&t&9U@Ot zx$g7rI=|~jzJ8zY=`A@P>V4(M`*|qmb)}sMQ_oMDa^9!=`6&5y{>S+GY{a8K8Ona` zi!EG!h?JLcp+4IAW%>PuPlQ9rkHR53e;}Q_2OK}ZZ_59=e;@ND;nJCBkY7Ka`rqH? zKlz>I(Qe|ecaxe=aX;?MoX>o{azOGW9_|+dOCCo_G0w-ZS@$|F!8+{-ht?*OlY$duIMez1%;A`z37s7;n^DWxc>W zOqbFD|ho$JZf9Jh)8=P_T9ekt?bofgh<`tk0F zk0yTBr2G16dPgqFI0*O4yqS44T7K5r%klY=@iSLue$d{0514fp&mD+&U8!>abexy| z+e`bVe8vA5Z(Pr~Vt#Ubl^>wvOAZkZ$o%Ixn^iu6m8|ap-`hFF{h{__sq?OUkmGAO z=O^CzI_J5M?mW)(E8hNa{~jKA^h=bBBtGRo^Jh$XqNJbe^dHo3F!{0%gvZe?a4_3P zei1Hq#{Ilr9&&si+WLe?qO{ME^Z8yV_3^lz$9|wZX~*i1)azz_Rr^-?sE7VeQRX@8 z6>f4<7dD*uOKQJi57eK2rT)}gwY+7YiO+Sex4EwT-rzChC;ww!vYo^I z&iJbBs2?BiE!)4v`NI98a3RJ^%IE)S;dT56qsmWt?Y}7VCC6E>dmg-x^HASwEG1pq zGaQg{81860$swt~VZOU+dSy4XuUwA%7VTp`a4Yyu)Om$=azCaYAma!gNW0w|=QFGzlSe(5jm?mJui!Lw{fIAHubuSR+Jo?BF| z$9*5ZC*Oew8ZO1Y%WtswpYg1NI35lt&*|@-QtrGTn(xi{9tz`x{SNz7_dT`i*q;dxIzHcPIaLT?v08f${_NI{1_6qxe0# z9tp1qXR7yA-Is(TtsLvfMQn%uokH4=Fy(=VMN?1O!TtaI9YDt6{C{B5asR}39qPqrE=9WXsc=2~068y;pP=c-?&yE#L;4@?S4zLcZlh(tq>J5m#f}Z9 zoceb$e#8C3`{MUk@y^rovG}R2{BGrA;eO|OF2wh!~M9f z^FOYG0}}t^p>jU+t#IPClTWt%J8K{2=~!ay`<0 zv8Ri&jzAf&aD>wM9Y;I=vtFD}J+FsyUqKUQzBe4zAD!}vnH_Z{mNX_r`V~XXR=-(LSEmeCGVu@~q`P<8LefBMkS8 zQorJW=J$)e-m9+X{r$tvGulbW@fRjxoQlOS*EwBM+2=+{FLF zFW?K|3e=x?>S?^?ru=Egn>1Xo*Ejv+b(hKQBoda5)iceUT|LM<3e)5)?qxAY&|Kd3G1H2C|i$9g& zXFLCUd*XhKGsYq5dH-Tu+TUOA^}MV(kN$Y8T~B&&MfpzY8gJO~Avc6K5M~|UCeagR=bC5k*@Kqa}Ae2CAg}w9qO}l>`{wD{_`1s8} zPVlS5?r0b6n0b$SqtsiqpIFB`FZw@5=GWiuepbI3T#NTO`Hv%LU{q$?pUzqW0yE6V~ zE@}IeKcDMQ%E7wx-$(j~``1i^G$nW8(H-3QdK*Fn1PyNH>5&j2-bqL=xb3Ky%MtDo{ z4A(6)|KmE=tNu?}b$!rc3STN7Y_^< z^gQh0?#Q3@EdMcPeTF}V>$Lb0#P9E$@ISd9`(XK>?Mpvmcc}lPk#o>4@D8;6O6566 zt`?pnuZkZQ^IF!A=PLJOU1>jPpImP^obQt6y5v9iH|dgZ>G~dO`TrI7bN+HaJM*p7 z$NJH3=7;^7&$%)lt^eG9+y`u5mHQcC*5l{xAun~jQZM_5{k-QJPCWS%AFXz-cJsLX z5I@k=2kvFLQ?Io18Ly>0>9^Ep?cbiS^DE;<&PzETZ}Zz_eYzi4$&dN4w5LycohK8v zeNpCt)vuKJ-tYKPQGfnlf-(-dj&Vu5UG4QnnSbd|=Wq90qz8AQKl8rtPezz{l=aDH zyMDUpkN5LXuK%A+$%k;1^a!J$?B}UZcK-Kx{|?~eo&V+gf~Ay)_1G6pSwDvRMde6& zPx0Z#BX}Q&*&Kk3mQ`R-c&zc9B0$K`A)?cMnw;q3eSexH3$_V-8rN4{`C z?B?5(GA|I%d|^L+YvO>+>-MAn9bulae10#`=b7}I9I(G1?0vcJzt*q7?nXk$^;>C7e`30WwJ<8qVxz7Dm@xj!m=U4Zc zy6-qY>2Jkx#{=!_eTMgZc}^aFXTQk*uxrEjhH6)wkA2$j_xJ0<1MhA2!gbnF=YOnQ zj_(8eHi~EljqaBD=&~gFps(44F^2)|07@gk}j$9 zwfo`w`@Z;09UrE{anhTW`-xm@_8Y|R;49oWxQ_pSc>UF;Tt~RH-j_7K_@7~p>yPGs zo_bS0;%7bbHS>{MgyZ%1glX^avBc**mG*=SoGW|}PUrpb_1iV=8_o5UC+)Ge6XBe% z%6;I4)}z$&%8B%A!oIDCoD%LqyM+H?Uxs~u84km~T&;GZ9oWCC*b|(PcEArQn)oR7 z)4$O36L0>er~eb>sj%0{73Gm~Kdyfr{x|cR@V-*)L%yVXAA$412N{>N(~G^GUTppR zXoM+OSL*%dh`0V+M?JZY`D9k#^Cv&}Aw2Ty(SO{(=-*kHci?_^#^~e!TFka^OU70G zmn8g8t?}b{ID6mKc9(a}est^udOYh{!qMW4#r?2<_@DCue!KSDZ+Cv=apo=k$QZ}8 zPmO2$(|JO_%1iu@d6@H|GXEF%3;#ozPom*|+Eb0s^iS+}R==kRm(`!I)b=3E{RHlYKUgX0 z=>JE&T(7?Ohd&_o`orLq`U%GG&;BY782)EH!~Hzo-}|+_@O!*J){#74V88G9hBL$Q zemInV_-LySoDcrT`EcND!|4g%+s zx5_6w2gEMf_fxNxtAxwQUucg?kNi!S>unD-+%M{R@dN#rVgLLW8asi*X)nGP4F4re zeQr|ft$m=Dzcltid)0g8-9Gg9q+I%uvM-`u;Y113uhzHt%2_ykC|oAjMH$~*7hTU! zd^Fctj&N7)g>-T}%60lHz$G2urQW}=5AGM*iGFDDmxcRVFYMIzBb@dqE?0grrW1Ra zc@*~n+MD}=?Y{D@YIly$cc8T~b@{-?+5 zQm?A7^VE~=dfK~(;en=0y!S8bjeoNFre5~X%qOeg%0B5A)-helhcN3CHT@_Dl>gCR zj(7Tx{OCW*mwgk;K8xe*+wluzA5R$0#&MMVKO4&P$xrt%|MTEJ_Tv%8uA=h4cXtjL zl?#$y=YOncKH1WJYfBe*sMk*K@op^NZ=u z-|1vrxjr!eTu=GDKL4XCKfvVM%fod&%sTTdoN_Zhd-;g(^AGc=^Fsc&qF*KX$YB^q z^LVnK9`5~hnYTxl^D^AAvxU<*N!c;lNBAavupdX)>$NAi2KNop!EU-@KXdv$Jq=VpCpZlgaPJPSKv{ieOd?+l{l~bKd%ZsYqaDpJ`A1VO*3kmqQY3Fb|^OZNfw}rV68^7|v z`TUvxt^SnZWVTE3GsESFm$2eDN&k?k< zuC({szvUOmJnMH3*-znj$hwj7O?>$UQm%ZL4}U((8D6KKAKdTWIFIlAMOXfp>#jyV z`Cg#^H=$oh&+qriCE<>ghj9(3W!_*t7ro5?=%?a_YCczA-x{XYp@OMeOCpMSs&y_Pch#{K-C!dbpoE=R@pUtWWki z@$;IwUHBa1jPs*?J!$)xUZpD^3$Iz#bRCbq9F*UD>{sgN@y^@4uK1thy!apOC;vIq zo?hy~JY{_95qr@7Vu!JZaL=lj{Ezv^_Meq@>HQ*Sr=RryePi^u$JM;QU0iVG{cCz_ zf7gCqJ6OZ>^|XWM$-n3y>?%t6V`rW>+g1GhxX);pZ*Iyu&agZ%{Ev1ry|k13k9M^k zVwab+^FQx<*aP=Z#%*!GyoW3w#C|<42jsqBe#tlQ>6br+`}?Q2{?~5*DCPgWDfg@A zBaHH%FUR})zS#ATxA^yN{o|(ZF8Xv2%l}B{lW`tAQ7!KG>4;|?WqyzL_kK%%vLF9q z(KG%>I>jw0ciuyr_p5!s?fkUzzY5c@?B7b=Uoanb{#VCuKHqt?{F>x$iW6-$wp?-2d{kCW~?WZ`PTyAc6<|%kl>9ft=7!ULt z&+|~82lg=j-}dXf+xd)B(+NNH`+>|`mP6%!BhU4|@BM{!!FRXu5k4ON$NeOn4aJ_L zFGhGh-g(0HI8OMIhDR_iIZrLWyQ~kok{{_sQy%J1xw=xm|321NFK++WTR*+^Kepq~ zhTU`CJHy_shv}uhDEEV?_jmG(|77?7BR}~~#t;22k1c;bc_186JL!r&!r!~{o;YFr z3srf>>+!$*XCr##+{Fi3=g$AZA-`}w@3Z9}c-h~Nbn3cX@45@_PWe|(39qzX8E@-2 zJcj9q|DX9^=7A{oQU09Yl>g=a6Lo&^`+v+2?njFIF+X#k|D!#qNB0Y)9{NF2e!0f1;bOFt$Mutfo92A?;qJ>x$9;JByR^OH z_qVoV@jcu5820+k|CkTtM=19N`ajzHac)QIL%Xe7<*xFF|4~oYi731U^*!baV{hSp z;c8L#^>Eix`%gY7|KobXD)lX{XMFc3%z07!)%4?^NO@?F`rciY&+~n+629Vj@D+IH z%J;O#;(ZA_-uR!P>ss$?$ME$?m-ijJQa{3IuBSio^HZN~{mJub`xSp*%UAw@v}1oy zIN_1qs5kY9dY;EuPE_@`J+)_fQv3(Ge;fbauK2f+9-IpeUyO#EcE3r^BOIP*{lojH z7wv)4UZs{h?Tu0{l>LffzmJN4fbsM963Ewn)1Q+6PMH2BC4V_q`WvM^4Ku%KH{pVW z+27P0<{>h}hHpPA!+=kJn!z4O0P`^j+}Kku^J*suL!KXTt7thyhE1LCJB|AXUO z-{{Q$cz-vXPyOQ_UjP65$K9{2RLBRc-w*!IxZfr$U*i57zN2#2;k{4dET!NzuJGx^SWQ4T&wdwIG5`w zxfJiA^8b?ix9~TleSWaz4`*^8rXS+1JwERP(GJD^xSyW!zpK%{J>K?b{YO8@Rc4OT zIbPQFtovDCyZ%3Z-*1g4-S9uS8)21lvVNysh_`);_i-Wn|0wx}2ZZ}on0n0qg{E)2 zzz@Rx!T~*Q`}>|R91DA(e(s;oxgU1udD;(Lh_Lp;+YI!Rety1h4)4{zQR)$Xa;EHy zTo=yDJWG6(aa{hMq#xchpO^DlPoAZFDSl3$`pBn}5A9@n;ec>C`XT$Wa5{M<^KaRk z^QLz9=7@KGpEcJ-lU{V@kd(*tqQxUAXZ-%6th?=xynj>vbH>Z-nJ?@=$0PmSkNcl# z%0FL!4A0*UkV88jNbeY4(<^^J?2Z13S|0f__GNnO_3}NQb9ui1gJ2y;m~|bRaOZ!f zr(MNfV#n0eew&r+iKm@W{0x~NqO2zgM>&shl=PFX<@I}i~u<{p+ni`uF?1&#)h19KG0%cmE;c>;E2H&v@<1{6ZM@{$KAWI!=>+ z`~Z*N2Qj^H!1e#ZRUXR6pVCk~@hLa{GP7Dw?mtPFaxhNOtcOtTGV`PVV_US34B;9Vxj(G2v z`$6tMdGEKlUpS!mtNI@`_PO3)bDt#sjQ_3Ull?s7gZ(H%Bh}4(!qpUL=A1XY7aFl!rM_C_h59Y%N z9(;d*^#S%B4w&OyFQ4N->hh>k{q-trevS*Sv)_vE#XgKb@;}q_J!a}ln05#cjGf&X z?MJ)&oxkFLoX`BEVu$R@O0^f-6T6uEwffQaKjVLLKi)sa53k-6ww#7L@1wo=E@u>; z^5ho$PqjVefNzg@)8{zp%L$(irT(4&(T;FH=0Er!^P=zluKbVZ;f{Bd@dNi`eB=M; z_uhUn+VN`e8Q#a>z0@f8-`j(m!3FQ$`gmK1@LsR?;m&d37sQ7TUX5Ao<86O*f8Y1V z|BwB;>&&R@P3#Yj$9JpbeeB1nAK_J5r@;T{NBshMzR!8LM>*VghyPIy>@6C<05$u5 z_vOC#EBAs6(Xa9%+8=JD+HW(*(cg~tcYU4rcxOIHe|S9q@zwt>ye~>Ra)9tZI05x$ ze{X+>1Ns~ruIKSm`cJ+P4Ie0#`@r$S{lfR?2RsQ%P2csZ?+J08>$La}#J@8-^T7B8 z!u_-(IUn^UU;RJB0qNhF&#-@^Kcn+;Rs+}(b{Ota{#e?JVdgo)%yT_{U0=chJzjoP z^!v;Q<#)6n91lA=azC%f{<%IJu(*)NneRCsW&Xtu;3aavC);uE1D2z!^8)2ye(-qs zX7t=&j{TtL7Y99Sm$X;4pW~4E$MfZXy#H-D<1BU%d(q#ReC1K<+@H1+=^Qyc_8^2U;LJGVP9zn$LZ63yw-nO;VjhejQ>$?_#gVoo?cX*=Xd_dCt>;D zvz-I#|A!rW{PC6!>mAaeJwILa`5yj!(Vy($FNRY8D1M8iGryNu+)qC7_uzlrH~V+| zxSz@a&y{j@{^$A3pPc{q(3u}_pM>*8v2*xe*UlR_kM|BaUhykO=p2A@Xa9fB|NP$r z`z70b_Wxr%VP`1)haVcseBL$j*p+r!euMURINp5Jl>$qPs z{v1y=-WX3Amr?FJjE5-Yb9|_ji!kcA(~p+(E`?ug=gZx~lV}IW>CJj6UG8Vaue|TT zvEW~&w!h_)|0jRca?Ko&a}&UzZ7_=?EnwLUb`~xZ{~lrpXu6ea6jvjaJ8G|F#k*Zulp;e zzSz&q^^WZj4j8{dm448F5I;QmU2#9lQ}ObUdha*ksQvo;y?>)e{ztm{{n7qwesVv{ zMZe^IO8FoB)^f!!OMk2K=c4`a=dxXk(`B5|UvR-v$DiZ(&7JErKIym4|7>sj&GDIW z%lIaqehBxQxsUzEdGfV-KRH}VJ_LVqKULvTj8WbmW_`1 z&k$z+Li+j%S`N7_9CuDX`IK6|l(V>>T(`pZujh6DQ1ZiW)Jiw`YNz#Ff_VD(YLu7x zNq@kv_y2%=y^o)oPm*u)Nm!-d;LxSS7mvm6IUcR=5RyOt386gr%|^rhqV`w$2Qq*0 zoxrI5)WhWehrQpUjAP=_`2R&&_d3qudz{z({jjqSHa}$6!<7Hd#`~hogWuoozxZo$ zKfZnIAI3W3?wA$+%eHU4J-#RC{h0rQkiPoHExBO+8+`TBKTysCpOg2zmI*p9D(&D{&eocXMaE1-Sx@q@juQF-;@93c|B_ROfUWfs+_O-4ezwDE-cUsw?)Zy%5hhg0HbYiNB)fhZlDKqaB62oh#|v z|MBPRywCZFeGv1K8h)pJzHWZ(ORZPz`n;Xe9^rp}$CLX;`eo*S@dqy6JAYq*c9H)@ zivt?3ePN%5XI@DC)_CWo{C~!M1O4VcNIy8|9qb_I9aTFke&+n;e^JBxSl4-8)c1nJ z|JZkUJnfnOnKgDryQUxLck*#Qk^ixtaok7W+U$e;9LJTe`4&H?o#;Q5eAs`X@D<9b zzO(!NJ=>Ia>im!JC*yn+p2u}4>8elm_kAC4%KGXbxAWiHjuZC!ng7v_pN{jW-}7Bx zhyQW@P5iI>E4dH#eKl5M@~heZkC`L;W#&2d6RR@M5dXTmUY{`ekj|@>br0_ap6}=B zPkOSHdAsV->q9*G-=u3koexmn&i~l2gaf*tum7#UiSSdUf8bGS?CkNz`xt*;Z2f(% zj0=vV*eCNvRNkBSfTQ2u*DosTAI9w&|8rc0`{g~^@Ibj4`Cae%qS!h6l4!U>l>3St zFFXQu-H`mcQh&#Dsr#P%r=-fk`g|=9W@hIh+ofV9yPyOH!yFoj-s8o&Uxngtg=Xi46 z)HxsH?JVrLsdNk{f7eU@H~1g<;0H)~?~Ha@)#Gb>uH!iKzi^S#P*G+j2>hn>?9d?cVqTJUU zNBR#jJ{*_u1JYBuzY>nJpCpVr-cVX!p1^(T*SDXJ)W5gK7x!b|9PY=w==JCP&*N*l z;TUp2>kGf&`mUre*I2dw zbHYAf-Zv|}fq1q2_{z`Ec7O*lPA{wNcRkkS_(jW);Dhk72b*4P{p$ZuXutGZ`iFAZ z{>2IBc3a=qo_Qd4X1l2LZx7RM`WvB?xA+?G8B$L98~<6hKC^}s!X5n20>|-(tN;1h zo(adVu(+Pb@jIlx6;HeIoj=OKd)ssQv;+Fx_}GWM)bIIWC$=AU&3P#4>d(ixy58*P z(LO#iPEp6lul9QVYQH|pb+l)$SLOEMfE<6Zr!Q}^ztRuU>L+;|*V|9${EzuY`z|GY z=Buvk2MNRf(7XF_{2mE2UwMA~?Bu5YAH{hLyW~8_x4e%0X;1u-cpkv_$gp$P6WBN0 z!g1mHf%UrWqf$=8t{0LX`$*DN8NsT$^mDSM|Qm$<)**og4!YToOVo@dU3t&Z#cZs{!YI~XZ{DrW}Kpo2bFfYP^ zS%1IrNyj7SGY+Hr?=g?{{|Hx@cKpNEekkRAwq38vo#cJF-tYgxRW9>C#?^O6`LS30 z{S31XxP9xR5xyFB`VT|lM*nHspWM0iqiufy4|IL_@uqif{l`V+fp=bV!EnDQJdpf& zf0%me-;aHIpJ$(J|I7XG^WlDnaz5NA%D4zOLTL}UUlhB8^O2tKA^M(j-Zy1@{U6rO zwO4oCJkR5OKFmzU9*>>z*=drVQ1ny(Uf~$A(HL>y1}%ajK{DvT4e~FmOPB6-la#d9 z_F;e6H>g*l$cGOp@>&n2yswab%j11U{$+dkJDi5|Q0^lyl(QK>>AKzhovc4xmnY8e zhew+4c3}S>ESi0o(eCG4*9q%9o-~|}e4}t3@1y3uKa5KpCvGdMUC;G){UjeD-=vwJ zG2S>&lmFpQwr_Y}IN+7)cecCSi1M0F{MM{9@5O%Q8(hb{?@F0pn(yP9^X@eB&}iRevi54+^} zT5ram(Qa8ER$Vv3{~Q-==kWbeXFt(j==aR`qtx5KJA7wX)~lpZ*PpBAI{;oseY1WT zHOEIC{WpG$e{;Nko_LtVAAGvkljoWB{rE`B1#`SQ+mCwEUQxEKKH0@x&mFv;& zq?xC9-2LA{nPkA?gO7e;VDtdWDML0%O z|ANCASCDn`6(=Jf#>vOk`!Wu|?Xs_S&F^XM=Y1YKkM&Q=tKY%_d0vgjO|SPqr(IXB z*N?n_dXq-s0IV0H+INosqg`pAD1M5+;kUNuw;uRjINzOy`+0r7AL92xn9t(RJRfLJ z<^}Z6D97y|K8JZu<@x#5b{^x4I?t2o594wAB^)7qA)4cimvV;izr6P^TF&SF=QQK6 z+#>2co%*>BnE53Amhy3bbWNxHo$ufCKgJ8Lcic#v@Y`cNRYz_f4)hf7TYt}WqhH~# z;ZVk}`aKM4MtQDPzjodtcf&7v{@p3}3IAI;9>??hwR*qxI_}5$V>zzU>2K{{>2Fc< z>F=b+{lAV`I-d4f+wGjDRbC!EFFNyo_(sMBb>@Hc7sp}wAO7li z?B4_NTm3PbziVdRbIt$K9~o!tPa{|G`NVP7i)i9yR}RSYh;_7_0)=P1-TtRPzTRrb zx;)2yK7Y04=XEHYX;sf}zSvQYF{{sya4UESeg*%4|H(&^KU^#KxzC^S$PuoU`-gY3 zE+>srpK!TyJMZVZUjDaoKgJ7xN9~uZhVvzVIgz}L=L_5qE=GOn*N>_8iJhXez2r&o zCVG=`Wwa~yqx`j__s#v&UX;)Mrm@SY;ixM4X~(=Da^;01H}!tROUmJ_uiWj;!QWQ( zd&6)wI33?vh41NB}JjM6X!8JWjJI7x}#ozQR%i(@( zxS!?J-ts@@iS$S2kNP)hzawiu9^(Pc*LDjBY<%J9$M|o`hyP(8cn|#^xwbG@;}BYf0zFezXC^PA6xiWxu5qZ&Hbq# z<%yR2al*{~I3GK$%J}O(Z1Z6~>HT6y#y7c>{4X3Zn*H6VJaX2n_Yun799LEjIP*X1 zM}F{@^ZngN3*UpkRjDZX>Tl(Rwxf21v+8H~1NEkTRgb6ryB}C?SNpX+5g;IohZVoUSaiT|`8f3c_OPwW@w{y#eOdy`TgerNv8 zJcoUX%+vA1vr=!~Gsn6N&XBbBas8dYTPOa=_YcC=oHxu$eS4g7fOOP2Nat~IM(zuj ziW=AJ`{}|P6E{Vi7wzKrPO-o1c;gDWkLe!_O8tMlU#Dsp*Y|#(m+{1OIpCb0`C`{O zxh@z^K%J6K-Y#d$XSva$1M@7R4-{UPyxiR*&z`n_q}=dteq^BnCyVB5cZ%yydj z9_94B=p47j`i0-4vtK!mQ9u1I>G~h*x$%0&XVR$lk)tt=>L+Jj>Uq|K{ye5>&(ur% zuYB*Z?_n^zF`kfedVRQGH1p$dC(9cS8P3OZiE=RCwmh9*o6hyK#;&mwf7il3D&IA; zy{~wn{xb7o%EdUtJl}bLI9_z-fA}}!Rg`)-e&zh+_r;QLxS+>rhjV#&&UifhZ}uPT zCHG^VLcNoYo{!J=!*5(K+K$xQcCY(P=6{TDXKt4Dc-HTuvK}FQr{tIOlTQ`@fjg?K%gKjz zJ>_mX$5pQ9yu0|G=Kpwoa$d?8?vmrtkr!A#??0~VX&2JyxDT6ox9y~|4v_DC{P2Bg z+u83;(;rCVucP9ZBd4Z+kT2)y$KinU_`o<}Kh57)I=+Vgx!%Zr;J&xd<8zw+$#L$_ z^?5HR{f{)iqxqe3`@GJ+{P{V~_+>e&u5-%&QjV|o{L2GLbDvSU-+W&3iO&0f;hvNa zb-c)T%s)B>bjZfA4`Ak>j!PVxxb^g~N%nwQJM)eO2pw$N##o+v^x#S*iAT#@#C8yIel+1DM|@$#c_jTo>*HzsP;4pK0vNeep|ph^pNkCy0Mz9N;|5G2X}f(o1rmr{WT+ zm-l!548NjZp!BP8e=g^BAF=D@l>_FxB#-ewpLfZ>{7?QA{$||Qo6Qa!f4eCh3NGmN zwNLDHR_q{Gk~gjGGN;LxcHn;agY6TpWV_FClExp=9&l66N43A4Cmhgy*!WHDW9@_XX)5~oKTpyjR_ZwDWsTx%TPng4m-zaHm@?}hi}eQNa!?kDHOpJNx> zQ9ss>mKT4f-1={Mp3k`+Cq5g_Ix6{)Ms0W0_VN1e-~Vdw4~+->dhaK2B6<;Vcf37U z?#B0+;Xodz{YE}Szmj8RA1?EF`H_5&^#u8|4nm2qL0NBk-~4X+<->8f8Rr?-$MYQf zF;BN2W?Z_8=f}U952)Ay?pMw6?eLZ#_L)^~^)GvTn)3?AQ}SbdTrTK3**HVr-w0nL z&HeuGc0Ki^UvQo6pSZ+uLe%!G%B$@k*{`h~Cti|PmiP&2 z`mg1){o!!jSCvQRy_NVm@qzzuw~OCBhA+|&sCW1uoSyoUCLYiIzZ0zZ1k3%I|yzl_!#hCuW|GQeXaF4L{>N z_@eVzj$8h#>&E%M<(v5*_jlfV6e5?5;fwEf*r8@|Nz zkK;W5{JrYDzWj~#2=!sS;koBJV1Az$e(v$_+^FZ{m$}~Y>x*L?Q~90aQT&Pf6ANF^hv&R3q-#5IEbxY2(KW99$ z|LCXmhqROXf3dggGPxi33s3o*-7a4o-vR#o;B$@pEC16Ees_q3J}&USKgI{&`^S8H*!> z_?=S!>)+@13t|V$m-my*{0}bT^Xr=b(SIDrRk(v`{M2=M{kQ(&b*sN$`!mlWENed+ z`5wnd9?13M?{X2J%dfV2n19p!-tYA~PbvqTx!%b4%vTQB>pj2kA?$s;?>Y`#bH6dZ z&-yq{Jln<}^I7|C`=h^qc-neA#Rvb_HeSM=)_A{iKJR-@+un`?c~9ib{}>m>aRYxd zE&pR)gFn%~umk-Gf6RObr62RV{W)>+;eT>?o{#h+;(P3`at8PWY1Dp@ew+9}&zB3j zUJdtA;Tb-^=x@{qW!ziUetf>~eE+=P10`SH_ZubuH+wl5Z?jLm%I|PN>_I%Bv>K`ZD)8G$5o!!O*5P0IB&81&VHP6Onb@s;7m#5UyOIu zi+Dil$@LuPI*!95tJ@Fz?@^wY?mL*(^3!jKTZ5zX-ayiP*S6~XUO%UN#`n=L+;1%R z`|99-{7!ioC$LXAo%?Z(>(l@37v+GY;d8Fb<#Z!Qv>b9h_+$9rtL=Vp#}|9O|L^vm zI=-tyn)02`w;gFO+LLk2eb)J2O}L+FzAJ+L*YA+fkK};zNH{sqsd7JgpK*ci&!=C) z`QVN0)91c&z;7MLN$WQ#eq-A2dN6PE`20RU*0JO(_tXAxK_L4l^F0uLR}&w|d%l>D@SR|<>wX;Ohm@zP-~GeRNm-xT z{^5eof7rL?b{`;d7t+w@53(| zzsLM_{(djzaD8L^q4iq1fb*v8v$ed`k9t!+?9O*$YX2>{^=sQ5eq+AQ)BbdCZ^}Wt zV}H*x?h`wZj>2D)#=hhFjI`}RJ<`5%y&f;`wS7EKE=f7({hDi(YLzTqjVe!_A2DE*H7qH}rlk2xNU^33@r4kPUo9;!0#TmEoP`4jV9?#uWR#m>}& zcI3HXI&olW&+PNM;(WBv`8e&)ar^hI)W_rbo}c}nb{_d#Ih@>&dbw`McRi!uIXKmK zCnZ16U$q=i-t)z=zL<~q{+0{>qTKk4>nX~A9*_7th5oBuSihM5^rW;CzoX%S97v_0Ps+)sa|{TZ)D{)gXrzWanp%Yo&8q~(6m@<01s{w_50 zKc0`S2fw$?cd6HxyYl=bT@446qtS1?E?R!TamGc~os1Knm$*Nb@{T-^ameSpT#)CG z*QuOu`L31nSl;eC_WY#h>!_FchyTrgFZeM2$8$dWg2(>EIPz*A=T-eQJZX&wOq^NN z@%Py=4x?NTAEO__!|s&+LO-?N`24-%@SZ0ZS*8@nKZBiR1Fed%N?T#1Bx~o97b!c$|+pU&=mp_dUStd>;B9jPm$!zPvAY zR_yzxm=*9) z``{(~o$F5Jih0i;_H~}1-CI8S5B$#j%J;Mb+~{!*X#3a>Z;y74J#rs-Ep{T_PYwlN zG2V>p%a5@eY04SJPpD6LhH;|W*W)Aq^EliI`-QWG!?8ZcZuk6;a`kXTIqLwG~6YS=7 zQSyTaMm=9Yzv6$4N4z&VNf;i`Fp9Hu1bFLVB`K0fB0$}&HQeP?*&YITYmc`eqq}F$a_33M^p|- zf8%)jS>kPdk0$Yf`Z1i2a#ZmH;sGgV`5$TKZU43@{A5(lBMpy`?^WTKtZVsBGJGp( zzL&y0lYY*3eSQA^XySjy0rJ%O_xtmheZV}I;e2S)W4s{i`xi$%VU&3`^Ax`;?Du`; ze{dx2$9o3xf96B3ucP=A@k3lEmm;3gd0^s-_mlr& zhac?iQyt?2`Q7x&{W$J=E%A72jz@D{bZ(Ed8~r5tth|r=Xjkr+{j0ne(ffNo{c23h z`>eO^*?7IQKj(8EN+O8TmDdOV ztN!9R4)o^)B)W}S=9@pp_LPxCYS8Rt1(J{|u@znb%P zy@J2-WYq8SUN84ia{kCoOeddQkLJ3S115b{pIlFV@CWlrIae)Dpnbak(|%R{m-T)) zZPfj~?;iI38sGWxvETdCN%2d5XCCT#pCA5E4ya$`J0RaaID?x0&UiujQ2VQ#i{H~v z>_0OP<2mE{F!6!im&>5|@>`y0-Xo}DuiVe` z!u_JTE}D8J?$2?C`Z!)BPC0+q$iCn5zWS~HIQFN}PkUT{OMjyu((kU+>$jgbzjj=H zcA@%he>Yt}wOmQh{yfGDdYymoy^1%y`kj7n`L2}y%yCq|GmhA_hhFhN+nsp;cCL=sjo0&(cz4`i?#DRZa(kWJ%kp!6xS#cT zv#+P+eykV5|KN5$7rs8qjZ$AZ(HP%nc~=fto=CnUH%hrw?ROOqsXgFAaP6x8+%)-& z*IQ1<&G5j{KjcVU4^Nu8?#K(txBgPUk+~~aIhqF&xZehF@oYMBNy~18{e_8KO zf52XrdoGvdgZokL=v+>@QhA|%f#3T6&S*HG=i~R-L;o-L3;&~^5T7bHUv=bv`fa&8 z>57{{Ckihl z?vi;3Y3I))|D(O#R~){l<~a9ZAMvQ<Jl%E)r(5Im*7!ZrUdK2<{-eUXSXW2+-F0@<@5)kt zj$>c0M@eJ1k>7>$Q6JX{D%Z1qpgrXZrtu5XSIYGqcb(#W$Y;!#`&nL<=Q!zbz_Gry zo6jHm1GzCh=2NxY zDS!RIby~lt0I$Jra+`h+_!oP=pY8i~ssGQnH1j059)DjY9*}hl%KZPY_HpFR{yXcG zJO1~}?RtLyn?;TDdV9osHI8iF|C=}yIG_1M6StCe?7GekU%Oiu(+_wuMzfCgIdRSZ zsE6a|S@9?4{ZXH@#!JBmQl4`;Er-Y9dORQUzORx0~{@s2~xv&T2nRR|o0Do`5PW-(g_KL3MGM#>Ur?vC> zdiwi^#tA2%=Zii0Zin_>b>)4H^Yi?xH0?R^Ke&hELf*?T?g#d{VShFLkH42WKIXY< z{2%^}-SKbyGs^SY=UsUF`o4^CHPrk4)3(mwI|;r&C-J*850ocxpLPGP@nZCc@H5xb z@FV8UaE>P7CY15@XuA@`aNzwUr*=B_ZWXX zZ{F9-_@m#C+|PA_{4ehl?RyCwHxgewEBE1dI3V>=dHQtTq5mb#_$5D*_iF}Dq(9ky#}05n>l-ciy^a)g#$i2xM5ZPM}Dqn{`8n{@Lq2HgM3_X z)4uSD>PK7o;e_%Xg zl-uj`p7wCWs_m)D;+IFh49-y32 zfA9OcUH{K%*0X=V`T6V3-uxc^$MeDQB|J{0K8!!nkpsGJ_~KFihn+bOz2bk=Oa7;x zd1bg|>m57DJK&+=f7(Mo(%#sSbd>w)H&w@%u4Cr)OZl9~jU#3p(m$^FpY7|qr@uR& zpE(D1@x1W#`j7RPc_{55SE(A0_pKui@UsVXKXAX}d**-6zr+20zK<`jH-5;t_-0do zzvq9>fB$wrFZ{2(&vx%V-*x?Z<`Ax1$8|L88OOb|IzG;EG@MWWeN4HI-&b8ZV|fPc z8O|}r|5@I1Js98NhWx&AgRJvERKxl1bj*i-_Bj7z{SwX>UE?^7Cw;s5k@K%8e3|&4 zS&ctsT+k1{{h;Rmo#TCwRmYidK%Xo01N&3eelfmpm-;0xE*fr^xV)!$UASM)Yyb24 zT|S@wYrnnbi9A=FzZ<{DI79kQ8Gl?KM6*uF-~Auwf7o9;<-G+n|D*lGfzyx9{yF>Y z+Aqg6{Up5J@%zP|X2oOr*^z!esQqRAJ^4OWo|N1EedqT%ZX6#^GR8|hbX4Q|@Ed<0 zxnJ({hpYYlE}y6ByZ#F>Bf7E?{#sm3#`I7e!Z?qjo4w(8-emUhD|A(E*|IDxHvEHfwm11gejxWMQ&|D!#$TjM9?NbHlgy&5NJyUXp|pX+{Aj*sz4T<3f0s^h*^?VEh$e(c+3 z{ay9FX=6Ld-O`?O`*go=IgZ=|ZbZK>|Ks?`_qZ=S_D(JDnFD%!?3eT-+v9qF_T$_S zyN%y1vH#mX>-V&L&o1*3`$OXFqvcnY$GBnQzGdIi&NK*i9YF1;50g+;>*|j``ld9QBf4+CKOJ?HYebyOXBB zxli2R?H7CpCj3u+_uK7$a6IE@QTQU?kH$`8JfQV8?v~^J-HCWz;t!46lLK=9?%#Fa zCcm=|^t>;2g`@D@4&vYb-(mNv{Lk+okG#+IEB)8~*-`xA`}=da`okklTp+xU{lPpn z{&G*hc!&@5y@ABl{jaUwueW`{a)los&vO)ek`MKTE9x)hfVAhx|L`N`>+bi31M)p% z=4o&>*Q>r?j`EV0t3^5QC)@fg+z3@+sP#daIUy zex@lO?K}U@cYcW*rJdz~AIksA0n7cI|H0?NSG|ABiNDVL?wp?aUw$wD ziyx`sevB9Tll%{!-g4Lv^}pti|8QOX2>ZwbbNq_ejr=e17L0G*2P|ij8_nE?=Z^Q4 zkA%`855Lahrb2cSINmD4+B8$CbYe(eL@Y1J^a~ zFT8J6`5*OSop7hvk>A(2Kib#zMYKH7E!AI#h#{y6%l<-6y9@|AoCSpJ89 z!EZj=>@o5`o}yVY~)#9 z&$^m*LY3$Co4x;YoN?d}(d66mFs_Z94|`ticU;f=-O^`XfE}*l2FbS^(ebwYqxsmb zj2E=8{i*x;5|_F1zU=3Ymj96t91uVDJ20&O;eS#5oHQB^9mPL+9(muH|1sV>-l?2t zfAjBcr0pku|BCsP={#ri_qMrzG4JKPD9;Jf>4)i;(HyV#`R)C#=k=WL`h5Og2;&XM z8Mpm?j&}r*d-($a|ACVq4{WshR zzan4La6i&;z*Y6zoR|CDl_SSfUj2OL`}E8EZO>QclW;xn`{Df0cJ6pRjvM8Fj3>PJ%l_Kyd%LAwA1BVQDrf2MTxUL2I3a#YoFMnJT%;)%^_bP;@)Y9dM+==8E2}kFXP(SF117K zGTR~cP{;etJW#)|{p3T96E!{aQ}V-ps`HN2Tl=w3*yHdB_}RR#8g9YwdGDg%w_v{h z^`7s@wX}QMrJRp-czEB~9-iO!uzkw;u&?{YxgHJ!m;C4FZ#VDY`SWHw%5w^Pr9aso z`XTql&a1*vXdk!=?VGgqv^|qw`epi|TnWCSzs&Kw@JQMrN`JRqil<)@$Vh32RPq#+Blw2 zFUOHQ&rvy66}vKCVrS+RrsZ$gPd;NiFdy;#dR6yx(tgBuFrLDfs`z#6f_nc^@mtbS z_@BQ=u_NVxSHks1P5CG{Trx_1nD^kX)WiIv@JTq`S4aP7T%h}>;efs$PtG`{MU`IzTP+yzw@3o-YZBvjcNFwJdAwu z9S^t}{E>AY<%Nru1A3glFR*^2zVKS>|K%}{kIMgu=X3r3(_Q6&^c(jH^Suh!0jeC3 zelf=nvJaGeRQ*ROj zLz?<~Jn#2cdwf10JKUddy(kCIrB(6!Io{Fw%R}X*V|;@CBM-!$V;Xys=05n3YQH3% zeoJ|6?|FZDcpbm5-0$&pJgR8_#I!? z8$aKFpZOo_Y4{)7_&?|6_xz9N<(uukQO}3}kx%1NJdVGGC-8gLwd?xV{&B_sybr&V zPn7YP^r+k<+*Zj}!*$o1`v1OK zyLta}T05=B$NE#RH9d}>{C>ytGT#3BXs@O%Pmia)v@7{x=ZptFj~fr@bJy_$?&mxu z-~W&Ueq%fCbJ6uMe$MkN@u}6WkLf@7{iyT@`<3f#<}0RA*I!lg&$_uBZC=NRpM{&P zya-;$I5;a@sQ2Y}%aQx3*pK^<`fjT?_I$f3$4N&iFX<}JVW0ac|H%J1Z{}L0tv}_( z9x3<8X}pf{gz?>RW#)k#mkYt`C|~vk`+W@R_tjp`QLSe=VEB?8DV)i5d+a@HI9~W2 z<WwkwuAP;pS_;6_DFt?zjL{`k9L~*pmx%Za83H(onjZp z$tdf0+G|w&=1FTx&;`_n(+fc9%O@qltz#vAzEs_-|tp8IqeUrfvYc+Q9WMZI6* z>hs(V_sjEmjQ7PZbH9f}>PP9fj(4=D{kZYX=d}4TKKOS8+e`n=-xVC^;938;^D)Ll zd0IK3>2Nl=AMthaufzw+0m}(FpYH|Je#DD7PL8|}zZ}zN{s$+M_eI0~(79aUlP!mF zi-}|GzUSv`%zEM zGrrFG3i|;mclVbvkILWe!()io<2c_Fah~;)Nx2WlQRZv#KNQ|)I()GEg*i_AAJ>H+ zVNc&r$Z^Y6?#DO`U$TA6E9de%&!aw19jCm0r*P(n*wKBg*kN3+&`y+_a$3Kx->pyg zeL7EtUoks{qZ&s^ec*pl=UwG-v^VEhEsygx_>J|leZy_m@2}!Vj7vY*{UH9u`ikqz zg^Ukl-6LO8sh|E-|1fTpb)ENLwf43>3pd+|c~B-^hdUC+(ehLX`Fi zr=i@=SLgUY=A#~m=NbQ7<@%ZbF@7AaLer?}*zi&7o^J4Av z82@t|#NLdHw4Z9Z@dNUiRlbKk>NlJ}^S}NcKMLoYm3p#X;qM?-@(brP?vM8M_wR0M zKe^(7*w=EMRX@ZY)HCsrpYHvcdTYUv?@hj@- zbN^atPk!fqp7%KagJ*MIzIQ_$ll3V7OMhe^F!@I1H*y&4_{+^sJimwoWFBTb;P1l! zoY#>L^Xv2b|2#g%|1n=)*RNUMIxalU|F{q1`|qRWe$LB%F9q-UV%#`$vm6gsC2QQ8q?-$-T zYT`*}f0F;P`EX5Q_*oculh-3K-Q znP0N*u^i=pmK*+nz50C%?Fa|d|KsP;_&0tM-iNOJH~i_$m&o_|*1jL6$)|B^@zYiH z+xDxm{PYX_&5%?>~B5~;P~1FWqoh@&8FrXUGJB4#;>O}b~N9d-}?IdYTu+| zpKCk6JnZ~(kGEz#`_)nYUmflDt8M;59AK~4j-=`T@IF=ytB(AS-<==6+xsc&ZtW=l z9!v9;!d9;eb3JIi57*i2kj@0sQ^U{XB1u-wAJeOua5#DRF(| z@BGQ%)6e+b=P1YJfKlxG@m62#3m+i8@;`p}{81bKmvW%C(;N@C@+{N%vEzh_pSZ4mmE+2 z8vE8hbNk3Y$+z~3-L80G?1X)^SK|sP_sju#dZ&JJQpUqG|Fa((r}J{>6!b^mznAYM zhp+m6HTLP$uCZ_1fpTc)QRRMqAAxe&9##Dk{%Sm(_CD9kdXDwyezuS8fqiV3k(q9#@X&`p|k(Z+Rg3!JW>^_56JX4#@bcQa;kr99PNr<(41U@jg53 ztWvI*+kL8XzoxB6;{J?J^*hnT1rl$}bAx^{zNb)r#(N$89`zb83m4?M@%0|(3V$Qs z)$eNX_h;VI3D;8PfXoZ!f$qm={E_43J)Mc){cPuXtUt^3$dCNDVs81s^HtZW;d_*q zxJTc22(Q-OeSf2In%ILlP5s^ZGV@^9#qc}U+dtW#)8T*5x3ud*d0)66+>PT^xFKmZ z@qffy`S)Mq$hbf1K3U=b*%#|NR4&JQ-ZbBlpr5MGj_;2=-}W1GJRB!nr<_dQN4y`L zg!#X`ByoS{&wSqeh~IZT)XHmoKOAWfZ9#JD@V0HrpcG|%fqjt zqrdRG?S+5ky@YZQ)=Sz;{~$m7hx?DpamHopgC-q*!}#Lya6P^Q;XJU4zd5ecuQ@+T zKKkvoa=(;wtUuS`cgC}ke>k7->*KknojuO@YCFrtOgo;_p5%jnFs?UkzFbHC>dJ#> z|De2_S3l_Z!#V-`&I;c%ewB3${Mhxx%n7M4$7wgO&+p-cDt6`m(Uw~~Xs6L`u1|QL zW8bV#XfN$P>&gQiM=TfTbKmGw?W*4x7f8KGQ@+QwJdybYoG;3CCnpB(X5pFHf_l-InwSqt z_m6VE<-60lo}*oOt`QfJ{OpH~>k0pp6T@@y*Vl)iym|1KU+l-<9{!@TUcevZ$*wo# zfyM#S->&(e@2R9;>8JhsgZ;D5JNu3Nk9mUgZ+Un)AmfPh+448ij9Vz<)|g(;hePsv zlSsg^-lO6e>eAeG9J%)l+WYF5yJmTGY(jv+%IaJ6yuoo zk^8Y;vK}M<(=X5bkNRald-m}*4lVsQnz+C8?^%Bz{%5(!AOGcfrP{AZ(+}72V(qt% z(`OE7f2QB!5Awfg_@C;1(*M`{C7tqon4b4TYe(WCtzWfvpuXjQo;Tb1G5%*h<$+1# z*YHBs{`Y3@ht&Tn{!ji#KhJkSKHlxf`dE9<{BPxbNkLkmUH9+>v}zD{5SlM^K%@#kJoRfZSxfJjkX-u zJd5WS>ul9_rGEHJxtINiaf5bc-KhE;b$uN^xV{(9_$Zr*M!mH2onn`j4>FEv zFZW;bT%7HicsJwpv?J~0{@hvNAH0t)s$Z3t_&kOS!T+?g@6)6|SieziH~fkF*iX_P za6SE~s{eRCzprWIt(u?ZGfn%+znb=U%1M8zUr_$=LCcFjQvQ4|yz1Y}_`8Aio0aD{ z$C(G9Np~LLxWf1G@C)ojf4o!5!MsG3L&5XlQLO8qQvN=`dFaXkoA&pP8><~-w^ikR zjl;7%*qd_Ej>JV+PsdT#Cmx5_h4nk z-%pSAwF>{^cle(=^8mOD^B~^u=lWBH8#%w?J0kRtd}qS%4~PE|@5j82?-vv2#{1}; z_lNt1*JR&oj)ymf`>EKO`^`!_X1_9Ai4#ViXFEI3<2d6sTrJlnKlz-zGuONB9`ENo zDDhn3kt*Yj^;5add8@pNafvjXg!4#i$M81yMs)WjV_4^z4(IFNx98*Kf83Au9W~{#o!h>Y zgZlA%G<*+x5;uY}FT{R{=i|Flv=7fa+ew|<9ebv|RqDg}lyCG0+BxkVwLQa!jrX&i z?f3kS|8YLNepdGZvtH#m*O_nl-l~t6pK@!DnFCS}{b^RlVeP46Kl^9)DarqMzSu8k z<$fHmwjb+Ha%JkZrmy`cepEl*b) z=lJZ1xBBEk-3L5!9Orl0=X+M3qi;6O6ZQOG9_cmyFWfJh^{W0x93cL{I{sSi$KyU* z@B0}4<4JPO0odn=ox9&L=Y@aRPsiUqKkNT%g(L7>pdQZm9nY@PjE5`lThrwl+>iCb zsMqx)->Z6iJ@qsn?To*`JM5<_?eG}?W4-vxy`A{(3;Ey&_}}P194C&{dC|)M;KV$K zqsISzYv&L6KO6$}`4FDn@lb!y-vQ--jQjM5YTmm!$I;S1=||y&QN~;6_vLz|N6t5< z*YoLr=4*T)UzU@xBc1mXn5irugG(Q->cz%xqsrSRNBXJCCc}2 zxR2k#!EfUK_yzqVe(resV)GOID;nMx%|6mIU((+_{``nXyVvAX^}gX=(UhZciJq5! zm-4ISo%<3ZyAv0C02>i%EW#Xf)DALDDEulO0y+g0sPnLnxJf3yE4 z{x7=nKc3s;`jzp={&UTTrLZVJ;PR`}`4zR1| z$*ZtK;smRdkL#)Dx^H&mecs1%jPYI`x18ZlGnad+eJQ{7_Bx((rs1JJpWz$yo7ltO zW2as(A8K48^~avIm-&1+|FfT!|LG5=;j2mOFQ(;=+B0??)qT2hK(8s z`{iTyFDJ(y_Is4^qW-t?J@^H7tnxlVIbZY~w`P9fft1(!X@BA}z5m!Al#evy1{(gy zeAn~*`x^5J(oyEs$Q9S*Wa)C-X@mugf?KJBcFUxh=AJ2O=X@_t()cV}T z?R6iq_4#@;2jdav!v(pX^*DTw=au{RP2+ccZ=d&(Tk^eVI3(|t*8ZT&K$cc^{zbXyOEEhv=Uj*Z;ds!xyRF z_xIy)zQ&okFZF+J<$inYE0zb+FY~@R-$O_IAM?rQ`}ao}mH&L7XUhGs+sOaCpU+i! z4fA!@Z+VYkHSqyg{BOHpYY%xJnm9j>%UhV|J8vBKtMZ(Hx7kirxhv~D`UCN7_z(FS zhvRX1f%^yPC$2N$d*lcAi&~DvA@;cUx4tv~t6jrm!rvO7=eiD#WBKoucGqvDNpm)k8)p?by1HqzH+|te$LZ94|{W-c0ViYBm5)^{~!(jV4g`F=&0~2=bzEU zL%D8bJ!X4k|83s?C$FL0u7~FL0QUIIWgeTaInVWc+THc)tgJ&R�Ea>s;%HKRW&y zx0m=l-s2bk=Qv|~e{*X$?KUd+Azd9g;OZZo7fz?*Z?qT3Rrzk(n|#OP^h?rJuVX)- zBYgdPIUfE)zN41=B|f#kJ3fY!-0{CZIr!hFJNKiW?(2NN@56)x z$Y~nS_gDLK^vy%uU*i9wD;NC5=8wz^S#ORS?ib~KfUH;6b#vC$jsXP&Ue|B*JIwfyCQIeKzW4WMd?o%d z^@z^pPyO&~MvUaQ#u+94CvksKxL^1mTK;Eyln3L#i35Cp_|>NmDnFdR2h2Db?iZ!M zb9@~a?T2~ZcV1wB2?w12p3`wW<9y@sxo-WP=Mu;7wd1?jn{L1L{$sxKz;MQJ!D#mV zM^~OG|K~a9IyLdYc@Kc!p=X@(KJpXBG1K7~(Z~3oeiOfoAFlm194-nkqQ8t>iS++C z{Bq_{&kr7T*1tK0bpY`Ov)HizOe~tt6PsRat=6`vP zvM#b8&HRtw^~;&7aX!cExB7A7{=)x~X1!;Bn0cSv!f`0;_gTX;;1R4dEDzUl|4}J_ z>Jg><_WSqS^B#Mlt~<~B`8fV=JAYK{;`)(wGwa5)df)Wlmdo}jhq0Ym56YG`%b~EV{LeJ!>*x3* zelPcf_v!EDfcc&LY5$~A`JwM`^#1;?|BQY?`Qd)_2loGx9{)Z-`!bJ+^1I^)=jZQh zRnFu0YW*zZ7Ixxy)pECg%eOKPu#a!%fJsNWzVUw$^2hGieDC^r z&Zi!%gJxwOA;;i8#MAgaRQ50WeOl@TSCMbBzTrN7Pm<#!95CZt>;iwI{3?FM`po-t zU(@)@%k94S3-8(2Psg}H^KIN~;$N``9DP-P=Qx}^>i%KAr@{H(9Qd5|4zCLrgcovs zRr~Qf@i=ftxN?=>zrUqb-xI+8bH)u+yOr~W|50AJXVi9W{H z<+jTDi|zT$+Y0{U{+xcfb3jJ@Ki}8Q&p(p)J)4w#f4W^yd4IC!2lsJ4ll6Nz5SsWO zmGwBBU{v^$>vWa(3^Ffce=_s??hEF9Zai<`fb_e3C#2sCX8v!y;CP+f&waR?8}91{ z?8~}XJ3AkQ4`shH?aO{qe|J3w@8fv5UwGi>+i~+_zcZXK-0$yqKZY;ZKHP_XC=Y}e z*iPI>4&nO;%Okf6ZGK=n@r1cAN<95ee))IX zaX6pz)IUAae2-DPRJDuoM1H4{a*$@7Q}z9j<_G8Tx~lo&U#zcGxex6Y{v%&*J@p^= z7mxhYoqz(VpxBrvBsKZ*6CP z|K^^5I8hY4S*|(W4}NrRZ};!gp7@Xb^3z3EeipybzTtkf6W8;6vmH^|hxUu#@Vosy z9PrHl^Pn+X;k5}VD6X(}A}3t=9?y0C zL*;kRcb_$X&zi4?OK2~7ME02{es_LG-$W z@@n7Dc6+j)!Ss7N-o6CCcBTYk5sy@jm(;{10Wnu;o~_ z_wo0;a&=SAD^X3od+iSt&?`SeHgnU!(Z z^+Mtg*Z9EBdp$34d^u0f7yifnoG*tH%KfmX$3Kk!u`Z^({3RAU^2Drv&3?(a!H6Dh z|MhryRr+~U{&ePicgJ&G@{6wVfbuf=P z&u96cZ+>lmmv28icsEKpo*(05w4Ba3*_TJW>>p1@E=YZ`J4$&*&EEr@-*rE*{qt%5 zXa6iOvwy(9Tvs>k^Qivo{E9Su$928jqWgT44%d)#WSxGej8Cke%KhjEq~+u37pUv- zcZ-heb?jCC$GVt!r(EZ{o%(xx<^=LX_@Di+afC^0AN#2s%l4uCv=fRy-Yflj2xepUQXWD(dl#BDO)OHL943E6xf3}b3&s>)G zcHtM%@S2Q&#P{eo>dX&)uF0vetLZBCd5QxzZj$vl_Ah^RK9Kav1;atB+>d>^s+

p3jxB@4XYkB_63t4ASPTo(a|HxVBpQL9yCCzsz zSpQjH?b7&Ox!8y71C}5B!^RijV~!skXYTo*ydfNr`pE&!5C8G+Bss31X^+tlI^Hr5 zi@m6i{13loeZu#HnRm%CP_fZf0I>)g$9D?^9!uxXHwvYU) z^}x==v8reO=l#z7@8xdSf7$uvXM4OIb}9F>9_4{>IO6rVj`%%)FZZ*Z!u^Qz!|%S@ zmFw`2FOKvNACx$0*41!+*46nwv-RLRH1K!cXF1n1T;KMkeXuY3a=S0wFG@SY@4^AO z4;+yD8VC4dd+#1;IHAYkeEcr&d%i36F^-V$-8%0Zc@E3!Dt zA>sh#e5|Y4Un~#F`vGUo_dzHR^ZxL{DD!LA1E~J$x+(Er?nBOgW( z-pwz=`KTX$PCOfa1E0dbn|`^K3qIlRazfVO9*+_yiC_HBy}gKoqutOKTYhjAZj6$@ z+=F$6?G!H3_$lXQ@Vo8w&7Vxe^{^9M$8uNYNx$BX)89}yjq}zoHYKA`wWsI7`xpn{ zgB+jvAN6vc{+(NOzWl{@ef)=V%YRh)2mVI+^~=_ub_xHB&b*oH;m=XdhqoDzNSx)H zEj|r@DgWy_()nulmpKp1x-#ob-`~c3V;<-D`-gw8U>qcFnfuUwv&#Ljm%L_vZzAhE zc~iKW{DyHEdoa$>@8FNIVbv>cH8cwOxI*=B#rh1$NhN8$n-_m_P1zr^|3KgM#7 z<>mgIuV0^)`#LVj^T;RujfVGC;e4dS`&NCL|2c2VdOn)bVZXB;5&XX6OvfA}eWL4OGMi&CEY@yh?k=RM~+e)All zUy!!HMB9JTk5I`ciT@i_|KWM1KgZA1_@jTn>ptL_clA3H>E}`Y4nTjZlJE0_ zXPq@%D%VHP@o$V^FAjdjep$<(a)rx%h~n3rcc+Yl$tN5#<5>7z)%sfA^FC+mbFR0X zFUMbQ@wM8YzpHTnKU9-nbmWTEn{uJlLv@_Ro^Ubem3RD)_lfFfK7SfdZ-0by@w>`6 zVE_0qWxj)d^Zc@3jO$kO^?2h7?GJDV%FlIC`n?>aN_-y2XXW|mI{Y#IC$FIY!!de3 z>qF}2`{(5XV;o@4_rBPN`)eoi8Ou{XDMx|l**;g?kM`^D_KWpA){*pg*4gaffdgJHo4o3Z|5>i`zob>}OGL`ZAF;FPXt^ZilhbnD+HOhDIj$f1T$exb+(&N=r9S5ZUQIGUT>~Fiy z?T($zuk}v-XYKtc_c|V|Y5c?Ib~W6ocF-QK-^Ot!{uHHur2KxTgMMy%l>a9!&w)!& zf7YMytEO#tj`O_!-y0v`ySBvH!GX+=zYlnwyp1&Ldbk?OI@GwaaKKsNnA|6Ju-&b% z_H%xaI2PBp%)dIX!GD=|$;Eh28$87CsZwtD-=}z&?EDywfre|fo?z{t)Q@ehHulPPe)=j)8 z(RoVV8%I2%^(hCWUL*h0&S&1Izi^!P$Bx9QvW}%+Q9srG86F7#gD1oNGY^XVm+Q@qVH(^^m0gK{ysAM+O4FY0~aJoLL!sUPj{cawde zApVl?fMnem&G%w;fmYS2<7OzbudC)E`&g7w(t1J~*B2 z53e(BGfF=Cf$hzG;|D7C!0xO+(VQQZ6OYHQ`5)z`9jJ%)ow=BP%Kbg>PUYn0lXe|7 z+%Mb z>uqNhPDeVtj&{&bqTzxnc65A;j^kbPNq*z~v@3t7;5^&7 ze_3Bfv!0J;9iMf2)c)Unzu1>`@2V@mBF#MYF(se*IyfHng7ZbW-_>z{w;YM%yZ^pN zIOgNZ`~SV)`8@BJ-_P~ucerCzJI(bQ;~CA*zl(L>Z_dXbm;s>jKkb?Kfze*rH{34@ zKj3)w0i(nTs&5y4f1LO6mXG}@>i%NBPi?>Axq<)cr|CECU-lE@w;9ju7fgf1q66H~g>tgZ_?R%nIMkdY<3k z9>1d;r~X<0Q;+aG;t8?SV|sVK$K_S>K*~k^@Q14HHl8>C?)j`6@h`>=ewSC}J$dpu z+7muQyU1z6`>Gxvc^&l*$Kkl;fk%1V`j6LPf77$}{_sxg&$u?m_t9?5w?>U0+5Y<9 z+`hK6?QZ*GKkeD``Q33;9m|vQYrp5)dD!#Cg~r~sGySV}(T_~S$Mhfg4SesMmJ9hi zT#fT)m9w$F3vc6h+cD1x>dSL%w9BKs&70HLV}?zU1S0VmqC=pY7Oj!umI@ zT}Z=ytMVRr8obJJWaNMFH`bT(EcqYv2G{dZ`5)ZRb$`#3M|j?O|C;O9@$Z{k@%H%) z{>}QsxFN~~C;Q(=IXEuYl=s02>3>n;21&~`sZZl3$*2Bkyp-j4Uo(E3{s9M*d&?2a z|K4w-8C(zk2j|01@WAjs`6OHrZkOZtJWrm(@5DXA`KW*2)2Cg_{pe3u{11Qpa=V}E z-&el7aX)6;-`mvshX2d`h`-jaxi}wLC zp2%0A(0QssH#m$~uAdOVsv-_wk(Kddgds1DbY!F5?0AR2|P~ z2gWtEe9!gLmpgC6&*X3LJn9Y4<2u$?QSv42c=5NJ5^p%`7e_jAfZ>AXC*RYavw|T zf37Eu_v`niyWiY(oWH~WoWBvDO+ClI&p5t&zQ5C6`f1j&(YbuIlm1rTXZ?-Sv;FkT zu9HpMKWDzT@;~f0o)=CS{)eYtl&PDnurG32a{ozj^AMGG7^5lz)>k*${G8NI+l}i zbN;I1`TWlFchuOiT05@(W+{L}kbY)6&i)O*bKH*hJ%EnSc@JQ8=6m!T$LVM|ol5^RpQ`tpxjg5kznP!shXY2( z`?)R&=QGZi@zU#4j+CqFb*@*)mvofze9qT+80NVipLqu}K##)@^dJAuKl+vaM=^?$a-t)VX-H04M%RXAO7w^JR;*?IIYKNhw$n0Ve4tRDSz$exCn3I?xW;~tKj5E~ttgbiVll!8|8!xQvdOL!;G7Je?tz4 zV%I9=Cx7kZ^`yxs-<{5PX5fB|r+#lnwZ7^9s+=3U(T@Hd!1!P6@oFm{JXd8r{NcX7 zXFsfb=+8H$-~8pSeE);>yzziM&x!MkQXcmCR?Gc0x6sGrSET4Rm@y_eBU)k@DaGl?c<^6H`s~n2; zlm40gr{z($@BH38+ueA-_yc|-ABJ}u{~7)_#`!t!J;nbVA9;>AFJnCO`B$Yr#Cy|z zBj<5Eq1^Zz3O927ow!c@kM*VPJ@Q-fHO>9~ee9q7KJxme@w?bj|9+gWa=ztS<07Uvw$LBbst{2w(OaO8dd z{{A>m{>Oa8`pN-mKhouZ;b@IdA|J|uQa=6cT5}%d_5Pz@tbWooenP&{a=$yCO1}1c z$`7Zu9-kcklKosL{@8uL+?90W{-_`6>J|TUKQM7$&ikXT|6gtEP3ON^uQM*t!dZ{| zyf||+AvnET&zJnJ?8{#bmU#mo`#$~M^$Oz|>Bsn=yg1yr@wfUV zaiaQf#*JwF#{LbL(|=cv2X~?bRnJ>F*?L{l*XQ+pdEs!xua19jNcnz$o%73mqL#1a zu$ccv5&=INr|=yH>p){EqheaQ>I;Y^U(V+|T{^e#e{fk#<1K|4iF2 z<)Dn48K0duH2#nA6b`_Aop>Gnb>)ArH^2WcAN|*l{@daID+j#df6k}Q>qG2u%@cCG zTyI>bQ?Kjv%0IBT{R?i#e0Ai2-{>EfLq1BsiT$dv>#D3fvoD)^*uH0Vz3;vv z>X-C*{up29I&tQI#!blsX|I|8g>Oa2`uV&V?PGiU+=*T1=SlM6KG-2~yKSGfzos3d zuJYD zI3DBUwaU5JrwFe)pC|VtUpSyjTuJr^yKa}S!TDU@%YU1e^HFbq_kDcuPy7e_M5$lx z<#;}>@2rR86Xnq_tJb@A;C>_jOS!E#_l2)uKikv%w)vRUNW8zd&%4Uo+5t8e0S!5_H*82L%%2P5AIn0_iCFJ5Xbjsn+5z} zQ}!#v|7_=9Z)v{M93_ADb30#@|H0GbfO5XXC9Ycj=lcuchWHtL4uw0)w`NX7dungF z8C*}!fyzDI-=26>I55ZYC%GVg!*z~tGwq-NW7>CCxUBsF#XkOS9H@R}eeqB15c{nvC(8T# zeqa7KJ})*m+xi>!8Wp=_eY~!Jvkq37#mfJ(E)NH&#;$TTxM6sl{e6xH4ClL3+6}uz znQv&Ps&=~OfwU+7M!CmwP=2qg@;mu+KJD9djyn!{Jlt@OAH@#-u5usJl!N=RPuly= z{EvBGI8WBA;dEIyMzc;uSr^Ru_DClVu-_4GzOF~$KJ;w9KdgE@9KrFk>&@_ns2r6X^ND)ZQ5}!`BrEC=W*IE`o`k<;-|-)h|52arFHXL> zPjroQ&N!NQzi2s}cFwq3?&tCQwEchmJ^5t3PTXJ8y|3+V{2%?7*5Z3V9;e;t?@{Lw z?*HXHpM!6Y@wEGX?U$rozb9?KAb!sLqt373f*cQjk#jkp;<&s9zTkQ8s|at1a-RMk z4W~FO`6T~4wLIaO@)vpD8t0ev7$2zpTn~@@&~dU{Fz2nB^F|$cpy$&+X{Yp4*8lLO zYWs1{Q$3G$CFiH#m;afsTnf%bIarT!eC04#>G^u!KPTVAe~j01+=07=>$y(OdH4L! z@h#jh8lIECcZ~cBe~f?89{Ss;Jg;aMI5x*gkA4~dM9WR>hqZs~o#Rpbhx^-}T#r4m zKYR%LW7i&kD$VuOJIeZP^sBa$ zb`7r>xgPhm{YU<1zaNj!{oCg+^*3&8R@<%oiuPgsD`!f4{rWrmxXdR?dCM2^FY~EV zPLIPoxesc;4;Ook``Lbum!BLQgY#{#s+?@icib1u`n~+mb$$6Ce!$-cUFT~z(!??G zeq@j5`r6C-*-x0~XpeI_^k>UM|4BSx)P26)_bcb*esDVb1^zYqbNN>|Sot62B|dId z??)UU@Bb_RGp6X^BoX*fINl$ zna;C~vx2wqJmJy^dxKj?GSc|zu8tIqK%)WdwtFX?FVA5}Y- zGiqnK!N|X`JAXHG9J!A7TR9-@sC`uCNsa^ZKjMIFw{W$#C-;#*{;vGb`G@6|1Kz#g z5W8?*xL?xM@Dtnl4fj&R-=gw|EB@#Gw9Clpe&wW!*T{5_oO<$(16aopxP;5cwr$D_yNjp;w*IKq8Q%k}7gq*>Qg9fzCd z_l`pzCv81RmjgB~ka}<&Z^PWzdZ_Z0TKR@o5{Bz$b ze$}`?>`0ow$Dr7O{v2i8AkBEF(jVV#{y;1Gy)2$DUB`0V?}5O3@LyEFojIV#&8Pf@ zw0}pki*yE;C~{m94X zz4IRGGhfH}Wq#3eJGmeBfosJt)p>x`y?JvE@=Of|1pn*kFDz8BjjS`g1+zXA2%++`w@)? zbRRk8C%zB6MCESu8}I9Vh&R+ORmN@J!yILNlpVUCnV16#s0hY&3Uut`l#_&aw4A6a6U$F_@Di}>wVIVOJLnh`#z@fzs(F= zzS!}s#AWGE{4TelK5#Yf$8qk1-SLa6$JvjI-@)0i>#TA<>PKAP>z(6qo##^?&PU7t z?Dx)hxlVg>Upa4-CE`|B^OhDWW+K40rM^S`_JKl}`P%ZshAd`6C?f5ad7z3nz?!>2p7t@BjL~zj8nMA9nLO6ZLt+bH{u>g#X!o_&v|1_#N|Y(oy{( zaev{!`W5Yq9jQkZJ7BLU{W;%*HqH<~(0(~C`b0~4Q-H%4Sv2T>;GIm9MzUZGm z$2$%t?Q`7o@o&@Gam?4}vBxQI?uT+8>>MQ@%Ny>6*1oScds08%3u`^+{k|*zV}6N! zqVm7A6Zg$`my_QW|FeAhpXV8eXa8=zG3Dg?sQ2MI?rV8-pX4+9H}>(o#FeHz+4tM} zI&O9UZ`QTzI{L5o@xANUtS^68{+GCyXySBo->Bos$j7KZ`(dMuH{Bl`p4WA$>mZ*a zJ#XE&=(|ULS)s`_ zx=()XN9iB-W4;UGb-p(QE@)c+JI4j)csO4bzanl>)$dkr*zae=kK^ajwLhf4gmaC` zIFsMk>yl2s(cCwh{!#9xox|nA>GGb1pY8T}_0iAvc6>Rg*M;-l>6&lS+@JnQKOU8G z+HY0rMcR4hn|*vCeb4{!H{<_!e(LvG$F6aJGyjvb$OFp#%+LNTpJ5y^ZT!*7|6F&= z8%9pSbK7}Bg{ z_s?m+ks~^uTK{q>>?MC3weg44lXi1`IC7{QzgE}X{qBkLx^tR!uj_B`-*ndLmfPcF zydUE-aer5O6-UTRbS?poE>4)Kb{OWNzbf1Wq~{fYc7j~vf^jIXv{1Bbf5KK(K(=ks|?xp*F1 zzWMpr=in6wbiPgf<$_5YZ$WuDUOUnra?P$=vVMvE!sm#Cv!9gT;TMdP_M58qB27D? znP+4kM0@!67JkRis&F;p|KM`&66Ke-D3ReKj9Xy8I75z&uG_*L}$P z9reWzQ}60}zT<@a4}XFWa{rP4;h#yP#>L42Grn*fPADI%T7SkL$|L6+zki&5vZ~kF z?%0L)rhOUDzj#DF5C7wQb@jI~{?z-leRzK%&z&gsA?@N?gxLs&$5q|{lSR~r2Oy) z>H~j(7ZL{;<@pGggD1lKw0D)?*~h6mZ)Sd+^W~7P6J7rr_m_Mqe>mcw?(6!Ie;DUS z{FVJ)4s+&xau~jsYdxqp@p3(G`@5bwbHDJmnbXPbvR^hzKl41)alXppo z_s9A1Q@Ju}_XCp;90Lspr2R>&@(=8|rn|0^7dr2nzb{QYFfSlZ(fL94m8sap-&N+N zp65K6=M?#7{6;CqtUhnTeY(HfB(437OX4``oY#ExGx&k)`0hU*{g2;m?~GH4&$Arl zJC=**g6&iPpUA6(bF zxjy-2eVlc4H05BuNq$kE10&CKe$8>#IafMz!mI1&-+8Y5A^gwl<#{XjOZtlcaowwj zdZxa2O24PvtHy58*t6<=vQIJkIRESW%G!S3KmIW)?NI*b{0uI_apU~n@5(&Z=g+4P ziXSpw;^)zE+_Zno(HJ)zm*#k6o)?_Q^TP9I{zpIYxEjtEW!&<5|E`cU%Kb8)N9p$* zk5XRC6-_y>mFLIE|LC`UE;*i)W_(4NFGanN{EvAVX~qr5<;*+7F``+AsjkBu2jG6R zQ`GrxIAHbx_xmwC2Uw}tud4BX{d44hp09tx{jg`g+tK#~%F*C_tPhA2#E;7TlGg85 z{?~NImvFgg`-6U*{_>PMAL{!GEPvt{dEcM?EAfY8zo5Uaz}C=0EG>{EzxNuT*I_(x~NwN6k@~0l@PQ(7hJ8DP%u3)=F%l|yixX`%i@PFnF+LL}wxw-Du z{`@!pzu$NY-?#010`&v=ocyo*fSC{I7jPsvSUI3^fbb^n!#-gC?&$Y~iR*yZU`KcW z`9wWVy@*$+YA^g8JEh*$lykI8{2rC>aUaHI{2}phD(#wm;wU^Zae<5*oy#t0#OSD%T4agaeNJFX`VL`8aQc<6vL-O%%Js1xbes%JJY6 zu8X7Dr)wM^?PPxLcZ3_co>!^IypBG{^U1C9-ZeN3elPEo``K@Lo_^(g67HtIsPH-K zMSD;l+vU5vQXkS$#xK(JPvY}v@2cfsUYmVX_@VPsmHK%f_#XE&|0wGrj(eW{`d3H4 zr<~;LI*t0{=kh1o$N9ayFW>Lwch_-pzWIFbubn)PdUAfaUgG{5mzsFO@I<*^-WQnb ztMmH-u^;{sWjrH|@_f&FE98d=8@;Z;0*ONS#IG*)k)OD=mrTz-X z!M<>w`S_Xt`MZ8+JCNV%Z?@0On;D1XJ5~K%F2wIiTdu^78IM9eonJ<~zs~XIn*U*M zo|`^bw7<`D`5)t(^S=BYP0cupnt$U9Nt55Ga538S}Zj^3?fuhyBYce1Ws*Sjk}%KF^#u;0RlKQHSY$HLE*T^gQM_wXAs|88W1swwxWCIo~Ljv-+sji=3V@+eA1GhgH{=RJD+^VQ*Jw3pEJ z>8q!m^IovmwcpoqfL)LG3%`{A8+)X^{>wYqd}@A$<+DGc--CNSeaEzRc7F*Ush)c7 z5jM|yUUEh31-@^``Tvq~toO*2(0+F$i~{eH0gEP6&C*+X%Jcf4zQuU*pdu*oyH%71Uy)IM&hdap zbN&pfm&Vcd>F=kjO9HNu0BoXO4o@*E-SGxf4w zE5GUTS!Zq6=X&e>HlO<3hj@QHir6|SS`N8(9@rP<`&l;Q8$T6}3P84Su-zKjl_0 zukD$3h;$`^f9$957d%hKpYh%Z z`e8r0BI}2GdyVSZcun-D{{Q*O^L;teKlM8NpS&Oc^N`os`9I>S*w^q~Kd!$&&i5<7 z2M^+VqQqsf`;hk|4ksSSeLK9+H;4D6d_3U0Lm$M!eK_QTAM!n4-wTH4ktZwuZ}>m+ zd;iz{qVZesN1n&x1JC>){|`QzJ@)+~`)J3>dUpPg`l_FD@amio@gJUx=et9mN8nQ& z?|IMJ`X}zs{tquGFNeNp&wXTZdGdVlDvr-R@5i~t>%a3r`M>x%?Z@|ZfBSL1f=?da zPkG(Xt^6bYUO6}~P=Ea2An#*2--;`2+|>i)%6WDD|1<3whevk$E=vlsx_T?XT z{%?4^%K2V!d|%l20*5#BzckeAIL^3Y7w8X+cLDXI>;Iq`ubuxpr+Hr)e~cU;dRvio z!t3|vL-s4mF{r%7Wnq8%)8YF{yZ*`h$^YShw6iP5531+l)wFZ^Z@YuYMSnu|Gym75 zU)YcP=J}qM{&VN+ira%nW4+{kde58jeV#w@v+f7(`9I`wUGBSp`#S%M|6?4GA6^Z_ z@7u2(vj^tC<09V|ZwAkYp5pzk==;Bv_x|d)-Kn?y(eJtZwSC9kaZ)aLQ__R+kBzJT z4!=z~zJFo)zFU}`eeamZ=;gZ~v2$PNz;Hd!a!!Cx;(Q5jB)ZS-JR5$V|6_dKJ^dDl zznJ&!^ds+{eq?wy{kQ2kmv%ngk@}{*`~6AVzUxK*(I`$2qw;(qa5VdI{I@pnvgj={+o-=x?8T{mt<0!9Um^d4{*o_)hph^%*8tJP646 z$oqZsSXbZySy!+d`ptPJWW3M*k@JFn$MZV#*z`wIe#z%D^L*wS|M$vYo3H<7 ze%bDs|BJtKe&=WKWBQq$|Lb~){Q0Ahc~8FcTpn=vzrM>b$bDS*e&dT-&=OpaS{qG>>Ve-)zl7+*gYd_9A=8@&xPYe$jALw^S z;M<%Zq4qyKp>{U$e%c>t_9y*+cm6YyT{e%x=2^U7SU&qC`9J$P`KGHkdE^7XI^qHC zXL7~+HDCGvE^$z2^#8u^4*zPq@O`u&&o_Mi`F_WX`Wd$~A_w`%88UA5r+$Y%r}*aK ze<{!S-Sd9syPjyz@__4n#$Mz7M7(74`!x^fJoGyCnHKR6`h!9F2I3+-FFFt6`v$3J z^)II9`Qdtf$|VPg{{rp5XdEB@t$E@1GGG6LGPd*E5 zT*E8>hy3~v{h<9D9uTkJ{-gbc&rfJS-fu;C0PgqwTloTcL3t*4qT%7bEA`Wcg z0F9SZ|GpOt4 z56&OVH_mDB6`t38uNS^|ctGkQ&3M8OhO|q6MR^%{HhDnoC|>Um9_L=pDU1vG;GTwu zgTIqcEH00D3i-Z}_J8NNU%7?{Jk0Zu&;4t0e({jSA@2MjeokHxY@BVMei9EF56b=! zJrCMmdh2d!z&E2jINUwohOef^(?xI4-X?tEbUAMqZR+xb8A()emWbB>a4 zF^-gaSl8kEK81{v>wf>Ep7R&`Hs*!<1Nk1-6WR&!+sZNjlR$2+qeuK5dVc?~tFMpM zQ9C2v8@uAV^N{!E9Pd{Mzr#6EJ&W+5>BIgjCwekH-;<*s@O}0d^mzd5X8a!YyY7nA zzpuyoQ|1-<*q8gYSJ;0)iYwgtKjgH%@yG7diw7EX9OwNy`nU3%_x<1bzs8Gwrg}8~ zk9^a^$60?oAE-U-`Dgxb^i8>VNBlnHguYfB-mm;uaYMxqRj&GW{*V1fJYeU(&c$K8 zPVrrxW6%6vyi<6--nlpI+*~_ha-8|H;q9>dmH%V?=YN#!w>zhbl@sw-@q8;UIQ6lU z8=ivvYg&H?FKK-vC+YagmH#`JvpxJMKf|zgm(fEPR?aq7rfcy8I|10hff4*Mt zxkWr#h~LG3gv>YniTiEZK@Ro@%Cpbk{Q8$7_3ID9ct4T#n)x0gr}KZ%`(1b90YT(O z&K2FyyMODvga1U{&duQ(XMGuHlpe)hZh z3hxK6b4K|;-s831EB|NvT;KUa$A|hEr`pM1BM14&7czeJE594!-|(wp{2$LnIG6LC z9C!uBSzeI-ypI2Kee<~|{GaoE{vX2p;`spf6b|n;d>_}#zeDVt^%*-ua_JQmh*Z&jS{@K5nUgHTJ=lm1MIJo~4 z8K1kf`S$x|Aj^U(uo z{5j>|M@w67_&@FGUeEDxqfgh1;v8LnS-;3<{aCLz4zF;=ZT9c&<5!FiM9F8yZGX^w`+?ll z55Ma;I6v?o_G8d;<5%=oq|qaYpA4C=__J_$zo{4gi~8mN1G$}`UL zROox>)2wgu)suFBUDRLW@9g&-&#hfj59isz^ga3V;L1n2Z=Wt79U?#Z@+{bk zaen5f#~nFeq6hX_J5tZezy8xBE{^elCj*IdgP#q{SKsIS;s4_MzI)t{ygxX+68m2M zr%bxIO6308@%$6J`uT(R`_Az{kCg|M7i7M89X>~15cGTx|HJuS9?1AJ^mOI_=m)&t zit>HDN6xv%c)*DR_@oe#K@O|j{ zM-RPoURim+_&kg{U9Ip5z5B$Nt>+=G41! zTiBcHTu43V|9@~kq+QlK^&pbJ>IHjOAM%{&$#ux{HhNsw?bc7~S@T^-8OK>qSvTnq z&m;FZddkWFVJFs8JK|cu>(20f$jAH(-KPyd>v(v6&km;F>7#LxFJs@LzT*3KT*vV` z-lOMfXZSwrji(dw@8q9(z%%bhT6>R2cb+kBM?2XTq^EB`oXd(GQ; zK>ttt)#H6z>d)`xM+dRToe!iv_`wy=Jfi)xUi#BKJp0x2e54;UFW2u65q|BBqdr^>j; zZ|Qf=ab%_AvB2b7apE(F?;AZhUhJb8N2HbigU3|QE5FKoopDM}+E4ZX%6E)jlSe)8 zJc;pR!*jqVSzi8wbo>cu+?nN_2b4D+&2qgb84o!1D8J(YPeXd*Xj?D79X8+YpVx6t zv%MWTSDC-^yXa^1fgJ01JSksXfxHO)hYum2_&(1+q**5!pUyGJVZYoLaPA;|&;OMl z@3-@S=u=)Y{fqKJzBdX#Fg#K`5#x$KvY(*-F25G~Uljgx0RK4t%KNlq{9pBocf1$+ z9KHyij&ybi55@ScC_g6;h<(Vfitc;VBm7_Wz(>IkYk$;dJFDF?U%me|+P^FBr`_A0 ze5E{QJXnYx(0{n|fY`%&US!_FgOKmO(DJ;WO`I3sUEI-nhX*`gCk9r^<6qJ{x4)d1D{v>%0+v~$G#gsLOt?;=moi%&&j)@;}6e?on84q z<#xXq4=De~cMRP(g2=V`=Sgk@1>&s2$7O@Ey)Q&HeE~^dG%qKk6aA>x{`=oXh(E59`xE7C-NLi(IY)pT>QC zrM`)`W<6i|KmD2K_|Eh6$9BTbxgxwa>mzp0xM6o7cINonKlDMG^M3jOk#9x(FM11E z$F$FQK*uwFj`8iLrE$}@3H_vz8A@5RDru+Q;3VJq_AWp;%850w0PzA!zT9^UU?&i|>O z;s4|T;{C$j`)!=#9awkJcgXmqf6j^VeXJ9lGei8Q&$rz_>v!k8?!0H8$@&zpwex)P zfzEr%mu`R0e9M2$K96~*|2Xr1lvj?P8|?lP|K)jHgon`2i0k$I!iu!3A8>xszWzl# z`-e4cyU8X0x5`idIuC{UTl~rzSA%~$$N#Nq&bje_XY_n}jqfr3Vtr3oJDTrpGJl6x zr{75IKI*Guew%I{xu5wq{Ga|IfAgOo`yco*_Cdpwt#-;h&)<9wm1n*q=svFhfy{fy z`nQQc%-@~;XKCgW^JREH`%!xOv-huh!_{xoujwcAj`#6J{3>bovFIgqUas%|GEa!B zW|WM#hF{Zuzxx8aKB(OeAL#l#{NJb2*lB*jb8tMMegZpnUf(0Up!32wF6IICosoHB zJ%hH}dw9hMTMzXPpQJwBhg`o$8xPKTUjA>&;~$wH_(lE5jyu0vIqZe|w43lw9_$La zcC7u->+zZL6W9L{dwu1(n9ZbFwcwLX>xXy#5Id6ZnRuyt{)g-K^U4FbFLU2m+?sq@ zyf6B4-5AV19M9qJMlb4tae)5|DSwU!r2gvBuI7DU%gg8Xe&@sm8Yf9w9wUVBf-hlT zy!QL7hx8^tCjaF6Is9Mu$Gg}s#)a{BT;%=a%h9LteRuYMo)72rtjnHftl#rM>rcGf z8R6yT{^U6GJgn>Sit>y+C$}Btt{wP4V9J`+JK+l}d23b$BlR@^Gj1TcD=$Ugm<3K*?Jq}PF2fquS<8{g@uW8mf?gQfm zhYy7Jd(HnDFDT!K-8ava5Br7pEv^WkO4=f5+c z_i4AJ;i+v;zL)oMN%!5qbNnCtwb%Fd(3|q?ykC4^@^Ma7&YwK?UGRSHQ$_e@)BR^A z9#CGXdTh^e;CVUrWWD=2FaG9?$c5bvUim-ff%D^x=x3cj$}!{SyjH);!@8z?o?n^w z?mOcxXMJ@2obxmOhW0?dv$v+p7nPIi@LKru5WhVBoqXf};A1IId?@<@zE41!c?R+w z0T6wUzb5@<{2%A&`nl=@c}S<1_&(M{^jJEiymnXI;EXf%BVTB}!w;(W?4x|+L(!+# zr+(X!CqS>COLIT_A?qQ&l<|u93+4aV|LG5hSHs`2PsA^PoF`Z0oJl(DTpAyA#?Gam z!_KYe^Y`$7_@Cj?KE>l9pXv{WuP1{tq7A{V4NfKi@Mh?u$d_n|?@aUmr5Bx&A6mzUMW0 zJ>~~#{GR7EdBF0iukz00{r@D$Q@-LCPVIIL{B% zm;NO=>-XS({=#qQZ~Ncfd_N1m4?nOX=i7Kd`9ja_p5Gnk&+~uSE8p3tzx-#1eF*=N zr9JpR@+WTA`E;E>=lPsv#3l{#joA(Dhfb*&E|5{#t0$!{9(DsH0ble*U_GiTnhASVZA1ZDyT;uob*TlP(w%zr9>|*7; z;KOKtZBKb-J#oCV2hQV;SBT#AQ^f(A=Dvvs-0h6Boxk zd@FC_{gxwN`ghgS`>Y@4sd_UmZI4G&F8ik**Y#Nas`ugL*7XPd^1Lo& z9l|{%|Ap|5=J!667$3=cOFQ8{9?4^z9&*A9 zT`^u}&OOQ_FEVj@^1RL~_&ZjM9beg#c7+|_x8%EwQ={K|JI3=Nr{#^uLtpWHlwWzk z$(K)4PWwsR#fQU-a6Xg&VLY)nc|>?@>bt|My<w*e7CtoEHys`?$|zKj^s~evY`d!Ti7V>L=JwRu6iJFZl7pZ?pfykBG{r zUzP`S{M4_!AO6UAzcbEz#PWvrXZU2tLH-ZE0{-u-H}ZesyJ!BO{2%9PctG^azJl>E z-VEMJeZf1yf09No;D@8UJRtw2)jz<0F>i+d!yee@9v2?`hJ2jQcj1@Rf4mv{Klu&x z`fd0>>b3lv!_V;DLEkqCPyADqKzkM-sbIhQG~=RnGnE+3SCFzyt& zN$;q?89Q#ig!(VfQEPlA>r3(#_a<)zA7_8g@h$pC^yI#0(0xGXan>!{C%^UA_1t#x z-^J;-Zl4jq?E35TI`}{88}xgG_$%Al&-?jtkp7_G9rt)mcRbVMxxSs>%RbKIUK+hwUr7DvmFFqy^-D3iK+ZR&<^Ax_q}fM=*bC=_&WXi^ z6eq&E!1XZRFZ|c$|2o&=_c)j8KSAd8#OcHf&h^Ug<@9s#ndos4KgT|qdhw91V^jaM zcdi$|UAg&AndK+_Y2IS}e+T;m-s=_r_KAP}5$Vs{C%+fI|H$k8>ZzCTPoL>Oed=%0 z>ZNkwpFhjbd%^biuOI8v*KdjkjQ=D45PJx-1NuvTyh?VIeTDK0*rWR*&%Nw_xZiUb z=MnwP^}MnAnfwj&X!Q%EJ%_PRV|@F6t~?;~-s@uJ?@&LYpJd+aFX#IJ_z~pYvF8H$ z33)#E7nJWm?)Qj%%+Gkh{CECpMf!2>KiAO*_p8UwM|{UfdBb?VmH)#(l>cq{KhC4f z(~$Fn??0Na-u)j4D;9cVCSn)Zx$D=U`>^2!n^*E+#oO^7tnJ+KX{-P8Kf)6S$Gqiw zXnQ+OVhU82QxK#6vs3hQGU}nRmqZaV{(lobuSk z{vB2HqFwKCey$&k*2)9Uy0Y?qt~1V;^E_cas($C0{1@d+$A1-9TmH_!z-KuBSH6XQ z%ENeWRzB^Ia~Nrn`RF`qUo(jRi0?x#)A}jvb$s<-@@$MNe(erzcjOu#PkHq(E8nNw zlV3U7jrW6BcU-TieEM0+ozv7$yc_*oc}eq!PqhBh|MaY9^sb!bV;5`wIzH_4(7WgQ zc&CZe!(YfFgx2eQ=eV`?zP+4&FJ5jR?|5Hu^pXBJ7orc=dEfhm33S{<`!oH-4r>75B4Wt*K_if4|JU2M<{>g|L_i#j~6ul%6QDih55bClk&B1BL0l{0`v?I=XrYgE99K{x5~l%v%TcZ&i3->^^kLn z^{n4Dr=8vpR$k;EUJLzTr|C!jk9s)IFs{5Wh}`fDgPwbov-e7O`KZ@<67N^P#*UPC z{KWX3_`mc&JfPp3laKH}5%h~Re4FuRrtjha8Hf1kl~0qOgWrP(GCq*{XczvE`>?mr zb!DH&S9^E<4-Xh0IQiOv>Gm%n`t*D>c9>ntBWF*>-SM0k`Pdi6^HG2Mzd`%~=dMBJ za6MxGhduKiStyVFk4OFR+4v3Y0Y6L}5NYD#XcvB4c}P1>%Efx3{;&KW`PfNVKjUYS zPyTQ4e}3?Q-#Oj`h7UA85O4O2BaK)1gU5O9>%;!p55d3w{d0VW_cOljzdZi;OFSCs zmH#6ikoZ66h3Bc?g#VL2VBZBV<+;xP5#t}M_ooZuKgdV_{Kxp{;Gyq9^$!2G|3_o; zd9RT2qWRbM^;=W#w8MCkFMjvXEA^=#^H=^)-V^;1|2Di|{Ga`CUkh({bm!2s@56!e zh=2bWf7A4r{1t}}^nUAuCzO|p2V}gk%a#A5J@t9zJK4W+eaCrEoByqReelcd*w>M6edR9JL`+(2Jzr`CS2ko;y zD>vx6Wm>+g_fA>Y$VV>so4zm0yk}n%Qr>-zNd2bwb9LoiFIzW}$N$@x-~HkH=Xo8z z&vxSc)ywF2>TP_(mG7m#^67Wu zWIpHr#{E3rjwj>HIp6XA!2{zJ*w?Q4>^C?ka*px7`Ts}f$N01`UQIrSI2YEP>-VPO z|BAP{JAZedh`;;rh#xH9^Evf@bF{;}u|4@e)93TC{wf}BMe9L+>O1p(@qDZ+JkO`z zZ^!>3fA1*|->1GNKb|7&`(Wsa{)O>=;g$chJ>&Gg4gaU!zCHh^KH&Y(%U?h2?ERZx zKQZ1fEUqfvFC6}l{?7OQoJYey>u1(|F81zz*nKi~-hN*^pAUuyl=s39;5WkYLuWrW z`##FMAJlKN-*%rz{vH44eA17c`M~^We17vZKEMCC@AI_zi(f%c_(%Le|0`R0KieJo z-4Dn2_1;s@N!Vx8kL!2N;rGz*|9iB9e=yyDK#I#*%4)NaD5iJKfhppykC6a*mZu%}DLWs;ywhJ84;VjGzPulH z&pAzhCf`SW>Y4K(`u1E1|EFG+zqnW5D}}G2obi3uH{V%QkLrhb%X9i%-v0Vu7I<3i z{l7oX=RB9_dZ?W2bC8$%(|>wDr+0qPdg}M+f&A;Z=vUP{^}=g}j+gz5@0hql+mR<> zJ&@-rtv}oATkCb4ljrq#U&jY|7{7a*dXlFZ`{%pY7vsk%PF&_Xonqd^qHhze-QYan?8Y$wRfyw*HE=%es3;`G?_Q7*}~N z)+xp(WF4j)>nZgReJ5}!C-QwRs_Dv!3%sxtg;C|2N1Ij!3v;#jFYS%t5AihanX;6FT ze(ceDh_|s{|M=ul;SbR#{2#n(eBksi{;%+H9pVDn zz5U*C{^DuR?;rT}F~4{ZIFzr7U%K*t^1i$eOq>k+7VMvW6X?EezQ-re22aQPu0MY6 zqxSee^x{4*{)zJF6~u1g|5&envgCUmIpCd$cY~*iKa2n3yhr_m>Rq|l_npn>dxqaR z>f`-p(f^bD*GK()N6&E|)PGI7`s3M<6a5YnFGo70pI!%*caV&o?<1~qH za~S<#yh$G~=PYpZS;gxzISi zc((rc5xzh4<$0+81k1k_hiDuh`t&{I&P(tr?r-Ki=6*`vuXw%MUFG(^J-)Db!Tr02 zv}-(M{0@3&-^DtI-p<$KeZq5mCHJp-H!fB`#kk1-i9E;09w?7rLr=CpNIUjN0tp`1lka?1A`0(f0ZuNW5Qo<^LQ<*K6LVrayQ5AHDQ^>UkJ@=iJZzowN6I8+MF8@LcYG zgYy>t(Q~Ez-@2dEAKm*e=J)Ea@^|?U=Ba*U;`#KWlV-jm&yG9qxBBbmseIB89_udq z%r$+kZ~VyBUn}42U+a(lH9pky9qruhyV2{bb7<#B?qgngzu%E!UU8jyyFc%j2Q**% z@%-0+LEb*b84EyuYIZ-deiu+bGJeT=+!yMX*5?B=Pc65m+3B+16YU53M*i$Hq&?&g zYwtBWPuA<)UwvWqF&}n+tGwramUiF8d%2t|;PXQ3L2tA-$b92Fec^uHeFg9P8s{|i zDF@fN-+2o!zI_!y`J6CazFB-uXY)Df4&!?|d$19JTlLdv*3( zf3csVcmI(;!4AKK|Fb_+ukGl!;Q8>^$jvzkx$)lkHF+7+^Byz(Lyzd=%TRync%#3@ z`P*W4LI2b9J?fXw{q{cmFL8*2InJz!HUj2~uP(Srx zht;#n)4CzHZaCiBm%J_hfwbQ%pq+TYH9k__ZRh(~uWVmj`9H@+xqLqoK4g#Q!~b%B z@9*+FhV}<{|6H7(@sspFeT<)`KI0?t+cQ7XcZht$n>bGNhjA2l{mDPTPZ)1TIrs5{ zvko&Ztk39+_yyvg*ne}s`*_aJ?DIXxT=|;#vBvj|v_I`Bx6k=l$4$?9K|SnofSpH- zN1%UWM`KsDt6sEY%ANbKeaZjzJP!Rjp71%mKS_V#{g4ko0pd55H~WddUeS4go}3@? zLf<>?hToKrkjInPl)oE3kNf2Jupi3ve6V^L2YE@+>+w)?pFGt+AMs(|9ObF!{UHJE z@92EN{^dK>7yE_%J?iqq^r+o%KlX!Oji*Ci_C4C6`e1*k{DayzY4nhN!MC~J134#Z zf5z=`?o~egEWFmB_KJVUZm9=5=6-mZIft^ImWBr*9hMKur~Tuh$FGn6{NsaH1CzJ@ zQI7NXp2n_-@8dhceE$#p>dnsoz55skXguJDgHPey_1&X9JRos$@JZpyH^D2RZ~3I( zdLZ@#KL%e3pTs<4KgE98eFER>BOktwahJd2J!$v3^M0x6Pw{{FDeI93Wd9>CNF1@e z9K0XnKzto?^u0T-Bgc;LBP$=sIQje)9t{8Vqa(fYfBZ*7ev$Jq&nX7ASKE;fh3~Vz z_%?VwR+Aqe$a}dzdz?4nn>;_l53-;8{YO6XaUK=5&x!w|J>oU>tJH@bPTZ#DCoLcC z_XgoLu@m)yp6JK>BTc`*Ir`0bk!Jkl|7dUG+n5LRZxDU^-tWqvxv#nB|KPj!`}g;O zi|?ae_l@y=rQy|(OQav{XTLu5%m1Xm`?zoT6#P5=3E@}R-+p-BkKFQf@Qm`Z)NlUi zA${z~xFJXA_)rh)9`(S3t(ZPT<)8lC@j=QD|D#_C>9=|~8anKNcFz3YIgQ_Qzj=?? zm-};(eKF|}J(7+$3(0rf;|;^|U!mpbxA)^0^(QN$FVbhEf8>Yjb^8&I8^$|}=>tD! zdEc9*Kj;&EtVns%$g3Xiv2rucj!)^q*Y!IO_wR)v592?)@Xq_u?$`_R7x!1WmH)$@ z=KV3xeczV<8{X^8hj|WPuX}E_-0*EXf4K95$k+8(_w}8BcsKUFeh1^5TjadRbgEU#`DB@qKUK{PN*n z-W{lXfAYlt`wOx1-5>tydH?W#*57--@qS^vUx;4d9~fs5`M){V5!2WqI}Pn|;{KRF zoLg82IJdDs65FqZl-qeg&+pVbydL`?{E++X{W*mDMd~R(-cMv6y6?`v?9U7GZz1h6 z@9~HFh5SS~^V$A8A7|e3yj1yL;aYEgB!82C=6j*~!+ZXZ@^kJ`kDe2Y2MqfTm&myE zp4pryx&L2-|3hzIJ^eL^y%7(HUwC&Q`<4C|93MFU+jiZX__ugB_giaRop#KAhaC-i z9+cN&{!<@z`zhT0qxB}o8CmzK?^8&9?tfmRdbxX#RR78OgdGg!Xm5~t!@LT;PJ78k z`^YCUZ{Pz5)r;fZyxpl0)^Rzg?iEmu>K>r=5?sptH zH#45%uCK;*PaiH=_m0b*x&3M zj6aN5gWo`J%)5QOLf5?fO`guOZ{luTjbD|gY(Rj(zb8eCU<9%!D zH|_TywF9mj4_bfdA9iJ2sBv=a+ptH*BYlMBs~7EV<^OC~-fxZPv;O!&{N&F6$)~vf zvQI=#`9t|X)@AuX-Y>P>A0Ehhd&mDFFMcU>ew7~HviXMHFkjF!`(5Ab-TA*ie)56; z?m)hy|Gysi_V8-|+avwWn_nE~DZa1uvjcq(|L+dH5}yap#C!>_@qgO4`zrZAcpB62 za)&yOdRLSOWFE%J^ji;S-`TEm%KoCFo_s4k7`^NnbSYDLt$;ZB#_%!q@A|L#pY4?Tk zY{bo>CwP;P{_pS4#s{J|_BYtmiu8}P=(sV@yc*M{Vxmt9eV>Q4#OXZ8FTZ@8DY9ry3t=lB=@H+oIKq4#l}dROE;tGxX$V$QeLxATASN$%%8@1oZ= zJ^ivDos+|OweG8b$%Q^>H$?xWU*T>~S9=>f%pUjpkk|GG?a!R!9Us$c|F{qNSDb!a z%To{Xu899Ieb%G;UE9+R&-~uXFWlK_?;XkmvcIq%&uv(y_6xEOz2^V)vv=RU$G*y+ z_&Cqylb$#|%g5*8*ErAaJR7{b^nZ z{J1~fFO>It`w9Nfc6-nFSI_!?b*w|I^uK(jfBEn;Z{PgM6TgK2c{k@_&yBOM_B`ct@_4{_zYss- zzFuU$nBKojz&tJAc6{!DUm=Y@H-G<5E%iIU*XO|4PyTP7^Q`Mc>jv|i^8ZE+^A8|$ge(8Y{*ryQ@_W8TZt^)ld4A~Je2&*>f8IHUeL8+5lwa|DPCjvb zq4Su1KJ$O#0ksFxU=HUDS(=knD9Vz*z8+Be^| zhUYoo$2v-VpF;Fe{|5JddtUh0;Qz1}c_q$atTXX_jALo~!4p*Nx46IX96v7a$GLUZ z5$)yvetAE5723nD=r{5Vny>v9A2)mret`L*9j|W%~UvVzve07z_bEW6A{FZ!Cyb-8h6Vbo*RK9-s-B9(BUc&SvPq6AKzj=?^=av5} zUwzGW(kt(nz07!A^|kiL`&WI~U**sLsONZ-{K`FYKmJ8TZv4`q|EJ)(e(PEu`{?}d zecH!*&PHzdOysOTEAL1D*KwV4+122gkCvY)-YGwdoLBx2`FP&4B7C26`<^e~1=KE! z6O{LZe^C!RuKII)@Vkuj=+*IE=M!==&y43(p6m7Veein4_sw%C+G9Op9C$xzFrF{$ zy5|_i$vDC8NAL1l@*VINu3zv`^oMmjRNkHc;~cl<_dZeI6K9>|e$FM@8Fp#^=?8ww zeTeq!dz$PT_jPsn$n$#Ix+-@68RfCGd*sDlM4xBKE4%KDze8`xB^sv(Pd2<6&p+Yk zU3rPQ~N51c$-tv7j>ihbs_pVbvdO{xl^M$_L7tB7P=Q8xWab!LA`y`x$ z&hly}_<7~OqCD8d$&tp7XRpfT_x0FE+TZxUE8k~3*L>~M^||*R2Wd~9k8-RZ=!Jdc ztRvX5<@gR7{bpZj|M7?PpX-dvv|n1J|HduG|LyUk>b3WOfBfM6ivN3i#Qn+t!TZ7g z{U49(?~nI@;hDbr_+Mb+0ZGUI5r-z<1rNx7Kj4%6UZ83ATdc?OU+`u4C*u6rMf``y z{`TF`jy#IIAMYodmM4UFabE`Cf4{?kW=ciqG&Xo7VzJ~Yn`N{Bq_=n$lj2lRQ@wf4|q5ARtU*?^>pNPE4 z?fGPn&*pvGp`JDKhov*RqGtbl;`)BmXesOp|`9J(Q z`%Lu9z7>AWeP_IgaZdPk?Tzym<6RtJ>KKcR5o7oP0AO7V__`i6x5IGo^u=+#xdt49MCzD>${>4vq4o1%8 zyXqmm#An6(h2(25J7zcGZa=iM^Lg2A{rxomj9zUIIcR^ChknxDp!P~XnNQ@O%a;z3 zPkpWROugxa^E~C!54hSj^=V()A@#1;r@Zz&^W+>qxblDUOYnYpaQQ#Jx5awO_w8KQ zL;dWBho8ejKgS1lF7Li8|3|xbydU~`_wa8b`kw!06t5Q_MLZhUK~|vu^ca^94`d%t zdhq>oofN6RdVEj!!;-e%xla1+ab10#Q90oGEEn(hw~uxF-81gbct7g#eOu%H(7${f z@qXSP{>d|a#(z2gr~c#p!Y}9lydV2u9JLepKkO#{V2=Z0U+a8`|KnVSHvAsD$h_{n zxblH_`Jd+dm=~;5_`4O$XC9G1eq)bEr(Ax4b&7qDey;gC{*U?CJPn!Ot}Ee{|8rg! zpS!Og+)w-A{3qOg)sI2>4c3d%EB3D*(`#6MIOmS_{6YKiDeL#}ogbW!n17z5-~nlG z(w@&eCt&C9gYS4i>v2CIPj=?hXovN7#WTNmPM^zP)7tMfpY!mQAM8C@>|mEqyI=E> zbL|gl`@f>?dtUf(oLlT)=_$XLBcJvuH*sid{2$sTe#~C z+UL&uVLz@vJV(MlTvxCY(_!s_w6pVG)T4bDU#9)WJ7M?eLq5U#=X`AcxsDz@=feZi z?|2yFlCW?0t1I8*pyJ?pRJkDM3QJ8@+6XL!JPzfd`7$8wAp<*&Rb za-pw5^=y0cR_J|APrLAs>Sa(nnePOiuUo(4LA~iAR8I9|e`+83*ZjM*wq`hz_(pOl~esb`;$zysQ^aQHv+{f-~!e!u4je}g`V+oJuI_oE%Z>%evWuSmJ{ zH>jR0w~xcl|E2dcrsu}*%-3;!ov&veCtf4uI{cvg3FE}MchGr>yqrHkcr!5mkA1%R zdz|0!e#Hff@|E0AyVTcn1>+FMZqN_U0oa#(eT=66b^Y*26IV6+702EE3VPR$_k9cF zqaX9RT>ggsU`O&;jzy8Pb{ZaWY;{Mh9%A3ohqi6IeFD9=C zzgIfm?}vw0e|qG{|8X6?$Nz=2gWZSv7v~%Kj^B!$n@Ee;5B@k*?%~7WUC?_-{pd?x zOhix4ckjawDWAwV*>CGX|HMaGFL94+eek8$<2WHF{$em54@6$-K|j9FE0&MlvcH`B zS;rh-`@Qmi>JfWve%N31j-2EhkE-9o?%}bF|NFxS#{Y$H-~2C+_nqDyae&50{QD??kL?EBvztM4Bj`&`anzgUp@<^MYd z{jZ1oAM+iak8>!zpK)uXiKpZof&Prg^F7yhNBNxxl=maPQvQwa>!}ye{!IGH|8YO< z^IzWgM|u968=?oV4J+u4{7*EPNnD<{V1PuVHd>fVJGl?+KKTc zrqTECe)?O=nSU*hozjko{KRw80CLm5@qe6qjM(>2YrJeAV|1jmzXbB;Pq$ zf61r6qT`01_WZ8%UN`0EdzYncmvftbPK0l9eB2-JJPzkjuE$#N`2mdx4<*V(m=aU+?>d#ry63T;nn2AzU|!|I>cr0p*kVt|a5}CH!CKOV2Z& zt30>)zJu4VZY7}#&gXb|EE20-eAW-oD1mwbmak^AMS_e`+ud`2Vkdz%p2myLgy#?WZs8o zKXp!5?lmg!>+91V@{K$rm-))i`dm5mz&>h6>$Bf04`{yUqig<@w?5B3@DR$u^_^cU zEox8le(-dqwa4M>OvmTF;{AFLxN@)2cH#l!|Kh&}cRS9WMeTj;a`+1D(*Aos;{1od z0PVMSYua*+xh&Se?!0c5$2QkClB@8PS>#yd0OSw|4^R( z&iuVkSI+wPc)sS7`k@`>)0d+9p?&3>e$=n*E_8gRoc%ec8xL{k&vqWocJ}gjyjA6p zgX{F$=NIZPeTS|m>3POs*T4CVqkaiqkNz;e;axwt9`6^*_np6+%6q)<8Sr|_Kj`>h zc|Y^@uRHHYeQCMYKQ?K{ckV|IuD^ru6wa^VGvsxyX?dS1 zkN;!+#=pVmSr7er&Huq)Ay;y=?z<0YKfw74xjAnrzvWrSO~?Pa?~pgPzxffyoBvyY z@NbU)dHp=6t)F$DcF>deiK~59-;UWab{+5Me>R5y^M4HTsB8S6dS_kseOh@ic|3SP zc_ricNNa!QV@L2>#`)nl?>h&NC+{a;1@A??260C6XvCRmzwGNyE|_u%kY z+8O&q>UIAauOYw3_-R-1ea0_xev^;ue<$*NoY&|t{vJJ$R?pfo{U$9xI;g(V8~B5x z9{rPcPra^7*ggA6cxwFDAoUq{h`(2Ec^%}Sf8n{mlW%$M=UjrmI9D?tOOO82r{l?Z zP>=hUJwC4Si^nQG*typCeCfaK`5r0H%N(Ehza7yl*F*Gc`7pk*_sX>^*}{t6%Y)>3xv$`}nQ;OOGM< zsm~q9j?#1U^^9-0o~y}U)8}*b=hE>(@r6DwnYcmy+I-({(&!Uj z(Dr*j_uKG)XTC4qFQmu!yx+v{#pewo*H^f8d7$ z?Wh0snD=}CyKf}BrpLr(s9`F7gQRa>Hx9^TuXkYhb{9kd>u8+#i zd}kleywqRn|DC5j7r}43POScP_ph!e`j7lD{!Ra&-x~i%e>_ik-ToCnC658WXF1L# z)<4Mo=krQ&f1Nx0Z?F8Hyc73hUuWc;N&X;ukuPMvF+SuVk4X9bf56x){gpps{|m3= zxpeGGIpUc==ZEILvweO(jU3#+;_!dkx8sFy>SSYZ@)htE&grA_zd}! z;W^+#DCfGR-n@@}H0h9exAK3iyQDdfihcjDcDE;RJ<$V7X#v8$RO&p;5hqp67 zoP6{#yr2K0_@}quKdiBM!r}dlGejQ7k$Fu$%zyCA$I&m!fn2Bm*aiL1kB0JH`V;gY z?*|V<`SbO&|069wXnXN)wOf6I#{bEKUggma83*ifkoA{+rtxaS|DE~3;sS}Qqy0ey+y1^ku!zW5&M z)$ZLV?z{%$w)1|&XJ~ixKV$lZpQwM>Dg9!cccg#Xb-b|l;XEIE$BzB)4g8+<#VhvR zNBBMGEAOp;^OTo!B671{h3FOeRz&}#L-{`1wcL)5ujiR~(kbWo$Uo7J`i!>{iJv7O zyGY+5a_sGmyvav@EGO@GKJQMslTQC({NK61=k%_B+grzl`t_e8{nft0GfzJA z1-~j^9U>?1Yl@B!aW(XR{Vy}Tse!ag%JZN!lltW(etAiKhe)vJ;A3ku>l>h2^|J#ok?`Iqx@A-QF zUu`(N+c_TZH|76+`P6f0J^m+{a}@1>fB7sIp5y({2j$Q=D9;BE%X$fKi(T*^WYP75 zaYq|tAIwwi#d#9%7y2DC_Q%Y#-g^mquI|1Pf3)wj@jvXt@UNo#Y37&do&RIqA)k37 zy6@0rQP~%8Py<0Xg7-;L+(Xe1`M>`ybJHo4>qA{O7EHo)eT~{|*D| z&@PAapX2>HN8BOj8tPe*a-_q~&4Zn5LC5tKcFtW9JDBpc^KJM)^ct@ukBr5{`wc1= z{s+75{qyYdl|TFTyde6M=R+>XTOQ5)uG35Mm5cQXJ$w$ePx(^j6KVW#`PchxN4w~K z#o+;0`I1Mu)vI=^ez~r_rf(6uKu@e2TxZ@|uDHPNKfec@ewYu<6On$rinC+=+t11I zf}nD%kNBofWB$YQxc%UM=7IHi&aYg!pWiE=+#&in^NYiCS-;nrPqw?``TlDf`L69% zU*$`O=5t@X#4G+wev9#+_k!aC$G)&{_ zul`CNg!?|7-q(x96V$JMn)gF*&Zl_5o&Qr0&U43C`?2515Axo>_m7;~Res?f z*Lj*>v0l!-*vsrw+_#+9>Dmd?vxxqXBaH77nK$_9LG?fJe}@2vo`wg67ekNnPrXl^ zojAXT52if!PI=~eXg>Y}{*UiXAg9Q49(XYJFXVInLN4}G%IAGN2hu)#4#EC#x1X`6 z^6S6%4L>;PYaAZqfjsCRUat3j887Rlzvv0OV1IZ;)^qF%UTEb3KOFtzdy}EOC48xN zr@p8D+CeYaG4jA?hko}@-j8u}+}Aiw{(H(f2|fs(kNWt3Nb$n^L zu=AnV3v!0|AN7PDkc%6snUJz9A`^oM>~2d$_2 z&KPfJ+#=&;f0Da%>>l@r9Z?SbRvu&=X|Hy*JfSh;X5x9T@NH&4({`d+d8 z5WDqy$a}!_uk+i)YkkT2n0@OtJ_o;b{U7I<|I_bX!SA!4@i3D`>-SUz_9D4ZD)AEFX#X4$36eY|2~xKm(TuAx_t3Z zpV!az6i*1x$M}SN*N=2~=KEIOkA0rcjlMpRb>*7}pUW43;d4R!o^hkh@8OGGAL9E4 znOAcTdwovxym-Ig?%Wt5?%^`DXc+Ai|wZ`70LFUs4G*XTah>*}ntMz{$o;$E3W`d9<-33E`v&WC4aP~H zN;`G_cV7r^=yQzFcBz;CgsZ=^-s%^%1NlGhqn{!A;9NsHgX%#$lJ~gWvybyW?)Goz|B#P-Q9Ws|_wlmlc~<&rhofi5ZTLXX?fgew{a$%M^5OqN z`?2zX^mpg~KF9a*9d?5R5?3#0&_PFz!uCLAi5c`qm z6T3geZ_D$Y_bH|0OZ&b-c3ge;aly^&;lXx2rcW_`?-~!-^~%3HIW8Y*u_!Z>UzsU0uw|C|LiqktL>eCOO(Re?3vi!8;i`{S^<1fnl z@f=tlQe+)KF2+$_u=l9l?`S{l4=2rfz1ABK`1PSb{xAJ+j@9}{2l|~sc|!Sb+EI_% zziH+f?^|m(gTB`dALxH?=qEfsvsTGUXOFwsJH9#J-qj8dHEOq?@K>@&v*DVc)H|1hX2^l8_xxAX8vIPJ!9n@ zSM-A&{oRER|>1^D-HiZ{$TGVihXI|{eJJs2lSk`eV>S&><2^i@46|%?~;xWJoA6?Dx!W}9;ffB z8`p$il$R*3N#tCoz4;zCye9Hf{*M2{&#I5#eqia4_28Ah;sH4a`@TE#)A&Ey(=L6F zGX5{#FFvd^h~7fhtJzmO@2_dw<-9>Zy&iujHV!MIf6|VFh+Q~Nd;A^!x85tF|9GZ& zsF8b(3n=~(yBxl-@uU8DJg%GmGK@Fue&nDZqT`|c+`sR9KF`x%_k&^Qdy#tG7s~G; zuXSev0cM z`(Mk)|IPWWbMYX42%abOJiv9%1yc^cc*p-?m&A{G{T2VWzvs*UHYh*e*E`4m{rcz+ z^~U4L!@WP=!!>`LK^)vjR`ks8{uKc;4EC1)dKHe{+KkyfRH^jI<#?AHd!{JYD$Mux|dthIn z`~iFkI}q%32ibJYP5uy+2;B=j`%*JP+eK&#Nrw zb^QSS^LYUNl6lX5VNm~KdfrncP5baMy~lWt|6?Dof7p?I{qP~kWxe>-sTVm`p3(N! zes*qPUXve=Uha9p^Y#6_K|O0clXkP7_wV>Tu9tu22g+YD-Y-NSTvuPi7vH6^IPyjB zTm4ZyA3I(BsPW8{Kl`V1diX!F3TA(#9g{|#ZD7Uu^t4)A~82OqHW1CH15e~u$O z2IKX4v_JB7!&fuTjth1qf8zhLsh>3WF;C9v^3OQsc7DhCi=4DWKX`6HzezJM81EHX z7o9KR&iAqITRvXUI4{;;?RUrgQJ8(5QG3f@_`g)<2XQ9U%l=)x^_+6$8N09N4EY;* zPV{M9;`lS$Kl6XZlfA-tzVKQOe=y_CIIa92yczxmo(w-}T3*li;XVE@zE5O5VtiM` zPF$xz>LVT~G;R*R#QsKp5&c=uj8}RSu@}zcBHxAa{5-r~{k9$Ru_t-NLDt_Z|L1;( zaXkk1F~0GC-yH2y{(Hx`!vlWzalZRf{tr3PPdL0^{2z$DhwLAI@7TW^_XYp={=oxc zZ~YI%I6!zgc%pYteE%k1u=hwo--{i7?86~H@6{F$cZhei2j3FH^Tf}2j*RE)f4{}? z`QH!Y|FC1<7Y^eAyB@;p$@k3vG~}!N-^U)ehkumsi*G9p!t)^a@SJ48cdiJ3Mp`6( zl(;(LRzvhb{_uU;$z7U$$xH1>|E4^0$wQqHe}&wf>;Lm12k$w{{~7NIzb5}DUhj|p zf**5!gz{#?`;~Sam`}tt+0Q}7asJcm`e_>bGhN&n@15!o$(QeNo?5>=3I1Dt zBJ95&`+L6VMR|??<71p8cCH?$+*+RdyRMu&&q_Pw zBe&P>2kYcrddkJy&iGM&+Uq|QV0zOo?O**2Kwh{ivn z57O9)`$3U$GHo0V^;3@eLF{zW(~j+FH}`TUzvriT)8r20{YuxrGjd(MtJl|Q#|?e! zH;eBTv&-z1eVp}*?6Vy&ctH1wgPvE{^EUg)xsLwloV}i#$&dF75SfAgQ- zc)u{dFMQ4GDcA6T*a!dPJtO7b9{e8tgij31-w_^-euaPitnaTrqSt%hHjJM;^LD>_ z))%jL#;%9e(|>!z-s|=IgWo*=JMzureP+hX{}O+5>>Jp3fA8>no+DWI+3&GFfamWw z4nM+vz<8*0{2%oX-@$x~2k5-jIc(5&a z{|uJ@CAjl~o?EzY*T3gG{M&xMg}-wDdyVV!+(&u+#vL+W=;w<1?VbOVr?P$hw&(Ep zKlov*}9kGz);f6jczkHgQYN1q2__v+`<{NFmy9j|@f zV^7Wxk@E0li2VO`~7Z!)H4Fl;b}6KTx|t&y)w{Q?7AcU602ZlsELc?X)iK@rT%p z^QV001>yk|kV72*AS|HAvO{9k$#krVyXPvUlvpZFQ&hZj~J)AD}) zUsro}evnUnepi}(CTaLU#zn-@kdFWR`e+Y(gZG2~BTc)#|7$#?`o~_i^A#O0`>CHW z&JVtzxIg8?{*}Y?(C;4aMd6SB;DPWjri}-L|1&PI_(1Xf!B5Ex5=TaT@Jb=P;*XE> zf&5>*nddg*+VE5SFPCmNSyyK~)rWxPoI5PXvJHssvNc}P3izoUp={jHmU5@|U0H|B$~pyglwQ-Y=w_`$Ny`wBNezesJgikemF_ zcAO98W7k~QzVF|6?mG8VE{x~v`Z--W-VbnG)n9xo_nGf}%06cN(xcK*&xyyyKp z56J%7{;c1JcONk4%+l^(JMYE^YM&E7bLNxIJfQPzctHI${2%t+|9&S9Fy1fxa{kZy z?)g975B3~xy>E{+<*yj;7ykA0KI8x1zX{|0!oPTyJOBS9KJOLA?}gQ0`(b+EeQEY> z><>71u&#^d$M-P~<)KF@Q5d;U+}Pru0h%tNsJbN@b{<~-p#63+e} z{mpq~@+V_u3X4?!vmK7JTg!6Z~E~y{tqvay{|mDddNRs_3=60Pq{`< z^;;f(oo}!7mR>)Nt_O?*^UwL<_gPps9G~L;!ul(AALzW;`Ih{_`TC^eX|AYT@|k-- zNAI@3_QQH!&qMjd+DE=s?(s{j-=Tib;oRpr9iBotoTtP8ozwCY@qzIe;W^%KPa}`_ z$9wI(Sbp*qDzD=k&o}G&)lTJGulyhSpZ<1T9%;32;?r#BUe4rEUdL_p$-Ms@Z#evr zdOrIz#vl3gvuph6YkSJyG|$5GJk-BnFRX*K<^Q;!|0>v?-?8KUVE9ko z^Hm>f{2$|QIo}t=9}S;SomPwrhXz=eFB-0PQ#Z*G{z~dB2{w!h2Ak2=B-H zB_Z$ovhS1!G#~xTUk=}hzSnkYuW^}iVjLO|QQnVvPn!Q&_`UMqe?H&;(Sh{yCkJBZ zfAr)7cl_#jPZ)lX`{4ye{1$P8^pAXT_(1zT@qx?};scpqzK;vPB|l?a;G07~oaaOM z3Ev-*2i*BS>XH9LuV;S4^CR~oC*L2Gmz?-Sc6_k z!7CzH@AnQb*!7V9ukZWbrR7Dj4|%A2{trEk9O$R`M0qLBAuI1kKjf>i2JQV(d z_k7`T{cj29IpkbX{TBD5uIz5BZ}f z%GIAU%JanovR>M6c^B5xbJ}yv@PO!r{R`!gb4BFv{v8{KaLTRmg2?@f_mlrS^L_Dw z<+F~W2jmjF&+#Mv9r;*?mD_%#55`|ThGT!`@A5G(unXoPc8FiL|MF^FM}HvsXJnkb zzJ7nw_1NRo57Fa#9X*jwU)Zz#O^>_1 zF+bFE{B7ehdQD$od^FGNyl+rB;sHVT1D#_B_x#Ss`iYhQW8CJw;Q#;mKiiKV6W9Os zdObez9RIi9XWSp_FuWUB++Dm}81LtQe?Pn#{?GQVe4pos;Rj8}`*r_cJ=VbwAL9>` z138gr_&>*I_&=|+{;;p-c^c36MdSYD|CrZ)_m6WR_ObJQ$~F86c6xpfa`*xF$>;Og z{kgDn-xY^9^qlT~e0aF?_dU<){(IE-6VB-K1N;W{GvAbZZ)e&wKmHH@u3X}ocR1IF zKXU&X-tm3tb@JytqTgEOqdwC+^8CR3Rezo@JqMrPdu!Z^yOS4We644ALDJZX=RZ*U z3dc{FUz+Rk#i912A710=uKBb_J?Hz`0otECr2N~5A7e!|jye91eCwO|=Ir~7l^c5> zyI=LV_jm0#^RxaB+RmhHr}XfAmYcNY?)uIAQJ*_~Ph;=~a&F{9Nr>f2bYDUvf@V9_A_c50Y=Z z)T{V7v*31>oslr@P67U_JRDQ?T7is)%x73`Sfa@ zb)Ej}XNpJO?O^TajJJH>`rSV4yEJ^Bdi6Vh@PW!H5(mWfctGNVNQ18P!|Q!IedYVC z_qDxy-SOSmIp-DakuS%{GWUtaropjuZ;gApYJ9x z?ws#Q6UXAb!yb^2`Ph9R`Gdy&_5LsKy`pdVWaWWJjR$2OG4AQt_*44de}3f;X_xV+ z|M7z9tNJ_#QjYjR$MFvq#6Q6Qh4=hlJmBz+wZG%=kID;QXuR%@GcN36etz(LJTLgg zfu*s}pB-uBhxZHdQh)s5{o?$hMn`@U{QW#ctFnY z@I{{2fA~Q79P)|B1>^fddB5^)C%y?@NZy5t;e)(x{GHz^ zulLPiSH$C$w*KJ(OVi%U|IxqoyMJ8|u}Aqo_)&SK;R8nw>XFAgBl5%hh3JQK9Py35 z54`{XWy(>Xa)j|;XN)g%9Eop3PmGWHn(-^GypvBmj;rI{b^1U2jl4s=1?W5@zKwY< z-vdwKywg79{irAY4>{pEe2*FZ8|RBY@vno(@q>r{Li~fgY6$;ldyWV7uH$#+|K>e( z`!C-T&xD-vDDf}xTJbjDd)oc?H)P*pe}{iL^D*iVzDIdU(=PX|xaJQ}>3mzq<9uKG z1(}~9&#%m%|DNpW>-aQoAnWXk@rR=0#dXF7T>D{ua))D2T!&W-M?chup0s2A$IcgW z9){n-E>_(6H}%Z95S~#UPJS*P5q+9poTB_U^ALIBsT;CbdkM$}aX~#7? zGL5{p6A!5U)!y}b<o@!NLDmcR&!X4k0Yk^($_K^+ zhQ$HukG^{PvH1?5>(czEV~@|{yMN5zFU3#sf7TNpc&(Rl{QB`8G59wR{k=bUK=cTD ze>~tBhZnS5=_zM?Pds1sg}vX)I?s57uHWAre$8(v9=-*~^!eA>O9573kC-=ltt^A!74 zxlJ-9BO#SqS`@=i=U-5zD z+y2U9bN)dd$A|0A-+exN4)i=P|Ht+G*3Ktlm(<5N*Pin_KCt^lsGbEf@ry=7l*x^*?Xk>6~d?0#VUQtNBD z>SN`p=j-V^dysch z|JXBW{98ylc)yVP@z3;=^*jF0e!8ynohAEm<^Pa}^@RH=r`_l;hF8`?={;oV=yx*X_pYceJ%TJE`=+BQ1gfIHT6QWo0L+tIi;W5t1V?TGfh*$Oc zit>N(n8g8N_sHFIrJuj~^>N?(gVzJ$0f}3H7X-g^#OM9`p~s(n%qK38|AT<^gE&AD z|Hk{nJH`XT5AwY{{u?45aPWWefSfCOADH^!3C`#Fc)t+d&vU--E&ARsUlr%S!T4R` zn*6@ue?7*Jb2aA`>a~9P8F(kpi+4zWZx4NFXV^jiQHD3B9qfgEst>=zh#kTk z+ppoL;(g?$jJt~8iRXKTtRLPlQf^Jh1BK|<_6OJYzb*dN;W=ZKx(gHLdO zxaSZ5x97+Ah3JL$!}vJ%A&yf#-W5k4$77X)db)1?pYCt{rk|Fty|FjzKYs^s;<-M5 zo@Kpe{daw;{ECbiX;A)r{VpK>W&Q62<=#I1DIMGw*lh_xAUG zzj}TL5LB-CzB6`xka3m&;~WJ4$Nu}u|JkqM^=v1;?~LbirF*}4_&@oCc)xJ?Kd<8# z?|47vIr)r(Xn(X1zVAo+%Kwp%=Znv6JlAoizMU74Kfu40&pwv=*ZutG&#U|SZr`6H zm%Lv*AoI?1-~9i`_T&G~*mnf1C*CYeej}&nkNrGCys!D4^Tp%{ zna}FceKqSl`)d*XdVR_>4(-3ec%68a#%;&W`RDN=t$tteb=4cL^=fyk-EbbaKHu}~ zd`6HDn0>C8-vP7h9hn#MO~_}taGj5q(|^V1-SK~ppY2XL@4Nax=e@ih za?2Z4Zs-5FzLrm3@~=FbdQ^^hj>cif=H05d#`CJT^rb(cU7jn*yD?wA?s&$>B_BMn z`-S4Y2DJ<2UHL!yQ9Z?B-LDJkVYM&%sXWZH{D*#{c^Jk6hOY1W5B*De8heh{-p85i zypJni7b@4v|Ix2Cjr?nxc_1H19N^UBefEcT=og3|SrLEqn*Y;2w5Qe1k#p?M@s}T4 z*E{!p&R=;P#`P{Ouk&T)8E5Koyyb^kH(t$$o~w!H^>x<4SvR#W(&+PQPve)oKIx?(ZyrW+1T9mhA9?`Fr|2tnd{*HJ)`8+UtkRLSuPhM`117!W7KI|++9>zz0@XG(i z+fg3gt#aNs{2$+QV}GSw!vl67<=KxF_b2~{UOybXn&b7O1DRiZPbQT2qud&oiGJg0 z>(BIq{>4k$Py5CEQ(wrfyyzRd*I&X%65sdh$37aq5Br1f!#?2q&dBv2Kh8_=bbbf? z#}B>_KI+W-nf~E%&a!`@=P={a_|BjF5#Iq+Kb$M#0pt0?&hH^Sq33-56XJb?_*>s= zv^;)U9$@&tc))Py|Kf?@Z{X$NYySR_^Xo@E9%F@d<5XO%<+`dvTnyYheb8(xooyvE8Yr~DrLpK^-B`<3tb^&YJ9 z!Y9J>^xo_6Z|a%x82-<8Egx?*|K%Vb|72Vraen$e^Ly`Dr2p6t`uFjDKlmK_ zfqxI}-}j#V2bs_4!}j5^@e_l#>-R3@iFf|b`GXwHBkXqNueIahuP8^n2*~`k{2uqm z`Z@X7KjlK||NcYIJO`(qEB{t}UizN)t=G8BctFRE@o*d&7wWyk)vmcN4=S>*Dv#q+ zy^f#uU%l!@9+2@N9kPCUUF3eRUy=GaH)9|2ej$1}zlXf@j@qC7^n3(=h8?_$>x*B5 z7t~%jukk$SQ}>|<`4KVRFF)3Qp@+XUp0D&3<@H#PtXH{6yAPdw`*qJZc0c;29QwDs z{0{raHO;m@O)ePj9nM!9L+qtrTjiV z>;29H>#LsX1@Eq}{Mh;Wq&;72x5NJ_-)eX9e}nRU@_yLq@P69u%Kv%J&#tc+58yo3 z|7!Q_B*z~%ude7kX}(lXSpF-lTymVtsju_=RX_4&*pG5w`LwYE>S??_#{*U_l;7RQ zt97CAViYQWM%zP9HA~*36An_3BoBh(-AMDe#cDdX4+ONIc>{_JW__4FS%Zto> z+^^&JoFAa$KWP8;5Aj5IycXs5xW3Z0J9y9k?ftR7b>23=~&+v}PcW;O22|GgHq2sSU^>gS2eaGXVhw4Lq#>alpzvff(sC03E z?Ybl{fqt_4^tsz-*Fp6|D_r$I^`-B#9Nh0XfYvLI#(qW~ zi}4`-jQCd0yOXb6jhB2I^M(5uSIW!tiR9xq_k8QaZkAJ13e`QQP`Fa8f+xP0Fy9v<*~KmLIK#o-6| zjtuEPT(JC*{?Gf^@|L8jm*>9OL5NyR1d!Y3lD_7@m{g#f6k}y26y}j@(fRCJy-sZ zeEzpwdm{W4_J&@m=ZwYm$^ZTClLr*x8NB{G3o0kPE%JK(w?3l$SbP}qZ;Xfi@BQic zuP{DUOb_V={mKvFchwW$6_q_nlGu);{m=k5>#=e$jD9Ka9f}|3A{sb;*|F zxXuSSb1ncWk|GFzAV|tq_=g|LFX3OLf|nR7EQO@7{LJoee|uqNRrj7bu>Z`8s;)~` zR%TY!n(E!^bC$Os^5f^oPa6MKPnO5-Z0~h6zQ~&~zN9%%$OmfArdcnQoAnF+xM|C$ zzF7VZc_LT&$=tsS|0W*_Z$bHBdBBz5%e_V9b|1Sw58oK1J>+V8d;k0IPfp&?eHQ0n z_FM8soCjR5(1ZNZr{R8{HlEM>f5gSNH~XF#{?B;%bdS&Qf!Iaw0s8+bcro&y?)do& zXn*o)`L0O5Gt%#lv|Zx!`=dQE-_d2=L=WNTp6~q^>1Y402x;?Eub6&(9=pXc5a6jgIPweY*F4A7g56*TN$3BnPfxHH@k#l3tb)LU+4x9T| z_T8j=UNauLA9o)-&l@w}dZ{n658nAd{LlS(_sO0E^&jF2>EJA{e4Zz0xAOL!RGv~E zfN@$b=s8MxjUSAc_0M}2-c!IoNfQ?*|Ce!A50j6yowUcf+k1b(=qGwjevs#LezXhE zU!ITI_v`QSC2M)wO@8Km@&&X<8vDe)cDvitkK#zm<@ugYe(W%aK0m+BFPhg*&!|0z z2Rz&NZtpLpS3j#<$=6RJpSb>CByt3i$9Paoy&aiP`THRDsXym;9rFLC@PKo^vBv=7-yO$Hcif5h`X_qg zoX&SA@OOAB=gE0TKJ@+w+phdt_^_-8rkNMo32Gm<8@pKhqutIo`m?^Mz4&~}s~)f9 zU*+2UGje@%oN|AE8$Tym+7I6+&riSS|92^e{4e8n9>eo`ACGt`FL!+(5dFTy|FJ%J zA2ita!`rTU4d1sSys~<9{gKahok4H%VWw-Jt6iIqU15jX7j{FtFQL50YvmsEf6A>t zh40&O<^Qs7b8ga4eJ=0kIyl!)#xH*jIv&z*?&Ea4>dEoT6EZK+L(%&ByFAaz523%v z1xEkap>nSAu>G3vImLCK|8r(t&pE~Ot$f_%{p7h;UXJ(|-tEI--HeBF#Py*3-ly|_ zw#R(C{-a0Q^ZZ~t#3|axj^w#W`+pzpW%6cIf93z=-I}I7_&?fVKjl5d@_;;t5A^p4 z;R8P&<>`mtC!EOpo}@+A;ct%gM7|%#It)K(zm!)_zZ>iQzC351zc``_?S6S^gZdq( zJUn`1{*xa&N;*hf`iJ}P4*mZ2JK)^=`^zC8{2vHU2R{gJ2QP^H@_rz4e|;e1`}RQY zqy75+{8z_$hVs9t2rcjQIYCd`W-TPCmll0feXVydJ)!JdWpg?onaa-`~&g zzyAT*xA;D=$hijo)pH~74J$wG!21R1KRjUgqu|ba?0kmxZ1>-e@3?$8cvARG-UpS> zy5{}lNz|9$Ddzjc>YIA#S@ib_<^Rkt-)Q~G1HyO6SIO^@hR1{dn8>(DbABn(KILt9 zoBSWUX@9Q|#11(} z1K&eo^|xq#%ahJM z()GP^9(`>oBpvk>*YOj?*Xz84d2J_bFw}cpKf+-n*I5{ zkG@Xt=jI>J{}IpnePH>&rz5_Z&+k+4`y}D#11G`wNjTakRu@xjUa zkstmpyxtj!!|#vv)pmoaw`1f8W}K7%Lm$M0iP0R$pYXgTFJT%xC~r{S zFzuw>GdeEpSGy7Q7tf77ANIV^eKO_QeL^srMN1gFVh*56us+_6R56 zHtU_+-TN_K!oS6zf|VCJ&?j+VmFrQzyPQ{Y*k1L79fk*-@mzbL9CmS@@A~b^yHGwn zjP+8#`SH({|6_i!vz2#IKJ%@I{b-NGf!&Vd*VGIDx63j4pNxZg#EYQgnEf&i(}^p{ zVR`(L{#Go{X8xK+ANq6f>OP=$Vf~dSLJxbp@-)d;p89qADX!zoyqr-#b6)lL=g!-gljU>ZRZH`QFc(#*eaoUBx5gto$YMpYy!yz}imiS-S)p$W$G{SB>OKG1W;Zg95xL=qn0Jx=f!}!~jUB+ZFdq0q#=&>l+Ss-l?xB}tK&Qp-tYYp zoybSdua5JK@^k->wC9k?C*cRYzl#0&J9qp(8t0MzZd~vEac+mto5;OE&&MM7|KR!H zFR^2he#}4ff4-;6_l4yTR)nvzKYzz9JVq4xmwyQF#l8J^JZ z68n2`*av*hHUEcQao;Ye{Y?H3c_;rT&nNH0c@Vxy9?<)JoMX!WAzyew%4y$4;=5CuX!(#=kPepH~buF`mx>>-^V_~`+=5A z+W$jfkKE@d(jIy>)@RZ^^iK z&->d~{Ga2}@7MRgX_xxt|JL|{J*!vRcU-315Bvo6|Kk?7K+oMfc3t$j=c1J#Kp(_= zkmrvOeOZ6y`#5Ja&S3aBQ9F@0u^#Q1&OOGR-%CF$FBrL)N99Pp-1m_GOaI~jkc;v` z_EYx%Kkd%f!3)w|22~`J}fGk@=-1<8$5% z&ON|)hd&cHuh4q(gnUP2O%o?+m-vV0UA4o0eSg39QQCI6H%PmamsGw!e=V(kTnFC& zAXj+5>cMjQTklaa59pWmb7Idq`?<$7^CMq)jc4A^ail-&2K&+e!WZP6*K2VISTDqP*uj#xwPq{9vAw z&b$|C&wIn%`@z0U(?0wZaV7VP%bV3sQ;zYR`DpB$cr)#mIM6twebS!!_`}ovd3d#R z`Mv(*wEu6YpY49L%b#@hz`Y{lWaNlkk1+94#9teCZQuBv?{??AV#I0f!udJ>zej(# zp7+c%c4N7mhbMpI_&uNJ{%>(_Upw9XdyfaxKC%1ss~nN1*m#2+-WQy9-S%Sl^%u&8 zFIfFZKd~L_eOf$AJitFVuQ6Z#f1`S_J=55^@&tF@Zq-lP{}h~l-1%Jnn|$r@%Ac{H z#&`UJcu{|kpT^FM`Y-dRy$89WQu}ZFi7&y(oAk?=dFNbD-0%FS9nttP;|+3Zr`mP; zS?eih?0L5b?{S64A@170_w&BI-{0%|zw&lTd!G+`Gk?9`hn@F*U-a8@;fZr!bmjf{ zUV!^Id4<>`_Jv)>4|lsK9z=ipeA8a}J>w9+XJkJ61^lUq-sb+8d17B`IpaC)$#XSr zdxyPNi{2=Q$JO=B!`)!}==j?k;XPsyKp1*?dSlkO^zB%7H@7-6(@8tag z+hLsa$N9~5Jo|@zo#%P?1U!S00h}%LD$Ox8J|{Z-=EZj*oYATp6eKX?$e7 z^y|Gm@6-8xhVX!SFSq<3>-<-P50r24-XD5LKH8IS(+||QJe&5}`I7H(ey|_*58?mT z_eMDXGT-ulmeVfG=R8_F$-F5?`M)*oJwogw@}~VD_W1q5_hHxYe(2G(h}}&7kMy_W zKHxDChral32t3B~k>vc%y#(Y9axa0j_Y>ri7^gf_-UEgQ{OpLg;L{OJ{4OwjA3Oo~ zra7B_7Z*u{tv#F`+xALo zykBtgde|{(;t|NXp8G50gPaRM+5_bQjSKR9Kfl)t@0WJu|DKL<(C@oLk03nYMEGsw zgjeF63Xd&@hYD{r`9OI#_%;3?qFu=QVPDmE^v*ce`O3TnIrliP@?hwJH2jAA)Ez{*2R*s|J08v>%oq7V^liD| zwZ6m0BA@lsKD-%r&hH1h9uhCmUoq>W^05Elx%=3a|3e80qxCv;+FgJoF6=oAV#z@~wJLxfQSV-+A=;^|`zN2WNXX{(Nfw?nisQ_+LQB4yzD)9? zm*~;_8Q-R!(tq^z8qV_SZH=R=|D&JS>5BAIJ9fNHGwwWJ?OUFo=icuP@An8(9-Q*h z{!FWP<$avrc}e-SBW6A((vSO|^2hBb_0t}xoy2~*muA03_@lqO^LF9)RvwUc*4X>#TXa+ZvAQUbc~xcdYh(h@}!^k3xDRlzu(-@G`pP12NJ*XT>eiU5W&B?y%&u9-V^-A z5BPi^C+`7so(}()dw}vv-`)5E?*G9Xyt`p|K=#r6&K>>xoelamEqZT|ad|J0H0KH5 z2YxzMf&Y4o6Wnu@5A^+D#^d|7dCxZWz5gfwCyzvX`Tarm$?yf(0epq`mel9Y&vE{e z_hTIJQ0jquf$)307mR(9&+ktn4|*yOh<|%eNq&od=KVtUjoz2^ePHC0SA(~dkCBgq z7nuAX&*YmM-I}+4<^lf1-36TpSB-tf8vv{=XsasZ*Tn+xz~pLPj`O+Z6~<%XKNZhkox_Oh|kUE9Af+uSuse1+V#%=eR0nR zJvU5bd~5$#X?X?y|3JiQdDFxr@^^H-3vUXlhw^#WW1m8O_a}ar0J(M^koqfsa86T? zd0$b!Bl7e)c5u!A&GQobp{ChS8vl?Ro(zAY9sO-RhfLq%!p88eZ$NKO5?CnJFv~%`<>iNBCc|q-{{GWCfyQaS7AK}?vcYD_EcRxv5 zKdJvDKbYs`_ty53A2jYw{%_YO<592jB>cXZdP+Rpk@$!l`9I0}d>t?Iw)20h|IGQq zzL>9x$a_x5j)S#l#$);1S9^?i0d44zFbNM{~k?%Pjq<+uc@$2%=wvYU0IWsQS zxAsH1YyL0g&==(&A?56MMaq-E>sNg-o5%?-6u%7rSAC|w^3MM!sDI@O?{SSCxASUx z)z3?QPWh|nyPuPO-CvnM`R*X=EcKdB+z{LDI?w4pIOV*u1Ik68MdJtdf**;LBQ1uf z4=)*e-}%YtnSL@a@IK^+2Mj+aZUtk!-(b1f9_Nqz-!Aw5_#HaWnf^{4_qrUnc5;0`|0?b{ zKgJFA^`^7G$vVzH9zB8bsvze)^5p?Zt8e%}c|i69$45JSKLh^nvx7ea;n6_( zKGqrE59a+@%kdsC<$WI*{rR0ikoxj~;PX8l-jDAq!mG(EiQ)Z%@_+cruW#oh?ul`Z z3UUw7bCrm^@C7UXhuqxrV^#Ra1Cf{ee~v5Y`2*gM`S%_m^2tAVkI(P@!sD60@=4l_ z=d8R>`VxA-58jV^ew;tU>w)^$MD4(M2p^LEM9+Qjpvn)*`>`wJUS-mZJKz1y`@a7E zA3RrhK<0)0k@F+}hh6e}Sn!hkJ{JFP;P(KDZ@D)pujqF{!v6(%Pt@~qc}UXe(Q~r* z#o!xEpZTNmNZLQ+43CBU@W<;eW$F>QBs%Nf`;PA9#g~J3J}pCB}Qj|EU+wFSL6`>#^^!{v))0c$ms#`E%Ox z%IZ$T^%9?u+jt@mfWMP2?)N-;Za2=%{}1R-5SC%m6=AaXT++Rv4~&}Zgt z;y%yJqy8W=-`d6NsJ%Yot#WTDb|0iX{!xCVY34QMMAq-#zi|IVzwD!?oQz}2gMH~g zT)&S!i?loKENT7P^-_OlJ=1T&^K<^ss2!Z!+x2N2s(!7P z@k~9$K7#52{WI_SDRvm%PgFkJt6tW5>b#`C%ujf~VBX91p5OKTKjfSIApR=fCn9%v z#GMBW-{^ff?ACa+qvOTid@jF(zn$$7KZ+gfNIZIt|6?6-J|`a~zsEfpc|O`?gwe1t(9({O;+L1C#?i++3ax zoY&<2v`2r>4!$aB=1pFU`6r)yfbxvKSL}UAed(+<^`r!VgddYjY*ta}g z-n$MDnD=-^&ij;OeIP%E6D>&;I`K&PQ>N zOnG=e7~YZZZoosTPk18aljp+z(Kje>(EESx7v$s0hwSf%hW7|wtv{|ewpSkHy8X33 zc^dqx_d2ade~zQ=?rHVzxWYSToFZ|G=b-klKEnSI=h0^nJ&{H(F!L3p9rG=RJ(3nP zAIeESad=|-xkCMBM`_gN^FwcwfeXOIlx8goN)-~kk{d?^odbrk8^aW12 zv{UV9>W_72>W_G#zJlm2`a=KJqxM+7Pe1+g?yq0o+Y#B1(JuS@9qr%qK9L!}3F2Av zeEU+`cnZHq{0z^x^MP0Q@8qlG3%%!u#+&YQ_$>0}_xAB5|1lyz`V79t6Q0LgJ~Ze5 zohM*lOuZoI7}D$$<~_hX54OFP=Q!)%=W`s7$J6_v+GEd!_)+)i;TO7J&2#;Y=k5oK z*kkIgNW1#iirBAm1Xuqio>&jR)b8oe^Sk!1Jgc0vtGx5v-}2>IR$hhpNG&BRd|gm|`aJW5p43C@F>fo+m$bkCNu0^KedYByKN?@= z{{iTCO<%={)N_2ZUF7q=3GJMp+x{av4u2h9&2spec3#wv+RpwQ`=o!-bL!;(ltVqr zqlE8J?zFe|v-)@M|6R#NJV8FO<5oZFiT>$VEMKGj=|}j_OvlfXA54C6y&ptBv;&3@ znaH?3zg{DDW%*#wcO@P5c2{+)BB_8#8F|Fd!aF@ML#8+avt z_pit<(fh*T0a=%wZ{Ab&9Oit>{}E42m-q9%?C^an|CjQ{AIBq~OTVVqcop91e81qa zUaM#LFL+q6_y0(9exAp&Y5B4gbD9_jQI{uko{?Ye;;p4d9m-~S0?*b;D_Tc@3-Y@&>G5_2*+PwDgZI|#%D`xRF{Lp$>v#5vvf z(Rm-(cCj1yD&}+YI@+t{eQ(%%knH;=|M%{QuJC`(gZKY8{?H?Fr|<9bp7b~O zG<+PVv)uEOr(;~y37%fM|#g0dvhHk9$9}qAMJd|`TfhCcL~pjJbAx6{4VoS zzC`<4)AUDvakV%0wdes}3O$itQT{G^MK90s;!%sfs+9_1IqV+AvxXWpyxocUIN`Vr;vJK`<*^zZXkztKPP_PP53>a#y+ zzIrAd9uWDkt6+JxYyJdk!QLEa$qt^B!{s-Mt5 z`9bxEeN25iZsrR+fagL#q|u{xw<3CVz9(AG@?YNTl^3Kv_Nk)x-m^{4ZN2B|AD{revJIxMgbyhrUNpK)4G zy=WKgbCvge{%8Dr4}krV-}OMg@ObQpNIyo~W&e=+Ap4jV(Ib3<`O*JAFEhQ4AG>kC zF3;q-TmQ&;aQ!_X%J(_@63=}i=K#(ZLG8@)*XPZ(J>_Zpq{H)z#1Wnok45%-q*ufr zJSV@5d%dJnpZH2ULHwR{5Wlv6k$mO9jx&sBjVr8g>dE}*2_!%IpL(BqqMY&4erJ8; zG>!Z`fA>S0b(VJIXnCB~A$Bo$cng83%pVQbo`dtyb z&3PE~x%LF_=J-hy=NON;w;zAh4|o5JKTcE*`)5DGxvJQHdv0gmwFB*W=kLm&Xos(* zdr!>v%FCB$V*b)j`N7#g@=+eU0=-v4J<}lN@z;s*s~zz>+qvTXwD0vCEw4vA|M~VO zM=#%=>X%nHN4f@ ze&;9iR8*eW&B`;N=Q;j$yp0F(*VR8AkNz$1haAQ);)(A^n_mB~Lpl0A%e}^J<1c!^ zj+l4!qg+#ev}3;dD_elyub1&9 zUmj}mf8kStu{YD+w?mJ~Hy$PKVDIeD(6jff*LXr4h5tJv_RRc&%%|)38Tb0mlk14< znDuR^aaDiOA2KhX_1Wi4{?BsZUCPHe|L}jF&#@2groeFKQTIUngy>3z3&HqmG1-d9x&E3Amhw;YAKK0 zB0Q;SzgNP&M9-!2PORUiCmI(xzcH`52gtdT-%l(Ls2!I73lA7xkndOX9x}Wk?>`gA zkSBxbNw3$k8@4+4!B^Sxld<6->rJa2j8 zn*GZkvA;1LzG&r_!dp?!d4$JOe?`W-@_*bbL?7__oD;%tfX21*ajyS)FZ1i$Iz@Zt zhnJuH-@3lo{>q2sJ2iQa9NyLQN_dya->E;&H^g1-itmcpPtx`yPjziy%!@ok`;`r(Enu`FUQs_Y_QSTn@@Yga!YWfcRbIy&t|^z z{$k$yh5w_!iR$Mu@3%f@UxGe^?59a*zb_y1694CT)I0nua_;v&!vlp!0+D*XKZc#m zeA@9GGST++H}cVY&wVp(ef!bBavyE|e-H75=lH$l!uxry#g1t=Nc^yW!L|)S=XFJGAKI;OQ zbkX@|ACFydzMg)gpTu9pE5F09%+I~y;2tlg|E=xT595zJ^1cxKq<(5V$@hic-uxJU zsD0}niAS%s?|Ju%A7tNNKUdGlVf$x{eCT`fh0K@lPl}GubDrZ$Kk|ZQ9u@4n^jTbnN&wjQ!7Yo=?ihT(_5gJjdf7)Wg2yRo44{t z!20%+{y5*VnkWb3vVC#3tG;G@vHjJL^eg>~`O*$V*N@I$=1aT2)>nBa$2ae}+1|WA zBag*+qo?qG!F_yd`+NK{t=^Pxjq7v%)lcoJc0b3NxHIDsdL;gU(I0+wZI98zI#2sJ zIOp4*{LZ8MsVNu!IP<=?$2ilk_OsUG`Q&Y|8+o0T|HHoE`-0S)d?5A02Zk3~@rxhY zr9ax~`@hDW+Jo_;Jeuoy_W|pEKz*`5Fb=t1H(qGB*gtmn2$@&pU_Rl!D3`Q$wED}w zo@M^&ca{HozV-XW1=dIB>5S$3!Yl3kANH1egN;KoF0mh<{2%*q-a}>I&F{{^A2MIa z<9p!T`!i1XzN+5`X8m60b>;u4Pd|x^;s4mjGd}nK%CDcGN9Vm1U#VVy+7u~ z@AjHT&+r&$9+0?5zWf;WPa6NAJ@oFqzv71@pXb5Uhd(1<`#hs@th^X@!~9VXUQOO@ z=l|dfIp@G9QchlxbiPxpKJ*9T{Vspx3Px_R?@RNXeWUW25AWdb!l6Ij_cT6E{?GGr z?NPZpPUUl-PrP2`RZpx-DTjT2f8*`m9(>tfkA6S=@OyvZ1;4rTfZzVW`%w-a5T1{F zef}Px-~XLy^W_2IL!OWF^v8FB>5nwu_cdSM4}T!dz81tTi^Lc5gUr9}!GrNTgKv&> z5dIL}F9_cN|5u~{_v7T%{^iiWznjPIsP7fahvc52@7E$f<@0_myp!eRVem)N;a!5* z75h}i75;A`JTqw!zTLET@~?L}dC&Kn|6_c9|3g%d^By32MXuZjWWL~C^4>Mi7d?+<%YUzwkEzR(}fW5>bF&zu+LkN>C7dCa`hKlZ|Y zndhc=%<~=VFZAnpR(=UN)Vu5aJikVdSBQMp3y-?;d+d{}_i4zuD9?HdvYv{btHTcv z&s;1|A)_hBS+#~5PjKCc)BZj9iQ!GT-R}zeLUrOk7wuq z;@3MGCqCTQhmRZX_lEV)#EszeOWIF<@cOy&1AVbmo_1}#u^sg@{TzK<@sRan`8Mqo zd$>;P-`dejzjI*xpdEI!+J`*g%lx16w13BAfAD~$%d_ZrE8oZS`lIFbgU9}M^&C6% zd>-CO-aP(#g_OrHf}FES2g#rOVEH`cY(LG{@0#Arnf5$SKa(eu_dy?y^1JFGJYI0>$G9`~7kgEIj{A|lP5B~!F!P9>)t^YddYk;6`cM9x|GmBI z`pPLU6dtfV-Q@eIpWg)x$`|#$;hARL2~V`Q@B6)sgE$amUX2Tx_sOFX_a3eL>T~|T zq4pZP)!yZ~_+752V}B{n7ygNO^K|oL`6$xv8%T5CPP@>LSa(SWGw?8ai=Wh8qzx%;DO&a|;e`kcJ()sZ{+^J{wx8VhuUw`L=c32PO{fgnq z9wGPWs28-Iwy&MG|JYN|bF%y-_j?!z=X~1X9v-|3`9bUqzU<@S_3)(rj-mcQJa_y> z<&kIP`A?4BICdh!_qCt3U-O+$?TzQAX`g#o*xCMnDCWWb*Lh9cWqz?Y(Rpln+JlG7 zeLUVDg$Kkwd5;(So8S9o{}12C{(}2{JYV_0H^+S^@`Lao&-Zpf?$50#ZwUXyeZKI2 zBGE;@Po!P=K;$4FIp7aTfBOUP_qSVofcIm(zx@HZ$A;Y8SL1gJy_X0eNfJQ z_M5c#!;&AgJ>-)&Ko8Ud8OP3VFb>ZP`@OsHFzfIAQQq}Kg!f?GVt(8wWM7tjTKPK9 zHx_eUK+aTuO2eBW*_%s=s0_3wPp-%KM9 z>Ew&{H_y|o_tt}lU>qWHoA%xr`v>JPpZhG-L!T3|OVj1++>d6T65dx#`Ji!ucp+aG zKoL1|uW#~w$qy0-KaKxmf8so?yk+u{ z-{;&{!XLoO&x%Jn`0}{W*W?wf7hZyW5aZ=MkNju;kLSJ*e8umv-#`xb4_Ku8V$<*l z+28MIJWaplVet$0{lW5n=mCA92l+1F|Ir?7Z{_{)Q^tdRuut;5t3J#7?P=Oud5EO( zZ^ywo!S=-U{|3Y%{X6f;)UTDZ=MdXl&-26;<3X_fsh5>cOMJ=y7w{{~WxsC!__6sb z5Nj?HS*Y+j=XXhu+Mee5La?%O}nz9vh#XKm3t- zG%kl<%zeIrloR!r_!r{~-yYPy zv7e4ZJxo8f|5+b@YPcLX>-RKrUe(+4k@q8lvMvr26zUX`6`@<`U2i`xVJma7r5j$cW##?dn zJC=(+BlgsC@-t1#wCm$XCm_EI|}9hoaaaD>Fe>wI5x{+H{oZDH>|JnEXJ3dx9|h)bn<=d6PnMw^<1VM ztZBy8`8LkUSK$}7&;9|w&<;W#J43-LY<_2mET-}%JA(k@%|w55dM$n&I`XANc-}&#Lb-tq3B(9JK!}sl|of5yohl%PL{W~Aw z_3$I~&OA-D9P!EhHT>SYTfFK$`StfC!q?GG?gugtLG4F}`9k%S_KzUr}?{)sqaeKcGeLWp=s5kVm#!=GhhjPaKy!XpEsQ2y|H+B?c zw?+Dxu!GOSuK3+I$B&)Gp0vO6kLa7Y>OA%SU&=p1#uNEL?2h+wi{br5?9=c3u87^q z5BlCO_2mJ>`vu`aRz8v63B<1R9bun`CxqXVKNQ)&@?J6gU%xX{Q1Fa{_U_I71TT_0AyFZ>_nd5*ogUgTWW^OpN~)2ut37tZ{n-=(HMpNB^VwGZYS zJt}v2nk!VlmiNAu{p#O4|0kaSKc%00o;lwqwBPW5@HV!$%OgMTebCyE^T9ce`2d~A zYyOY*%lVe?BmR{CbDhm|+N1oGkGQEG!_T32<@NkD-@jE~bDnbE40`TV?!8>~h25mz zymu<{|0~Mn-pV|W)82j#$3C>X;L88O(N@8uTd1(eJAS?z`W{>*2;PFkd&mG9fr z?3d-mCOSUbo&1RHg&)|_eKX%FU_FGN6WM=|X1_uILG}mCDErx&pXctEy`RB&u=DUB z;wq2hUU^aW=QAI_bH2`e(>$k9k2L)j)eG{Ww=*(N?(GvkN$u*QePlOXlJ{pTb3GwG zJ71AcBwu~3<4C*>&iFz*y!ShCw}<#U^Q_!o+~Ni0+z))b#SM5V;s@sh)-w_PPJU2( zF|MS&8Bh8={jUD4JtrPGAKtf(-BVsYT=R=-dux2z{Wa|r6W6qF%46q6ZSaj_Tc-W+!xfIgQ?&4@o#uP?nl8J$s0$G%)jd>^I<#)vY+6D$3DW} z{WU(KXZ8zMh~2mk$$o5IM^^vV?r5j)yW=Ep>&rg2s-7Ss1hR?e~{2m@q^!Ee#oj`d+ z@a@6Jk)Pii3_lqD4}HiF<{qK^pM2li{^b3*|99s981HY6aWP)r3s%qn`~%Y7R|g+a zgy)ox;C`U`m-c5dVVJk&NOyMns_Gv=ljIG zhpK+d3sH`E1g^gych;xxE&G2H#+mz!z2_wFhWzYHgXRCexvdM>o9l=7{le2Qf8+*oXOLKFXS9X94lInbnXQb2j+PV zy(;I``ObLg^YA_8iyoo@hVg2(ten-~a1^ z_+$5J*|)pDJ@bO>Q>btJ^c==`+;3Ok;RS;F!^(%&&*FE+SJo5#h4Vr7-JWNV3x5>P z{GaCq&yAip)XQ2g^~?WJ58lXecy3@Gl|R_{Z+`vQ^n9+pXTO>8%=keZBR}zLk7vaR zxJOfTeq%3=!~X*?@8S7~Bc@lx59I&IUwOVgt>56U@u$^)Ders*{TEF%obI;?(3+-z1lkxlF8ZT`p@zeQx z?9Yxj<4zo?-{?p3b=ZsXBD_}ko~HNm(_hgmY0!4gnCG(|{c_F@;!pBZLHRw}^*ogF z@>tlH^@BOb2R+ZTUfXWY+bjQve!{zf^J$uU zf6jyV!%QPjc)#2Oq&)o;i6gYj`ak8e{mAEd%m0Nx182O+zG0$qEAc6q_@!SG$Jke& z=a2HtquBM?^#Z$RojIfHu6{A&kK-+WXnOhu?`y)p$nz=JIj!94#W;W*&cA#d>!A8G z9%WtqA+OGNRN94_#|MxB=wp)berdZt4}Te6Etq?ESLpik-Qn+y z=eygwfgQ6>6y^WsJwW#lob&R3gz#|0C{C`5e zC+I!V-WTM2mvZ_&yaDk^dzr{MbFRKd&V|bDxiLH{h`v{QrM=992yf&({^9}7dx4G< z{*SmxJ=UopdSKmUJfhEYPW2o}9Cuwt?(l#;KX*JlXC1YiyczTAymyMn zKYZFjgWt9;jb zo@M^J|JNRR-X@JFPsE}~PozIIsoku+ACcewMa~DLuMs~*-XMB=slD_Y{x9{4%(UwO z{aP+O-y>u{9iCxD^Rs^s&-Vx^hrZ`|fbli0{@u5`kLUbjJk7no^FGbz@=Klz^!J`) zNqcT&e$Br+pJ*qZ1Huz}?!@l)_Ike1?>$#|j^y0rx-t1ZrU(-yqM!A?kfMv{~M2;ALGH7_xSb2JwBPHobl@8{rQJm{J<}bKaX(lukl4a zmH%TrlfQFb=6zi4-}Oqq4|_eQQ%=A393$U|yjSgB=j)GWUeJ8{UE`x^=9T=$CC_V= zhu5Tk;@p)Sj>mYX9q&Ah{!ToPo$D`G`TF%$JItp%0rftuoPNLZXUL&nKjPPBdGA9t zPB7no7p~~<#IQcX2jEu|v2)UoFuY&zEZ@rWG4IMBes6t_o)Wi$@)U`W@LSkfcrJM> z=21RD{*QL#4JKMI=g;07R52Sv1 zJLL=icSiQl@OmKk#vE7iy1w_t;32JVI_s?Vf*jS4^A3*zpVM{UIF|iE+RQ~jOvv|seL+AHgx z^IT-!hy%`_`S`!{yZ^sn<^O08{j=WY{$BY%e9{GU9XydLxEJQX?T$qP=D*JFL-IsW?^h7a7)`J=u(ApNs{+EIPk5C4bs{HfgB z&!Am+Iq&7c*AdUPXYEY>k8*iG7qp!s&#{-_&i|Ruy+6vKXYU`%`z39A-UFmx@BP6a z<8P!LZ}~sR2T#a*>dZIx6T8HIv@7ei9oDnF#|!ct-cOWI`})S$!7q`9hu}HiC;7{P z{I1+z?%&NV@5ebL-wnxkg1dBM+`6eIj zAt(6pI4vO;^Md^7$@h#oM^C;JUhMfUFNl0ehYyr5^mhy4cY2Qy|1a;yKGZbhn&nJ~ z|Kpw{So%F@-*m|^SSfXbG?3U+VgvP19$@JiSTBm zLHEgd4;r-HiNr_u;hx_;w;LzPXP>m9d{6j4{MP5zPx;&c=epnD=W~7Vy-enhba+4b4AP+M(mda(Px|4x{dunedE7U1FH;`Ib3=Ha$#WQ| z^1h?voaZp-({qsZ@#CJu^n1?##1nYo70Ks3W!!N8KKDl*N89at$+gScDgNL2XP(#j zNm@Qgd#T+SFX5-;J7XuVN3@GQsjqo1MGtu|*mE=YR~XN0{2%gUe$->$6Bl`&`9c5a z0c8C~p7}m%=PC2%{8%q~@ZMec)9`=ce`kN|ymo#oNBph*M86aD*Z8%39)3hVe&qA= zaZNk_%m?cQ`HX)e^Jw|Bv*LWN+~E_0YkRhzew}aP)r=$dN1Q>R$c(VH~z8@L$C9EuAa@Gyd(Z;I_CtD@@Xgg_?&~=uIohjz7^TWD-WoD zTHf`6xIua%<03r~KQJz>*#Bc(^MCY@o#Nlxum4v{e4!uh7}U>5(_c_Om5`$v3XZ2NFlF z(zK&~g7SpM9qk$UNIQQkpEr3q$6?%|JoB;t-@>?+_E@i3pY^9RI!^nQ_ds6t`BJ^M zcjfH9pV z>Q~Nh*7@DfXFNg9mUF(!@7d1!|2EFK=7XGrc#gdCFW9L(&)ILz{zL!zF?PdzI)=XG_j=!tbptlq&v{>#^Pc_ieOC5G=Cf}w?YWkHjd4Y! zKlNid_8XK3<@cyZd{+M6|Kq)3<|p?6<>TOy!!tWC#0B|f*IO&KkdA~6G(aDPZ0m}`yTRu{=VE_ z4?XdIDf}4ksd8TreyMz!-zk<4{P{f}{w(E#*ctEpde3n3fAW3oCglIz`;>?8spr}e)&Fll)+_&<2GKi~C)Jm@R(`@ZqdZu}qo5$Tox za~#h{e(nPXx#z?FQvQ$U@_xaU2ShIK3l_OAq`c+%!uP$u$pPOd|CjurJgocl@-mzg z;c3FN%==d5{c_%4gcis<{ACadsj<{cz$0P3L+`zcJ&&RIwQ|NmGJa2H0^#9n%#rmn7o*$6I zw0s-(;kgAqOFJrJ-{E1!@IQ}`b;a}A88a^Ip5N8&`01ziq&%KqTa^b*mB--h{$LCqV3{ej03-;d~iSi6DKIQBl~#re+(k8 z`)$twbN_BUmJbNewWzU3?*zHB0KjdJ38kC}GKe}t|( zS$~3zcl|$J$`OxfFUUAaPgLH>&G=lO$fq1gyb@h+%5$!~ALktV3;)MD5c!-J;{*5m zOdCha^O0sA#Sb^+Txf|;*3uslS!yKtJR&K5_CM#vSCs@6M>-m*3md#zp7X{}b%Lckqb+Q~u}$`65^3 z1bL2K2Z?goe=sic*ZoPxnQ_}s+fV*pF6m&(y@dE}e%Cj+$0PiJ_z}dejVEXRk9_>_ zB}_aju6!kWw0+~+&j0Pt8L#DuXV?+ES`hmy&qn-%m&tSZ2%ZT2B6zxJw#)xW@UOui$`?)8=DGcJYCm2W8TSNn5b zV^{N@7yM4s+D&;r=e;~&(vH*lD6dDFc@QW6H}idtAJQ)8q$2Hx2XtL#pRGLXC+MI4 zl*9j9?tXWjW`5*_;bZLAc`wh;yy5rG-^vfN9#WpTVLiU|H7-szmeJBKwn_|3gmrzo5L3@8=TNla^;Q4PQVyydV5v%6aaV z_amP)`c;0B^&sUyc!!|v5RbVZbLRh?C*v=1g7Vl+P&s){{g#{c{QrYIAp3cLH&0|g z!2P(1@PDL5?#qP-%zZ%kLHvs}ze5*U`!@$Z9r?dK5MGkB_xZ?wcgRIKR!iI?v8 z!+XG=(r@_4GrCXk`@fWP9RWW(?8n~)e0SKr@v{3i(%5m(_-vZ@T+PqA;yI3W#{R^d zcR=^i>MP&NUG=43qA&SB{DSiMjps4icYeJ`89os-j&csv??re#>?HT-h{LV}Mc2{p z!<|QX0PM(fi}K4)nIAjTF66Pon+1ud%n$b{vA?HVn)=Q! zoP(oRvG)Y6zv>IQ$cLxbZn%HTc*XGa!D(-vE8+c|4|o~osi?i^@7m|e_w#)Bum3;( zZ`Cj3_}MMaT;cOEPIwFO5f6x-l|N{E%n$Ww_a$V0s1Ksoq^WPaFC+foe2DB%NsH*4 z^S6jSvCk|fpM4y>AM$d}$KK%wg6@-jE{_M#H`AP}v=dQ2P`-&B&WZj<+{GlJ7bbg`l zyr1RSXH(DpHT<9RGxzn(uj%r8q_M||*vCv$&$!J#)p<3|`Pj7WdTvNRt;c>0I|+LJ zOF8?a9eKRS6FKk);(gF_1@&O^py z;uY4M`23T5oceO0_TcZ@zz3Sf--r{&C;7qnEp~vP2PvmM&-|bNU(5Z)AIJaEE_zr| z`LwU;hsHhE>+qsi_nq}ybM z-sq|8we^^P>S+heul2*f<~uLB|Jixyyx6by9DBL0Py5z8KeylfAF=5Ej&rR071PE6 z?Amy<{@{_z~rHJja*t8fX6D%&%xaGu|;i(v5fWeWtMw;+;H#@-?2a-=)6$ z-tdC(TiTQ7(U~S+o@nxj;fH4Xk>?6oAM*c}DSyV{_~gCu7xgcn$GS%vdj*pY;@7i0 z{m*u<=kjskjb7&eXy5x`@_Oi{_xZGonMUs3 zCsW^(|KoZ2KjTQ|U49Hbm>)dbqtCr(haEm0^8zLxB(2>z5Bqwr{b~pLwf2$y!hDXM za~|`41m#v9FzGyZK05!(;rPz}w%S4c#C?YUH)Q>n2ZYbFKlF$kXa0};@P0XWeswQ* z&Ht@-gg(QkyKiCLR?hr?bfWVdc}4#pVLj)g{<@~i`*EIRo`Re=nFrDLYCUJNUzeXF z{db3S+=Kb@uvYd5@^|nTv?q^2JeDUb`n?S9g;*}nt;ac+{GxJ)|0`0DI351a`+d3p zm-m5vp7(%>FVh{FM88LF_X3`F?%ybsvw}{QZHyJbM4{2NKWW|M1W6-u&?<@An5H=dTV#zF*$b z@P2>1`P<(gh@QSWka?h7(&!6bF#Ml-ga@QP_Xv5P+4qngKfKZ8|Bzq)FW*TKd9V2S zChxbm{Uq<>@|}^7$GF{R=63|;ALJp}O~LEgKj$>`SAHdF1`1E%eLr|W#;0F!kIDL} z=e~9FE8+b__dPi;$dk<9AN2Xo_sz6%t?e+6oHy8q(;o7`Zv>gA^;`mPg`7do6Qt$) z*p<>$exH%Jk6nQB?x68lzoI|m@{H@o*YJYn z|6E79{?IRSgE{Zyywu-YpZeE7(U<&R^obnV$ErWidFqGx|9IFLaSr<}Vjr9zjWg_L zSw}rLpba*fH7JGi3|D!$Uf439zZFjYwoI{J< zrz_XgFYWifpZ>AiQ~CPmV;sm|)ZR^p2m9#}2b?G4fxjD&dhm*r57NK&gZq8K@P_iE z=m9xF&!;Icz( z#&5akO+E3P{ETBqo-4oiDv?9^y|;tiI$!0}dVWX$p65B|lD{JU774Z&l@>^2h)GjpzBHAPxjo8{gRL0PsGlNyFtob z$0hSwcX-ZvA%^D@kw-fW8ZTWB=->EQ%(@{`-~OB5_PXAr+>VTc`eN4qpz&4SBs^f& z4>3Gp)#=tJ2wm4{-#Ftri1zk0`}~<7e-7%G$RY0+ zOg{52{};rM>A(D-JfnKZIFw(zP(SF`bmm)R{u~d8{6*st=R?ow+Oc*K`v}rb>}AEy zTjtMp!Xvi5EBSW+XB}l;g4nn5PQDL+X1^H3|4HLNl$&uyUW0t}=5xkjxicSOzHt-2 z<~m)TL^;am^_>57^f&+iLI2@1%3sOyKzKg#pz z4~)O-Q|x)i+9CdH{pwf!y~GE)4mzGQ56C!>V@35y9Nqao$GzT9XMC$ZtcRV*Gw!&) zS4@3*rXPps)B8c-oL9!PkK4GCeC(C|*2?R#4!b{?$UY37sP_ZWzx}EIeLb%IPCL*( zVkbq`U)!1Jd8K^4>(y)zy;Y9Nll{e&f8jrzbK!;fJ}~o^^CRaz=d1SsO`p$`GyhzF zoo~iXc~SpT@7ghThFvF4t?@;9(LeIeIAgiJJ$Mq@70c^!o@5^+FV}p^u?|fnep{Y> z<+~%U`G0u!FUnJ-9{EA!v0RaJfP5A8kS_>d$o~;J5Bq;opLZRxUHCrk!*CCgxZHby zJm>$m@*|F$c{RUCeR)Cn81lvNenI5Sd*u@yS9!pu;p@l`GH%+xZbv!h{Xo7O^638H zxj*$tdGy9}@B8I@9i-v?4si~9o_rX5oN4dJalR#u{hALCXnWlEeDweMF+TQ_j2nD+PxBtF`&D>A z#=-ry@PEqfzEd86@ifhP1|Jp-4;VDg;ScaYl!HfXeaFdj?92QeXMfH+`=iP0u>X=L z^gb7U&Al$lu@3_EL-b&peG&OV^W_DVbG;A7{s{Rfr@lnwART^b$M8E7-B0>m4)|8q z0r*zpAN(Tg0CwxTyYAQUbK-5{IoNW_?|LH-h`hGv{SVr8pW*q3=gI@R4#}taUN8P0 z{tvxykGqIIc#hwA4nrQ&`JT$k8yi=QfBc`_buH*Rk^h@!Kg9ZB`_x_v$h?QoS`nVh zdGp>g_ng(!`Tn!*@qYvQ^Zy6=ebHcevK6^MgdB_uWE`J@dwJ}QdLZM#FTwDCtdpc! z&&8xyWPiYO+6R%Rs6I$DPB8kz-%XeQL!QVP%=oZx15pM}2*?tI^# zPPx6l{2u+w+jTs|=_~$^{`+3A@tpgBl%KzE=(s%xd%i+%#uMU&<0x96xJokDr2(hqz+-#OamqqdfLQdDb1)E!RKqeLdp;ki&At$faMpE*cLQci;DYzRCH; zEskIpFQE}K#zZUtUAF=$J>6QOO&(#xg8$0xz zV*A=9<0LR@rREFzyg2!5q}?Vo)w&x_a}Y3C_e zKEmh3W6GUTzn%Ty7s@-|6Sv>w*FMOPUxBgj;BL>P>u2tB^Zy+B#b3|kuAcQb$AKR0 zr>H!RC+kkv75FmR_xzA`Eak*~Ua>p-pZB;JM|i=>&#EW+q&ZLOxxCR@F8P_iqT>zE zSHvG_|E!Ol2h6?y><9Me@=LJ~$CdG3A@-quYnN-f{-(X?kGYSJ|Cyij+H5cWu#d~} zGSBP>gUloTkG}Z7I%(E_^%u=9USCys}&6XpBh zx8(KY2g~>E{NG-leL#3Wzl&=>?3)~q>m&OJ#s%+Jl<$)l3GWxod%)h~>+kXP{oZ4O zHvTWXp!fgifAV)vhn}<-^YgqI-cMA{e?RWSt=|cT$AYhuXXL&g{do@%9>eci$m^MJ z`Sg=^LE;K>A*bJukgtQ^V?P1^7sTHEZby*&Q}ARU_xZ4Y@A>`WKCg+f6g=Rf7~B=9$-I2T2!y@ui#~fW8Q0GJ!4$xz4FoTe(z}=PsWWMP*0voz0wb9 z<;;Bqk$mDMe2?o#)(!lMdiW_wTxa!KzXy_h@0UA%+97TSS!XEcdgK1kbC7ywze4@! zvGGtpRes|i|7VK6ippuZp1*7ly*t1DKgRPX>n;7VA5*UV|EcBwdahMY;wW~-et+c| z8ISYa?@s5v@yY*L-}#4Uww}p`f(q{xn4a@ly9(p&tFZ${}~5;FKeDliIX|+bYI`|l5x~Dyfx{TyWaoP zzU6{*e}7d!=e?Z6_w#hl)xq$7o*S`Wm z=KZenSx;xaY1dow^BjFzuDprzoOzZhSLBS`!K?$ptaqaQ%M0bb&+>aY*V~W$4)duz zMdkNCZsNj3;s9ypS7!c<3+gTR#wHIzdy{9dzl_iEyAFF# zuH{!ggZS)wx1#>J^LqFreps~Jna?*K)qnSLX(#<4m)}DIod>^fggoW_%Kst1^CzOm zIiJkSOh0;_e9--lc5mAG%{h|&EBl%vPDNpLS83&P`e0eV0XZ*BZJ&?|QNALUf`Ktd_f9N~&U)~VDY2|^mQ}`nE z6YM-SpZ4>7qVj1M@_)!FpFH= zZ~V^vvh$nsSN<>6|2J^H@f;+c<<30nSF|ht$2~UZCHoTj6Uxu~Bg)}C$op`vMt?=l zpPmDhKl>cx2koPG{=WbZ_3;)@oPYJfjIYmI&i6#%cUYe(N8G0#`$_F5*!XOH)BL}mG)R5UD@k8t>izA;JHl7MLvo&! z2h6$f^&j-F{x`wbGu;PHa~9-aK1_x-~A z6@5Q8{2%%&4@f)kf5oTU@BI;vzPs^!+>?Xv3-Z1!=^(rt@AL9~k3ZhND-8eV_elEw zFLC&*h4EY)G>X$*s!M#P~llO%8oBZGB z2XDza_p^hS^qd^tPo(_w?fLh&^K1COAo^loA^%_;aGycG<0_&@?i1o~yie>rQC=Pl zIjkoSnD!VKe4z2j_VF9-zDRxY{r&>&dymj|-S75(p!>M>zJlih`(b}Lzw<$P;t1^o ziCf4MBwjh56_qRFD`wn5^hx_c{Lp@L9?Lzv?91fq^f$*(yoGNeZtKTI=81gTH?Gr; zdLkZE-ni_#LpkCyNW4uvW<18)q@8pY!pU|4TpGSNTB3=lkKH_9EZLeN4vpl08|z<6*qvN6{PO3U<8JU!JEO?FxHl zJR{yv?=>?H{x1R&A9ybEd!pLWj?||gkp9K+hU@#Z zjFWg0WW2_iYor|V@8$OT^h-M+$G~>uUkZXk3v)!i~GE(Xj z>DrF%5pUQ2)^y+ZC62#8^cJ)|e>eBtp*PblpY+<^ltX!JkNfHD%e*%jdEo(l-g|?q z+>zh7 zj-rPvL=N(UjMs9>&;NnUXB_B*^6D$RUr_!JIV`vHL-Kz3rTvzdS8n|jdom7mKY_h- zPR1`LkMn$!XN?Oy#~=LtK*yiB0wSMi|Hza6BbV~aM<9>mm1l^($G&P;EqAW3KXFdM zf6MzNUw_4}@XPvP(!uzt<4|7oY#b@B{!70fkCy-C?H}L#<<0**%K!4%eaip6Kk{j3 z<~zu|IsY$X%F~|pZ8vsc zKaOMiQ|vt$y9bFgL7p3Th-ir4a(?NL^}+skT;pf# zG#L90(!Tp$?A-aW-NxxDf9eHo*Lv~`_=EQ2IM#STf7;O%p6!|S9XrxLv={C19CxBO z8DeDs` z@Aq^||LyjEFzc%K1LgIIrA&-RWy*yQly{bAG{5{J{9pM@_&WF$-p7Sk>vwgrNBJTrUp@|L6Jl zcQ@qTpXXhX@}z_LzOtx(J-6{YVM*h+@DilI-jLrHRIi@rel_YbZ}5NE)w~C&KFDXB z&o_BEZ^w_cZ}X|Ieu~In-p_q7<(kj^rSLWQA9{6P~l>2*; z@-^xwdJ?TCzatOIycrMi1LAy;eAk5vaS1^3@eU_ATzO}(Nw+nMisGe7MoJYeFV`!&`T?%$#Z*Bi#cdDV4yO~$9`(ZvNGB4Vd$az$Iy5{>R|9l%C{1mHKe!oE8 zir>u&F9)K(mB$OuXPiSHjThQ|{(oRT|5rdSe|L`~wuhXwi(lA}{ZfuJIC-``ja=c~ zj4$iGJlZu5IWF`@yV&K#j5ml}v>T)y`&s3g{YMV#g;&gd$-FNtA_sC6<^Sl9dBMIx z_9@QedhTMsHuKpplO{j)W;;AL4Z1Hay3Zq?vcI=nc!b;s%(*}P%Kym&5{K9OcD7@C z;m_KB`Vs$n#9#JJ;q^X+|6_mdeyKRev&(ax_8drjr@bP2JoBFT7y0-julO-yE{)<9?*8ZAISJk zM~*W(?{mFDPis2k7S*@)dd{aG{Mr6;&#!#j%tx*@9vDApAAfFKNPM_P+M)c!wcW&- zRSx}vex}`<);?B#kM_w&u4}A+gs&+YFOp_G<-CRe;pg$g`ltPS4dB zKm7rHq#ye~%cEZKTl)_WSWNzkt*5<_p89k@y~YFV(Q=}CjXtgKyvv)hzGb}&PX3Sn z=DJAw%>UVb_&fLt)^+)VdGC+&;Y>dr{=xmF6*(7CuKcL&o%0>fln?uI9P(=TiQ^UV zr$uJL z{D?mG^yL3|-us`9yZ(Q}h zAN&h{EB^dx9{EZ-m1U1$M5WE&;9-e`(F4t`8=NIo*(bSdM;k^vs-z}`Q9(QA@#+h zfm^>p^85XdzW=Knrhj(ufBHe6%UhKHlV6x}Rw=s4|< z^SSBgyMBu2eB!X{th@?w#k4#i{9m5Wc$585a6gx{owVnB%h(s~fyyQChyAVT@`J4R z-g|WZmB)KyJ*Op3me+C}F%BngU!!_4j_+|g>y`W;{G{v8R3N`AFU|w$M}e&(M#}pJnQ(*{Gaa&6Gt5P zAhOZV>i?bhKDL|Wq*IZ>Cx{Oq3@UZKYlmB zdc*_%-&bVbQ75Pn!14_q#>JFXPaP}xoOD|hde{3<=o?W$N9e6pW`>io!}$hY z8h^KdeEdAfd^SEfzw>#@wY@dIkgxuNFY$rIANd93)$VfNEqus&9%Fpy2`s;-zc#Hu zC*AWG{>gj=9k+U4c{j$DaY(Ta!f>Dd-+xG z(SPrY6X)0`JshG^zptff!_0Ry_h^8?S)5N?X7;c@_+b+e%^haaV&gB z?&~D3y^j0&-}V~!?C;D&J73tJ^Ai4;`a2KEcx?9(w!gjqt2Faq|FQR-Z)@85W*yO9 zvVInm{|K`_1#5TptJr<}Rc}d8KF)R~?}tA-5A&Xw0s(#VdZd~vz^&)%Kcx`&ZXCud9pryk;W=k?b4rXGHZ z@57W2|6qLK0Xq-I73zsE@JDZN@}191z~dk<`&{MT`MuWXdXZ@B?+3F^TVKBKdfcwN z@Qe6Qen*TvSwCW(w_WzBqq!S%E}>+hhId_cSnD;BkxyKUhnUDojHE=%6h=LK(I*Xid6w{{pO?TM*>j2Rz(r9Se#a>n8R7{l|C&+|VYM!t-gz=6B)u!vD$hp$F_AJ7a%>-JSg*ejZ*?JM4X2$B%-J`}wXPv3%NEKl2Em zZ+t;6`9Jdkue+aH^8(`x@iF|X8~VWhnNRoo;h{k1MZV8-aqxGXd!|3m zL8B+*)5`N<=fstu@ddvpz68}P@rHGmdh+KL{W;}{jEnMleAIt- zs|RT}h<_Qc{C=7Dhm_INMCOh1j=68IM-SW&D(8xw2YEuj1EAmJ?akMpZ~Z2Zo9I5w zJdHemEvtu*@8gbM@;$Tl>_fdTdEJ^PCf{S9Z2Sa?yYqY8l+CNSkLQ$oephUM5MGXU z*jHcS%k8J1BKy_0L%f(}$+aj5A{LhHBMfyulOI=gI$Mx4t?5BQMt^Ucm9w5ye>Kp=2f1s<67^_ zbIjx3pYl_$eY9LVi(T@(b_v?A_MG=0*L)w(dEYfph#uN5{idJEPv{?xzr0<_)9&#X z@(=Py=f8Z&)Gy;=zanpF-o&{J@~iMS6Y+QV2h0!q2hjLJyU4w^U;g7PXPygUSNu;< zka+UyUjEZtKbDCr-pBbe?hiU1_2fJ^E?kw-lk=VT39;wsKj%6p???NO=CSAdT#w$} z)+PFxW#pusdNAt)$aS&nlk37RN8Xcb|8xJPJ*@Ep|FAysWXJGQiDyNh>vhYCvm*Q+ z^C7w(U>~eASNGR16OXR_HuvEtkwbf$ap2niocF|+)gI9M^IhK`UN4=Oxjw@)`P|um zcY9Ob)gSPej3@dreqWv2bG;>h#t*q4`StUxbF(bJ-20S&me2jCoyfJ$FLoI@uTXiE zYmS5GSa;cn1XmvK%x|8rGj4c3;tuPZwN}`skm1qw7}po9bEq zkA13k0T05yqWqt7n4g9B%kLiT{2$|h7ef!>{pg?gW&8hlZy&qld=>Kue`5Ko!~UoT z;nTvSalS9SU(Va@{2%LL&-;}3%Q?W@uY6qJ|96@APyaoKLm7L+FVuJZYw~{bgr55= z4;Vf$JfOT1?eJYFc80tie|QObqUcB74Zcr4knd{Io9E{yzlT4s=KyJcKL76aKOOLY z{9iA>Cjycm!|(Atyk3#~)biy0up__s^*ZC^x^hqc&;A`J?GQ)&Kad|DXq+hKdQf}k z`(e&m_PiiGfaBtSi0Mzn-#otCJYC(3`Imy}&U@vpRlKJ+v43fqNmGyZyCdBo?to{RD(l(Fx| z7wnoiQ-l}uIr%)!i&75C1JaK13_i!}*F2#7kNgeq1wKBWqd)#XhxnK{2@*evi^fsE z*Cmb^_v0_}V>vGe9~3^&I3C`QxE((V#=q33>k)jI_3Z26-&ud)qm8S3yq#tB&v=lh zsQvOh^KX5=gEqd;``Q0dc0GiDw2WNgN#Vhwmm>G6x5@k2&dTd?z4bm_tFAs>k*Zg1jJ=P!M z59i*A7jJL(6X&TnzI$DMP2Q1lly95-8U69z0RORG9uWT`K2XoN(8EOHrQ==szwm(g z0pt7-;&=1DDJS(;W%DWdKlEogykF3~Ej(cJxb+;zRX%RqTJtgXmyY+NJIepju6haY z7nCoP|6&{~UqIxLC!inVzI-706#WOucP&r;&;3sF81_N(b3yl;-4C(O(vJCAG4(;O zpW9{KLe932M|0nbX@_}NZZYx(i7PMhf4R?bJm2&&^LL(K^Q&1lu8`O04@IBz`k9}b z^~pb(H{;ER@>QtUq#H zKLqt__!|2w(vLh&?)xw%ZWveSU;i(^w92>JyL<-yx}L+&=_lH!{_se@$fv$|PQN{) z{+srTjyKP<-jYX9-siF9@-LNh$}6u|{s{gLx$^s=uaEZG&tCs8QpN)&{uP}^^_e&` zc^l``>sb%_eYf#H^RmWw#<#8mAKlhZ_zu=l5q-V6txLo|)+dnnf5ds$wfEnm>uz|! z*xh;kbsdOb=68A5bF=2B^e4|2zrqjoC(!vT>Nj3byeseAd7pN${vQ?V0Cpj&f7=V+ zDu3B{uN!#>-S~awRYh8yz_swZ+qvs zw(2o{Ie9$wV?J!IcFD?SIc*{-v8NgoeAQ+pYs}& zC!js^@|?qi2lSk%`q!W20g+q#o!D_OFaLPR!}q#H`ANow{AW~u#2LTCWB&l}p}a-( z^7+$m4|%!%+hbVpFuy(SgYTk@oq_OvUeA3Xt10*Mob|a6ginL_1F=)^5&tL8ryTix zzuz5pV*TrzzR90=zR$AbJoA6pAADdCy~6YDs6EO5_4{Gklkaq#lo=1aKz4xkKgeBw3mAIQ9p~{$@>wnhDn%lvd(|FGZoi2k2$$O_ti(;oMiS22&Bd}zjr{#O1o zWyfth&qrsJjZ2-T-khw*vcuVW9^7i}-R#^jrjYsO3ZU(e@o9l3Vg*QMFc z+Q0D*|0FI3*(XxQPbboj_w}65Y>$2^r~f^U<2Q^KMDDC}!O7=wo#%tD>%7-94m$t) zdaHii*E61To=pGE&sksePwUrpJ>yWn$uFk9$s3G^$Vs~|;c8FjW!SBDu6^nM;bjsh zf_uEkeW2|Wm526_OZ~;4i|RML!sP$-fAteR#?D3JzVj^)5`9yzU9bK^T)|A>ZdQOG7pu9!&ir-G; zdCJAc!Sa4+H}`qHcH}%I&ay6{Z&A5xC+G4!KU%-8e(i=3eLUccPS#Bbykd)}_=nCrUp`uO~-?RLKQ zevmKoC?=j1*?%~W^18F%_^%kbg5(#B(=z!8{^=?~=`bJdcVVeXjhQ zdDQ+~c|OlKh4+}xA>S;U7nz5J_X54|5&Apo_zm|l&yKt3z6zcQehNEQAKtgm_gu&E zSFa}z%6Sp*|sHv-iI~^h{jV4n@{! z${_c-{|{dAe)5m(hv=XEhq%sj-Ya{4hx`irgl{UM|DWFG=}(VyX`Z9Y_rUOa;r)W1 z2kbdK`i0*M(%$5I%`3|TI{)&4+^7EalWFhjp?0nP^Bptuaz^LJ^F*A_Q6B6DI}Eyh z^ZQ`f`{y@%C-2p+eD5sJ$2u$;W*T{inToK2Y9)^Ni%F^Z!8P1J&=D2h=~!)6MrC zN91F@3ojs|59G;tK(3olgPse6SKzy4{wDzYW`7|%Z-0N2lm8d>oFiq%#s7_BzwAT! zoiz}9b3X!VZ}<^>3kZ+Pb>w!RGXH}?wKF$KRj3C zIevqFgIRw-#@F{x=2zY~*C(EzW&IyNWE~)0!Tb4prSM+i^}_QZZ}Zu{r!j7rNBMr4 z`_5(CH%_XDHNW&a`#$+c$Ll^sJz+QKCx|}Om+^x5k^9+au4TvXb@svP2{{=*^Fw=Q zv>of4&suIiubp)N&vo>Wdi@}NA@9Wa<^BBs4f@AFgV+cDi@k;S!~d~E<5hUS@89Fv z_n&@qd;SMEB#)-ddiI-RoV+iz{PFF6_L0QHV0c2FvmeeW)1SXvKpufS@CzX0GoFa} zlk$J^Ex#6?Exe!CEA*8A0;dP{rsi=VIZ^?PCJ;ZKQc zLB?y|6<$yN4*ePbRz44XIBt>WDT~gBW%xhKMefVFK+t?Pc*Xy*&o&;3tR(;N>fb&6 zho^skv+Iu!&*AzfH*|kl{^I+`Xo+vU7m^o5B6&HG`2BjId8ya^4p|;#Z`b|Syib1d z{QO$ae9iNK=wlt!SU znRstpL=Ni1H_)&5t?M#!VTZXtNc{2n;I7}DKk9n4>v=CL$Ij=hJOKK3-D>~JGkIs{ z#r$4B(eAaE#sTN+<#^$Dp4er1KkbtB0-mL)9k_2QpQOKsAI!P66|rZ>5gsnrKco+z ziyz^S=!d+Y_0#hf`Z4wRZ}}blO}*Qn`c+TSYwaApRzBo^y;F9cTV@>0TjndM-NZgz7d+QT|K<7AV|czpq89f#k0X1$$AJoJ4W?PXmKnh%xFlm813xblAJvpfg#mG|3uz?9E? zBJ#7IzJ$mtpVWEkd@=sktB>-5mTf=hHTyo&arb*-%WHl}o@9Oqn#ZW8oFiGk??n%^ zvm1FM*h+Be(-JIo&PhR#*W}Qod>@EWxSu? z%Rm1Xu{-#c;{JVYzN_64h4UStd2~@er~Dw-<^4qUt~^)#pS+azj2*~BP9!gd59B-{ zcH;TIiJ#x=;rq0Q71__$p5W)mSA+athxw}ruQho;zH6Oj^lE-9Pe{Hw%REnh3r{u? zy;H`2I4{FE;N#%`it=D7%M;G;gwbcdD+ZZQ_`qQJKjy{nfw42b2NuW_MO*dnWi{9)>SuJ@C-!!y3UJttq|ey6-&_!I8qy+zCDqxYTTiS|DCZ{hWV z`}+#=9@=5PKB?oX*c;3&p#jSP<->>^W&odLRl&^@~=od_$N1SH=#{EUt4a&r&9ap}u?bE;fok*Mr zKN`eds1M>7%6X0Kce(DqSABIH_QO7sev6DV=R5np-{-oI+xP!mcij@To16p5KE3D8 z%m-fL|AM3(_Ql4*6_J zt^6O)JHGOJ+(&$#h`;%K;?&CHrC;n$d9L|B{E6%M*TmF=_7l0T5xo*`kl(nIc?+(5 zALIA_@PjM=hu+nL$Uc-ZDDRi{axSF2qH*T!E#440XPNyrW%k9|p-BBdy!!qzT7RFF z$j)_E9^xK(L-B{lXu0pBLrU{STIBvB{2%dIzHi61J^W^#-!m_fM_hS5<=n5EKeEsB zdkx2zae}nJBl6nsK0eF%HF6e-d*rp|7sdy9hnaUJ9`YRf;OC{9MKzz0CamtPk|}d~09KeC){lD2K@PmenuiwcfJ! z)qKABf%D$$mi7Pm^Zq*t^=JGYJ1p9taVBwKjVH+0_OJS%{>JsSocPfCRWD~f8AozI zaR)u=ugE*g#s&O?xZu3#XYv5GG2j z)K^aLTg&Mm`ScI%L^};1H4%F-AC3LsZ|1p~KgKuL0n6G$`MtfYd_EW6aM}~svo4AF znf9rF_Pw@#UEc4C|5JYTxAK0BW7cOr<#~8c9*>=G?ICvY7>?aTx1u6~)gASRBu z4|RTgF7bErR;xWZpS0urmdh9qI zAJ3;OKXuLjVK4F*llQ}(D8D}R0Ixy&@Pw|%L3k4KZodome3sAUc~L$N9?tvAhnPR5 ze&_L6Um0)kJbv0^-!bnC&pS~$T(9@<*}LAOC-S0+_(}6W=4UOt55PXy52PQ_eZg** zi6g=F|1iV*f%*&iv-vB$8|MotvmfC){kr}czfu;FgX_#A`*D!=G#T&g9i?J{%hrh!%O-+V6(D=LWGu^4=i4mie=M zANQO8!V4lNJX(+kU*i94SAH+QBk1o7GM{IDQ2XJ2=BtQ)$?v^h#6HaXgZMY{it3g7 z{|67?{ql$KJ6_LoBKZRKAn)1WyYOFmKmCg`er9{z=k>;$^FEIF;yz9#s%iKS*Ph&hq`$;+LlkfHO`*zw5`!?-DL=Ur^eYxwH zdU7A{`7`Wl@?Ok$cq{x{-jBHV<6Hb_2N_>bUQ1pLe|5Y&|L1vR;sWjZUP8a1OnzcK&N;`Ik@>crmH*r8DNng0 zKl>r-gVZB;5WP8$;8h;S^Vjw4Pkny!fB2j2vClQWUGsnJ*R?~>C9toj{0M0e`^~uq z?lbuderF))AS$T*D>ps%{c1AF9t$K~}k4??a!XMgEu?f;+0_eCE?+tY8E2mL!3zZduXUq5qwpMJ$S z@h9g+d#Zo6JnsuH0dGLwNFMsxvFrSLl#N6BMR<<&{2=3M`{;4y{}>n7gZur{{;;3e zfB3)he%TLbAJc9!Z|8NueytC`x8r$TNqbj_|5kmE&&KoU7yCsn?Re!`*Lvj(Uj(u~2Wbz##Q*rc5d6(^ zyQyF8KlA(;eV*(3d*%`Q;k{tcIAA+#Ji^~vpXWv7Lw@AV`97Cvb$LShAo45XH0vhM6}|3v1jyrc^D5*gzbdbn`C`1- zdy(gyr`BT!_6tu!zeVFG*V#Xw*L&t;KOaFp=g*W`N!^q`8_~*K>UF3gSie*C{Obk!wViA9pmIaG4=92|9HILe|MZq zE2duk$Ormexcr}bFVF4&1(*MG+}J<*C@OdOKKz35q^w`~yIPz()6XaWhdiI%@>lpF z@>b6Onb-dOKz>(JevtEf=D|5H2wzCt^E&(=ydiqzKKLo~;PpHp|NrZ`7?Jxpf9H8X z^&}t1_jmHAT<7~%^Wqid{TN61Kh6P?Us1L_en;@tjaQT(>G#0u^S5`s@_UBpsYtt& zgWAz=4?E@e{C<11|L%tJZQO@H20IShwO{1d&g3yU*N41*zr3RQEU(FTWBmV!{3CoI zdcprhR*C$-r-(e{+vNY|-97(fx%`OxBEJ`A-0<|gKcIbhFs|cYMdJ)SCGjTrl^-N- zx&ue7=om{k>G$W4&NJ zUT^;6e!=r0jE8j;|Nk&*XT*8V6LLR%D(%}}F!y1%$ZeTCntmL|n$ID}tfxK7VxFs< zU3bXuoFC<2onhSPb9uI>9+@Y~!RXhx?fftgk9b?2<9d+!&>n)>PY0XdX`kV7utVjq zJ(^EbW*@%WyL?yv*GNQu{1y56Jp=eZ;?~ap&GO{`=!Y^qnsIOaKA3&~tfx$W;N;!N z`zeQy1CgJ4$6=Z07+(-SRWBm`u0H1P5YVo1bI0_{IF!fpiLBR@BPaIc^_Blaf0GYH z9`$_9|6#9=YdyzEe~x3vb3W#M|FnAcJ?drU|JeU(f60F)x=)5*V!v#Bnb(=0mH*rK z-|}GYL-+h_FDIYF-{}uOTl0VB@tQA4{fgoLYzO&Sv5TxPlaI_eQ(w8)ym7B*A4eYd z`jD4=*6T&DGamHyJn)?V`#k$qo)>wJdiR^bo%dtE=1ss|V_lXCnQ3|A+j1jTf||pM&NX zMfHERZqVQFU;VGAUq1btqu-xD{lzf@%Cp7`{7XHH*z+uh?-22W@)hPiw5LDp?W;H2 zvt94g&Z$pa2=0ESf9W^O6XVT%<-Nh=mAvjgAoY{4BY$+C!*_w$<&TdMJ-_<$>0clF zNy_MBqIs+KK>hCTdpXay-hT9V{6o8(sGe3k<9_F%ypeX0xF7WYJ?Pi{>Rx}gw`qs; zGuI#d)a&KRkc0Xw#Lkp6C_lE^4SHScGd}G?y^_Zhzk~aF^5JsYaULCqewR4Gxa#B4X`aOL6U|2%oA}N zeV{*~ABzO2*S$NW;yj}Z9}v6#^sw6?e(=>%mLK|m2QLI~MVap{Mee8U@8)rCOTI10_kYUQ?{MY+ zTK1ft=lD1uiaz*mT)h-&2RVb``TW0+o&WQHkBL{_hutD)5jj5lw(L1c@_BhMaq!qCb9`Sv-9@IYd+r01C{dMwv+2^Qt_6w{xjGJ+= z-;g&nUiqGh{POh^=eu23<~fhZUBo`zcdYN7;FGCGZ$aik9P7g7FK=c3XUKWW zIabfDBENPK`w(k)YrbdRM*HS{@O0QQD9=>>Tl@F-2zU<>K1;qnJfM6X`wQX~_Ud_P zc|po6|M%ltnelNy_Gp|d4;a30BJ)H4_{ECvj`Dwd`X5h!dGl8y6ysn;a6IyX^g|i{ znHaub|K@u6e#W1;NhU{`ajJ*>f60oGQ^YQ2T(&))PrKYlyUbS*`6v@_cpp&Yx%Kx9 z*@ruxe-64|VxPi(+y1m0@+a(LqVcFap!P?8?>@1JypQvL{cc|0pC{hJx3NCJC#Jlk z*Y&HJ57@u;>p3CD^Qc}w3tw@?|3#i)*sv`cBO}$ry>s6PW5tKUU><53jNLg%G+r# zd%X5NBI7O(r=0pF`9b8iUF*ZskcX&O(fGl*XL-gI>gVP#2eZ#zyA7|*YM%KfABqn&o>Sr&o%!CUxMAe zjE-mChdh*n$mMmB@p@fc+b13;pUw64`FVfr|B+vKU3=s??RDkcR9j5+# z9?<#D^|L*DJ^Rp=FT<~qD;R$cM(!Z;WgHXt>y&qUe7v3{o(CJ}u@C)Cz2PU0=Q<9| z_+orV@2msJoj4zKeV~2pvpgTyk^l7*aVI>4C3IX~!SuA}t7^F8KC&If#y`Az?ymVC&# z_z0EL{Ep`>hX+I-$T2bNHHduV%@f&=Ye&H~KlJ&e#<%c={CZ8lv_W7+0-}iry_Q*qv_yK%ck$i`; zC|@N1#{A0jQHHk+!rQIq^vuKI`4}(vF`nI?!z-Mz&+)uG9_at$7T+Dwf%kIAMZTW= zKd2r&SLAn+jQ^WseB|Ym_Y40AuSR_kzSR5|zK>ne*9Y=E=LY5RCjaL-K-QZt?)kC5 z7YN^I-Yp`>`MezczRdq24|(Q}@R6Le_(-`-%JP5M2lu@>jH)1f!_)ho{s-T}Uc>&5Uc?(^aQ zh%axCc4#;J40#px%**5vIe$f&-}4jw|5C=o^Am}C;Sp)ib#lk@imbcgr)cL~Rvz~g z?Bk3-LDx;f*weV_@$LA}T_fvLXnfrX+ z`;>$C4#)%gUXcB$@r3)_&x!4K%HerG))}s2Cq5VS{CVC(P5rLxl6)?4hIL3}KK=h} z-dkvgu^*9nwLW|o|DTI|BJxuXa=&&B(hqhn%2TcHAHv&V51eOa-iq35c)-c~VRx2& z4}f1;E+0r4zmyLI+2?rv5BVqWw)1f8n;e(p-t`dv4?jgeLFP$)?e9s}^MCMv_MdZo zB61Li*f)dpyQ1Gmqc`g5FQ|TPC-EqVojPyCDeV=M4|M*JoBfLNljplHY(o1+CX!*Zp_);g508*RJ?K;syEpj>KE|xDR3SHRaU*R$dJG z^!xC9D}S(Gx14^{{*J^6@)G5)e$*Rfc?sr?e%)tJM9)|9=DFlQ#dTc0k9zIF_RKpy zZvJ7DdA^M^c{F*p@)UjEa_pbHIPy+h?Q*w6%EqPg#dChSKFiU6 zaKC;o#}0$FXZtOGMwxYQB7RO;L=TjMj??SmgI3hPynkQ6C=d1*)T?*; ztDUX#ukuE2?)SbG_0yHln>@GnYW`2X-;46Q=kkEG`x5_m)(`iu@kskXF6@VPLH0A) zA^aZ*?*j5X$UL7>zX~seeG(72FT7vvy#8RkMlSqE`Oxnw=Q^+S&-}mxRX@mQJQCOW zWuDjjEvKEX+gZOs?E%cb1OKK>UNg@t?(3L5;5^T6yYd?OZkOK?Og+f`+6BBI`|Du% zKJKUA@UiGO^TIq@_8cKELevL2YSM`vC_XW9+aj?$jyJ4>Tyx$S0jDC9_P&=pW^S%#woOjFb z;>WgEwB0lRCttGie^=+_!UKBF3Vx2?a|8L`R`@v1S%I9Vu|4=c^h23`dM>Z$_PpQo zeSEk3(P6FhA2j~aUcX}w&wYjVGx2k3A0vUtnH5zYmtDc=Y|P`KtfB zLEdS;InVzw9(XQ!Nxu92=*|zae{X&&FUYySH%B|+_sIM4S9ne8ksJQ-n{QD&_~vd8 z9VdSH*`XiDAM`rBD(i2~N5Y?SpFAr5D}M;uei40huE=;o{rY{f_3Qaaf4?x}6^ZWo zzY@QD^m}OHn>=6;dDtfh>EC?a^Fo%D%Y1(26_W3Z#2fN{<9>M=`jyw%G3U0z6LQ`7 z6wG&yD`M~5$9Rc{l-<`nzR&x^FN(;`bE0u2?}rkE zIp>!DZ=S#B%6#y&%k?`SGI==nmYhhUX^x}Z=08s7ou0*QyIVH1F`$(qn`K! z;x8cIs^GDVZzaMk{GLOMEUq_yG z-N|^To{)3e2XcA6dAQ|0|BoG+uOg@U17-Ya;_BDs=Zrsl+|KoD-k)~k_p84r?q9zT zLVn*PkdLT;+G*VJ{Q!1t`zzvq-Y?1vVi)j(v}61Ly-%b)w+bE_OP ze))X!`aR!IobkRHFZ37ZOZ&LCi_Gt1G=8MLm*OM+qyH6i9+A9Pzt-N(f9aPp^X+px z?sgf!4jMO*Z`z}Fs+~J;tKE8C{mkc(-}~jSS+^*Q+7o#!{yp#0?i|1Kne}Z&`qge$ zd8Qvlp4``S?Ve+!9v;E#wb#b;$Nb-U{#N}OPteO6XBeMxT+DUGQ~T1sm7jIPcw9c; zyjLE;c*eMGSF}CtVb=G)vwg*Gv@7k2c8t3#(hl{(^*;RxK8N+MsDEjv^Y``~Fa2YG z6VY?z3ZBPfKUpuUH{`o|KcF0apOE-qJIn)e7gsyTJ_A2w{g2;8Po86QJ!8Jh*D*eL zJ^I^m@_)Hc{c?VgcJljdIaio-hT$8X4|!VbN_oQnv2M~YNFGDnfX^UKWIqMpfWEOW z>$#8dvXAJzs2|3Up32KPF6~F&4LQ`$AH)B-|3^;wXzgD4uwVNtdY^LUeO%sSx=$fL z)sD=o{N4ZLm+mVXj}oVx2kXQ8x&LN-p4%gi*uURRvaeRpUAMT-eT-xBeBu9`pYnn! zuUP)icC=&mW!@K5FU~jpsYkzW(+<2pc2Qmsx!J!J`5u$E7S=ldK!DZ{kwg-BJCV`^!1MiP-1Ihc$CP$M1;! zJw^7p$O$jtc{l6_{_oevxH*sW>!bhI$9cXY{wx0n?+5>va&dk?jQ%G77v9g`%j@^C zhx!kFk|%pUP~?0Zy!j*K_w)FU6~2peJ?5|1=l?tpC@;bOihaC!E_tu>%K1BZnDBml zr^|b1J|Kx)IV;)!vM>*pzhW``8`-#fIK0-dhcFX@MSIhL1{}q5oyt*z=BOl29 zEz?ha=gjj>&X@Zc&--Do#;fm+tgGSw825ZWPr+xigzAC?uSKjKA zJ1^zAHS9}2kguXW{Uo^m9)WxwekE@w&&U4W_$1OUWyay}AOsu#yuR{)+z)?yyXJyKW;wD{7}xh8s@|6McZ4)k$o)4I$K1Kl+AxueMC>; zyMn|O_W3y%m~s%i=6VqSe7=`K;y;L82b)J2_vJn09qEU7OZz(-PhD3cAMI<8!RRSG z#ncD##IDcx)o#?g<>vYJGoMG!wx8#n59?=t`qj#JAU|uJ5mZ#!uI{kT@Xj z@x*rRkLTfgLG)>R*L)xR9`?wN)B7ni{`EW#{t&;Zea8;r@8-G4g*`DJ+STM`GT-b+obNq;q`YJNCiRI!JC^@Q-Wr}}@_* z<-UpK{o*IutK)awKyK{ojL4I52P?n*J8t}y=M$f+PkB-NtoI|Y<>=A-*ZACcja^^I zXPzU@WS)2AdhENXobol=8_%`e>pV}K=K93c2iNDle{V1RlJd^?SK9d;2kl zG4=F=T%z{MIO*q#2Sk6&M-lrne}(6#A9zCfILmzJNJKS;!x0WhsUIymG89O_V4${@OjvQydL@q@8|hM<&VE$ zkG6{+$^RAM_22_v9q0dkeOxck2M=id!v1 zbB4R#qCZexp%{J5ynW{H@+0sn%Ioh8qBnWXoF{aj4Nsvzhd0gd5KcY-JwKYa%p>i< zKkz)?_c}j0$0dfZ0Et`SGmzgnCVHLr@_z^4jUP;$O#9`b_?+a# zf0uK36Ir)%t}gZ1C3&^w{I5|_o-e;o8s6{2SpQUi#)+5tKjVycJmo}g`~o`(>X)7e zWdEaHv@6ze^hbNa=?}YqP|kf5IoCuPzJc~xkJMNBQ~fpH{mTE*@AUV~OX3Phdz1g0 z@-rU$WgORj<8}8H?0+b;?_M$WL9erKTJPJROMY~X`+l5$wexkKPCb6(K27=bBkJ8p zo{@E+`)&NP-($Txo}--K_1VkwTps^YbhW4 z!ykgq)6~(`4*N;FwIA#S zdwY!9QS8Zi-+2P%QNP9w^ko^0pNhmY+5y-5u)EmnBV6rEJ8-_~hcf-{aoqS>o?G4} zyiw2p8FwcSXnR-n*ujVD+pqJeUGMg*9mhXvht+H5-FY;A;78iUMD^D76&?h8AfM0t z#~!G6-3wv|uH(ifzq>@Amf5%9ACL4WPnX~2%l|I)yq|m@{Gf7i?#bU? z6MJ6%`8L1jbrL>=ys7Wakdt-Oe&jP=+J8Cj^S(^Eu-(KMAkc{fP6^viE7{;rmwmC$Hf;`*@IjIer#oe_}c3FINBD{dFxX zkLUW>U&Cu*PvpOo|5H!Y&)-+W&frJb&xt%w+28H+dt&m#)YA^}f_~kXfa>GS1D@w6 zyc_ae@qhLsAIN-h-{b?~$KV0Ek8>|xFZ#TE8}rL`cr@y?>KK+^f~f){EfU6 zo`LUn{oOu(SB~?5@PPiVKXOy%J7Cf8{otq4j(Ipdq;aLF|M{KsC&xG#*Y|JZhtK}& zqyIDh_+Ag9&o2hPKA!*CQ5JuFAiUp-=#7p(z4ZfcDt}15el6enqoa&p{p8>Ut55Ft zd*U-PUd{!}gE;=`Ve+n?)BNr6|2l6E`Tai>cp2;j9w4Y+Pkun&kNKfJ=P4+!u<{4+ zZkb2sCwv5P&Gk=yV)A>`Pu_!a_&c6=pV57p>#6TGc#bmnv;PQRn0n;)eo*@}eo=P5 z8_z5!&Jq7OFUtO(^+@^m{d)45 z&!1)D8TX&Z`=}m0UgaO`U(helMbF&lc#DpgGLe_KNd#*d|Bzn^p6w#-uk+#jWWT!N znGbZoh2GQ`{uceLd;ttR9?N@T_WQ;i5qa2G7+2Lh*Xhsu@_vK+oPX|TWh=t+y&q-l^YvZ+R|kf_ z(~gy&=V_1U*bmSja@Y@cJ=-TPP{xmo#tZcXUub)_ul=K6^^o$Jcb{>=IHCVK@8$Q< zbNm{))%$lvCXLK z**$V9*W?H7XT3k|8fRG-(X+_?@x!yfOg&X!>d*OP{COXCem;JnUR^KQ=g}_jDV(=; zJ~FT1W8N>kAo6>k>zMnE^k@H#yHhWjSNwS1Z&^Rg_k6}<^ys=#zItCDtAE zr@SBcYd_(Y<^8C?;_=Y`tWSBzN6)9fAkVpOgs;Ya_3NPeV_%?utGC@RyWVL(uD|-} zd3}|av7c#g$dh;(l>cKsX(#?T{Z0Kxk5fO@Lx1P+`4$KKJw)W=`^5SGD3swR{caLo z(75e)jyYfG`!f8f{GN80b=WxJcT$;m@b?D~;_u7*J8HEn^&zj+IC+kb+GFPD{Ju~g zhU@FYUv)6CR!Y1@*~WoBx`>T25XNME{<@ zn>?HLK>R>YJ5IYH?`J&6}nh5Xb_r9K+;~ZdkEBTe41N7Y6-yZjK4w3I);UkOK zQNMp>pJg5z{;%i%_V?}q^BSKf_tf&AViyx*IF$iaBa1KQ8jC+8mJPyIjU$p>EX zAK_6%=VP9`oP1yTKjR;IL?08;Bl}qT?Yya9?t=$$|C@P`KcJrdG<+O!BK#iXrEENF zy*!5e7x5+M%)20cqWfRyyrgbhWo-- zurBf5pZZ{~@3`}dtjpLt>jXTn@gAN{J`TTqf9Q?+j9WiuT&@?ci}dU}$T4|9?1plXcII{L(so7WCHx=$!v5cJU*)sTqk22@ zb=srnW|?2g$ajVKwe2Jy7uk1FUtIY=^r#=N-vQGP^~|%^!xx%ovo9llyg9~izd3g^ z$5Fqbf5)@S6M5%zQ{I`+qp!&aq)b0)$NZYS$8jf*op~AUulsQK)3$@0mfeTAkAiP; z--(}-e~Yx^etWIwI_n+(>--3btDN7EZ%F&TpLHM4xb(-Dc}wMu+>gfR_2@;6o?!B4|~^+y^h@4ciYka@n-r#9{Sx8 zdE^U&k%Rl=545jeDZhF-$0O#KI1@bQxAv#K$TQF`aVY+V9JX&f+W7?Ux1HXne3Y4Q z+anG+4@IxXzLdlBTRbPf7oI2Q{pNWo+skvdQ@^!7`<&F5|C|01I}OH8DbMz)x1Y3= zc8#<9{<40EKPqqZ;yh;Eo9KP+59=R!PCYx{w69&bj>6+>e`(M6UA&K(cBB2oZbjD{ z-nXQjc|@MX;k?KGF7X$;$oj+hjd!k3J=fE6;&agTbH;1-&EY|2d_)iDvU;SRc{9F> z%q!&;^-uC`{M75^v*e%FbA#*ij@RcBufzA%p0%g)eA-j}wClL~H{Qh$`~I@?>HJ^^ z`1@l-|E$L%^UV5KG=6435__HY&v>g(^py1~>sR#*KZu>FH+WY0v@$P@3`>TJa4EBF2w4>@(IXJ)O`AGX`yfa>=+_U{f_Fkrd9IcBBVO1~`Kj<}J9^)l|Fgb4 z8S~G3*`V^npLuQ$K8)|EgI2}f1LA@XO_3&TpRq&U*F>8XE!7tw>;1P zVNdXY#3Oh?_VMsoJP!}Zy25!vd99vf3(qC?`(W>f&*C|GEYSN}RzCCS^;{2poBOse zZwQY_`3l<}ewFh-KREJr?KbE+JI>qD4&U_>hkkVEL%-vkA3VgbE|CBEpk9>s`_(Zo zocog(K@4}J_J|4#q%kUzfZnf~Ps`HooqpYr8&faXN47|GCHuqHlRY<3)JF@PEjk z?@M#eOumovNUW#1-geIahrs%Z{AbkOQjeV6cZKMI`XcZDjl1suiI@0`adYJbwL9W6 z@zQQRHR)W4)n$`lpQj6`2QlzKP12-+f&5 zid}IXM1K=A-|}5KkNWw|9%(=Ry&}AveplW*WyW{r>2kkzo^yElodSQCKwdEI1h3o6 zd0XNE{RJoQhka1qe0J$iysQ>xAJRtV!di3U7v>kXr{1LuR`(-`%yddL|C$#h- zo=Y5zK;q| zZ9dFAYv;^2@fsew_7OWM?tJyW{;t4I&rzCYCS2o-&>l>2KuD8tFH6N(I!?Um+W`ELshtKIZ$m_V{ml>CO zTF1})N3Wg_ocyWwSN$o6d>?wIyz+netL>y8{5$g>WZtj~=R3IX1NL&qZNK6BcBDP@ zsGaTa#lrgq;s4AR&=dP?ko?+n`8%`M~gR*0UdTT=0GJdY0WUVqaI~xu4`Z<(xYWj~0GyKVP@^$1We9SbN59 znAalXfp6SVJ@*`>FI5cpv#celHC_B+r)*Xa9?Tx?j%wba_AQR=wssOnDmQ3lGS3^i`B!qU^aq z=f(Ko|B*0HDHF%!?>rZ2oC{CZ-x*;YBVPc+`@u_CmZ#!8S=*!EE8b6e=^wd+?As|{ zA$qXh-*F?KL0{_X2Cb;r%AkA7yaApE7n?bUyGucwqJL z@!gL;dVuBw%&+=uK7d}a1NFS0v$ULfV0`obJcs?vc4N#|JDTZ$fujzQu+bUP|aL((|BkdLKzh$q}Uh*UJZq`xu(?Rsv{7rq$vh7xW_KoIG zqU*BlT|Jk6x^I^cGaqAr1mD2(@@6Rq&-zUM#rW|X z3BF7Hm!FvWLyy|;`@7y#E|0>x!uW#N1Lg23)qC`!{*~Xnvg0D}RNvj_XFq0r_l3?w z_jB%Z%^N%?ZrpS}ulM~q2O+-~zAro=<;Gj&UU|ioSERq>F=u3a>-!kzf%r>*#$nKQ z&;xO#_1d}DU&FW3AZ&*>Na-c5g*_3ATv6=%PRJ3;jW&tROomT#XQ$D!P@zaaCL z{2hc(#gE`&TW-DgJHOnA|LJ$`cg$~)Yvt+iyVWn&>%BjI@d)EbSNkXXMUV6+)-P)R z*n8I5)gNNV#jJDJDDTJj81BnoYPa+D;rV1eWIsoI(k^OeYyDYI88`QF&NuJ{2_4;{z^?GF zRZLzalGl+BH6LSNZJaT0BmPr14>f--?{$_N{tDhqWZd2V8b`Bl3%ai-?=kMKNPNT} z#rm`H=}MmRf&8z6dh;Baa`ApnKFWCFc^&ed)`thw&y-93ulyk6r#^Co_Y0~A^o2e$ zpYT}lTgDIVm3@18!pXa_KG+@zpEi;6One6m|L1;@xUO7h)UK@ey#;c4Zjp5%yjoB> z{GG$L+kL3}p1BWYzO{Fdar6COk>76d!PopY7HyUSP1{K^;N7yMqG zJXCl;cq!&l{F58shaLUd!GpnH{`o+k&-p)iD&!3B7xa35-|ovhfA!T3=l|n+4iMgo zc0t>l2yd|R1M++FeegtI-Sd)s@5^=KBj=0s-<%JkUHnM?uX%js#gF-(m;K1(>u3-D zPx;FK*^lMVkL%p<<+rGw)$7xucb`M=$Wt`Vqzn&<|4@HTKFL{9Wbmpg`hhp?2mLGMz z@Pf{3P`Mh{85ep5(c47pyZ#W@-Df!d>}##x<3H_Xf0sOK$MCD|ANi02WFA(`@AyS; z;XOtCHF{Pb+5viuJ;a}}OYYY%<41m(O`Nzd?S>&2Mc#``O^^KfHMmJw&cg?($5Y4}Jb|W%WyZbH6Rx z-nE?JD~s;K83*k!-W}aP_#TCE?)?!j{e3X@@$5^@v#oc1p5M{>eD?49p}*Tj{$M;z z9x6_M*B<0^+~;YJ)MHmc$Des|{>)3bujfm&4|zZ8%bz%ome+Bj2l>r4A6fV5@CRI< z`6T7+|IAm=JNqf>lQ)>Zz{eT?R?K^n^*ulK;PYuG`K0e>ukz2?ANreR>~`+^SVw33 z_P5Gs9$`E;e!GvSp8foc^IrG)@`1(;+d)6h*CW(kR{O!9(7WHuyIW=x{ye|O z^^{{jc6~a zWW4Ap`vAt9c@vRKJMg_4*PZ{D*4M--{hm06|4*JU=LFaNh5kpphlh`x`pJ48jyN;* ziT>4R^t!HZ+<#v0oPT*2*KOa2b>3+=eyu!nKjZV+C#X;CZQp05?EPIYqW9>>a^?ec zJ=0IM^Q=emdhGj|XU^Xt=g$AJZ&v>BRjgy$d3h~(8sdq_@9E_|Z2T-pdyzwIp4hVT zQ0BSnP5W&b|Lu76OYT=b<=|XC{1fXsIQc*PkUS83Bk$8cD z@{`ds|MSXz(s=#T+j+I8^{Q8bR8_2$h?^>~kFYm~A#M(zNyrAdU z;Q#O&_$lo5>jT-}{n>%GXFmPK?K<|B{2Ijn);!zq`{0p`o8f6F(_Z-~zwhnu5z;Sy z%=fsQj|;CBx#cfCAIUkp@_hQiFOTQoXN&6Lmv?>q@;)A}zdH2#%fpU2m&bX)6_N9c zo8B33c}2(TeEjI!{(D}KIL7%*?344EB0Qk~JDl;^j{4)gBW2L*`MweTU_X3+E&rD? z?ZH>bJ98cTlea1F)po+Os;9~SF@LUSLI0nH`Ey_FcijCSm;9fzyrAcpSjFU>!t;?o z5a+x;G2e&J-ydYX^Zmcb{n}A*^32#9^K|9#3JhXYZW$W2T zvj5gj_q;a$uiX5^_QLC}XkL{3KbZc5_BZA6Ij&#jQN$(kAL3y2^)k|)>jcR2?7Ooc zbl>-A9Qs@H9iL;I_P_2kulT_9lYWW&<^O1h$VNMiOU5zx-^{1wmG3~F?!(l#`|LH( z*z-c3EC1*G?s*#fG3;XIE6HDy=LKy~{UuMCsGPa3eOB)DKe73)ad+h#@K@^dUC)f) z^qc;gH_5LcKhKdrP9(pypL4!voIwBBN%-HynThdV^Cj$P`suXC*k`UIFY`{`$9>_? zCMrkb*Lwfif8)o-0oujBKU+3L%$FLz<~4JFpgvu%i1Xcl z8TT!tU;5*E5WA#a?7ZkVl*0ou&&a_(*tjvzN2ESze2!gLKF1rL&+qG4*W`(ii*X?j z=jANtJF?`5>$wW@AlDK1|2c22pQ<Qzr5e??);zpF8i%{AM#U9JZyjT%X}BP5Bbpx=S)93y!EFCzCTt&et%y+ zvzT$U9z92o@O-X^{tt-r%sjn6qJ-3eRbmrvd?NMme(G!T ze)M17k98CN5B>AKu>6(h0_XSH&X0Qj*)bmF4gad1;ZKNH{Ena~&%yVP*dM$e_QyU} z9-T6N>pof@P(Bd3uJ}LYWuL-0cn-a}u7&ptCcXvp`;Gp8%jB1gV}8e&?@Gh_6=!@S z{@EV?4^6y;PY2)J&-1}IAy@dm9nbvGZhtS8)vx=uc}`OOsE>?WL|=?k)J|LWIrp>v z&g%Mmg082;v02~v%sBD?tPieRTxT9d_2>Fx|Ex>QANxxDr)Bl#{<88@M*fU%>KESA z{cH3Q-YtAt_&NDJ>=3&Z)hB)`Z?8P@TkrEZ=9O}gdCYa<2lG5J^GrY1XI{$##$RYB zafxwKeuRwIe#2Xq|FfTuZ~d{a)=qZJdw-GnQ=h?{Gr9f_jdhXv2;ax^<_F~8+5z+F zc^uE(v452J3u+(q8{RsI-#O2o2V@+US6<5eF#QE>SNq96Chdi9OkR}yo_q*-n?GIa zZP%maU4K*F$PKbzRd0`R-k)}OF3-CUM<4DZvM(=E&-?ukq5Jtf$Go|}M}MoHonPwr zJiqz4`cAoew?5zfT0h65-|jqhc#(H^zj^a5?mSE6_k4Nu(tS8~=>9(Y<;JPz0pSIC z-|F~R?D>J2kD!<2GduscKA-%}_H*uT$MACK*}MQm{_gY411higm0##{*YjmOW**gp z?a}^T_W7&!%LCc(OMIaHm7iJdB>YCcJH$Tf$F;lF9?_3}WE|Sd#E;$Xkb`>h{G5JQ zUPOOOJWO23drbTudjeU<-X6%h@n)1$AIx?1TKkUu$G?@EJk0fodU#q8d&zwhA&Cf|8(djaixB`#+`G$?J~Z~ zpSaR_U;8a@gq+L+ej^Xa`m*wW9T#~G{mlHE@;uLC+3{sRBf?K)+_p3QmgmmpDR=ar z`ItEUB=b7sX6N5|$@+yoagId0%KEg&*LD3z&#^<0a@%h?^%Iq|=eMuQk)P+*ap8xq zyG6&teLNTaPE7s8HBRk%?|g;_Bwn*0Ax~!Ar=IqT%0b!h1jYH@hxu|n*xwiBTw8J8 zCr?FxK2Kb79mzSbt~dH4`9JayZ}lJI_sYi^kMtXPKH~EAJkI!&xKyNF^RoBfV*E7z zTy&q|Iy-;&Byws$nIH8VeT(Rk`sx#XWPYsAb#bnz^g}tkjq{lPw42p$@jLBH`;#a0 zdG`_S2dQ`5*;h~|Z=JaAv!aKI=1u-jgL#&`*_t02?>Qg0|KCO8gmSx|>HZI1OL!~RJN0iO)|9EbOd`Eurinntg!}az1UF?qM;V<|e zuX>UP>~rjc+CK9|{0;vX^nWq_?*9K6T<5!7+AnXI_X)%o_2>CD;)eIh{}DIjEy@F? zEUzIC=l^^1JBEG!k=%Q|^CUmZzLoZglggEPc~sUpt~2hSazwA?{lWus9sV!KbMSyg z_?hy5w(E7?o51(6PI4|0Jx0&8$9%|>s^_eS;r+fo_$7XQ=wIIWs5dtrkbMk1V37FB zIY8nY=K|&b`duqLBzzg?E#U*@xr(fJ{Qm{~75^)Oy-)t{Ft;tAPM#eMAJDwoJf1v1 zJQM38?YPhL`r58`Og_)~FXZ5P5&7}E&u+-~zns_Oe^GyVjO*$WrbKKVD>OMMW%&g+RULG&!|=Xb}E zM>&~?wLi*{157(X)@k|^nWsyiEUKUln`N zpPX0E_p*-Ae~|HWJ&51gfA~N1^4;FpFP{60JqOX(EVxuS{9et>qqt7IN1v;{ z%$LY#QqMk-`;^=KY351kPkDVWOWvWLGLFb2_W86MobU13Pka}?k9`etxi8?5lm^f&c5%hVh9!UK|zFmLcIw99vw=J`d(x9-2)H~Rja z{Ra7f_Gx}qKF$1OOu3k}X~^JXiZu--!$Q3HEHg zeutm3|Hto@XZH{62z}~L<>lH=+Cwh$JoL+Rd2bPW^}6|^{t&yo=0|F$u|xA?cqZTf z%2Q*P##_tiVcK!p2{sPJ?-TzLx7PeE_w#)Gm^{I}!MLWLc0bO02mC?(?CAW;i#hMM z7e8@6%eSSx_BZ*5#GAw)<~4CnJw^{f`qj_#dlsFK+KuvCp8Qk%UsS%>p@=~@J3;S*2++6R`tM+$| z*wcPL{bW8KAr@ru`vz}cS zC;!KMq(ALq_s?lhKJWigVwaRB>ep-BA%1Cx-rxO~^WpwZUJ-xnenWX`pXajsCgvM{ zdY3=#+b?p+6Zt#)_zk=a@&wgm{f+sUd05L&M}OSMKF9GU9*NXD-^!o!fBSiwP2PxE{v?Y5lre*Vu#c|LzXG4if=(!VwAb>^4^rm5Abwn)Fzr$gKe3|sqi^b8AM(i0 zivCXv&-s5Xp2MVl{*Oid%Ex*>({q6889l)V@xLP2TfPTIkN9=@LHrNiM*W8OlPBr9 z!pvVV_XXV_`FnuOhjA=?QqSdCpL236zi0eneC`vGi?|m|yXcX2{%QOlas6sMsgHd{ ze`3am9jYhhL;jDl<2J7Ed|!Az?2&cu{b3i32fhVlyyRKN>&7eATjTv)FS$;A5IN@c zv?r?P>-8q<5b~?Xl?O_F^c@UOlyS2TsTYuJjPrgw-?x|5U--0%^kaF(1MXjWJ?_&E zUq?y19op%Nj8{3t@PdqM%7;B7NAic1gQ@3v?J52s-`M`I_rvUC z?QhN3(O30XeX>qd4>~T}rL6vf$!pd;hjty0c-786{@G9Gapfb}|7G7k&ncyTJ+G9! zA?SD>$#1;qyeq%<5&eg6?L4@jjQz+%GLI{dx{tqle}C6A^YSN8|Mux$-O7J)tVfxz zBI`=`>V3%TzIF0d)Nbf7wZB1pX)++ zr|>e@_Okk|aU;B6^DFvW{Umm_KChft_Q-uR9{GIwV?V85qUYF)_H?#S;{f)^^Z38x zcE9-U7T3{(@pt9_&|BigM8;RYb{)2V;&0^a`0x|Q!@8^AmIvtkz`yi9?IwDd^Qm3f zPyK*$^5$ue&PVKp_99P^aVmH8Njy?t#3lH@6~p%>ezG1Zk9x`V8E3qn`RaZ||Bqgf zvplr?A90BK@PF?2vj3r8J}~E8SWg{i?RYOwePUm0dDmaB+s>M2$G(Hp&TA*m1Lb+% zPy3wfmE+gmvaWUAns&(irL6s(?SIzSZkccU+4&IcK)(tqcjj#({o79QY+u?X^@&eB zr@j*p$&1-X=UivvZIF1Z{mghxdyVI=2VBQa;GM9WD?W~r`;_=o=5sy&=XpQli1s!26X@A8?KUnu4|BfIL*r2V@H|h( z8};G%vW|v_-Pgr+Jw*{oRh}qw!P!-SaW``QiOU z<#N8m>nJz-I^+e>H~aS$@xR1V`6l@&{SrPP{8)KF@89jg^JP32zDu6Y^L^C2eizkK zcq#cRzMOG%eBtNd$KVxw&h-gB+HX+ami>o3 z9fr z|5orjf8Hm;=TY|iJR?;t!_v1V7_mdm)y(v7P=(v7y$jf+q zzTXR54{s<>Xg}#sl=oAQ<^PyB&TlfGeh)0lFUtGn_Zb;y_*m=`K14eV?`N5FfZ9nB z`;-?f$^*h*m;c*&G5l}xh1$RIO&$T>gfjEvy4G`fYuWg2zN&xYulTq7lkf=gRJ7~5 zCtn30>wP)@C&JgdpUU|(_+#xE`(nO8{I-~JI=#nlgE5iF5j8<{hdVeY4j9i9%nf` z8AzOot^8Z`A58mu`BDAk|B!<`L%Dvq$Q3!5Kjn=axj*Ch!Tq{=VBetK z^c)$3?}mA9owxXf`v>AZc2FLtycX+E_AQ|H5==Yc;j{zBXMg4Yv}ff) zp1sWd*rWS2<=yu;*a7!p2i|Wv^*(Pq#v${0_QCdN{?7igdc#jYy6g3fKG*z-a{F2L zU#(BRn|*nn-{-~Od1PO9)emw;?v95zJICcdnfEW8$TtqbPh{Wk{pgi^P5$sKpYx@> zj3fI)=9~EvV<*PXe7`7~S7{&T_M^9n>v<}oiTe4$A?F+iD^}!3uF2=5zuivFt9stq z{2@G@$hf*Mb)0Lt=MAi%d8GLx_4tq1lZRTypQx9YP(SS7I0x5#t>Y;V$b7B5Lh@kb zbwBo-D9w%ZysZSX>d=7L!?tB_wa$S40 zzuxbB?epH})#Gk2GrrJ%>|VQ+$3qX;pL}1Cd3<||6SdoUf8vgE>bLbL{0`p2{=)z1 zR~=t?J?26GEz)jy*WRaHCqFL#q@B!pcYV+vu%FnYa?ktGOXgMm%16SBlBaskkM6x1Z|Y`S$+Icl43S33?Gzj?lPKkYsD1*gAwUwK2%3nrd} z?Dr;OH?uH7T2auv_xb==fXeeqoUj(Id*fxedzjUU+ufWFtzfAgI2$n%1{ z7tkNq^_%|6hdKYo>&#o$4dkUC^ch^o*KsHQ%=@N)%e%=xr2S&}vc~t=p>e?8Ra{?UFSUoqogpMsys|Ja^>nBRGVm(%X$q2S*<2NZ<&3lF&R zY4%rso^jwGjyrsnyc_$h)aO32`zCoRzVBuKX+7~ky(k}k4-YZhOS{?u{k}c)cIGSP zFMQr{qUZ3A*d^<^`jIE|`#7JI&tt#LJc6G4D>}bk$G=y8B6<(1U*l6JkNPQ`MzNIzasov@6-Qi2RPYc*D@~4G)O_a}G;no}+A@()ZQ+ z-rEy@%Q$^MR8(*5n|a@u`H=4#45F|1d+)(=DlO(jAxM#AuqYk_w&1w@$B{Th;!X{{quJf)*;RflRvPY*uT65 z{oKoQA9)(r!{m?0#7@YO-8dI!d;7gt^d|qsId=2~qDR&>^(jyGq~ERYc(*YAEkq95 z=Nuyb%6UWlv-gX;zU}J#k^SQ7l;Fvis~u%rhzb+;zV+*OgcM$;UA+{i=O#ewn|X`b>tgCx~91pV6ayV0h}!e0KKV+Fjnl-%rTjDTmml{rhP@^f2SFAIkA4Ar_)uWPO*% zl>a;B)6TPh-hPRm&6_srH{?;C53C&0tNaPipZiG5UZ4BhhkBlf=gpHt>|4I-B7SN68|mM6 z^Y^jW*?-r=Cpj25^&s--FXwuW9QspvkNFVo=4Ts`hjRGtKI*rBa{n&x>*M#XBennT z{;4m%^oOax`v?80hwHrcTxPz-j?KHi-^aM0=WE)Re>;EYpx$};&iCzj+0WAsb{YPn z@*T13+^?NC56Ja*{XfN}{)S$Me@AbvoAG^ny(C}1mgWC!N4prm%wsz)w_WJR{{4Ls zo`T;QjmzeT=BJrgu6mrZ{xQExDG%#188_>pXg}}~^yfNBKl&s6pYu_9Oz3(#`A+MS z_Htb3{Bw@metaJN)Ng1zGheu#%zRZjbll$Wyoeu+9PG=8&rm(EPMy3T*Wm$?vD38ypBizE8mcB-+7FF`^>k^clh}I)BIe&hbLEF_%`1|g~uXJ;6tAH zIqs)kULo|nUp(CY9o75g|5yiYfAD(U@#=^2hVXfm$#3syd-x-A&G|UT<2gQl7w0}hFXy-)U50*djJBP^qi&wO8Zu2_+ z-aEb`|M$^*HLPdq30@LDhw)%1{006`p6Ne);BUR&^Oc|as}KD4o4@`%@8xF<&!UzxBCwtJRa{OQ~vJryj$(V zcTq21`)5}5J!E-G#((mB?BC`8&i~=!2@#64|%_NjZ3@0|Hb$5zVctZ%KYlxcN-}) zZ-Lo``53)@|GJ;^OY-OPf8-&~U&H&!M|0itgZMc-OMKtAFa5x?RF_@(7To3Zx&d;x9?!T@tCqEH? z@eZ>~_VAo7c0-@W1@dDL#`k0VAN`;o)-&V(%Kya!g3g=s{Yv%3bMyxy$42UD|3u~7 zJYd(!L%BcR4*6(L)V|r-e*WNNzTtW2oquy6i|I{<>qIc$Z{paLScz*I4#?$^t?A%xFF#f0b8@m_Bv)|F)?nl~(j`lLV0&-*O&U_0>!ol~W({x@=ea`T+e8;@t)>(^s9 z_J8J!gS5Z*dFHuXhsP5+*GSwlPSHFu-Y^~!^tnABr1!z`3;YDX9yG7zd3cnk{X_Nx z?a%Xx@|5@==c!nKJdeo=fSy3~=KjX(>h-!`y~<}f|J85Rcm6#2t@WGV=DE49Jt@=9 z)b||nxgRCIxQ@S{XnW>S+Hdl1=U4MB;_X_t|KtXr#3;i?z{TO zIo~)xsHgGI;>Ph#T+#n|e)w9}&y~}-pZ<`Sa~0va@5*lOqiGj=poc-*)gPbv5&EBf zw)eYV8=gZycAuVKzsKFr)&91xo!;sHtk2%>?bABb`jcKl{F3;S@1s5A;y2^}&iR3H z?0(PrV#gP9PkeEo&sASLVf-KSrgGl*37*Y)kbj^XF> z-_A$lr`Q*N6>aa@{(b&U{%J?QcrM@Lu{b{cGQZpNF7xZmr^dnleMdX)di=w3?QK*K z&U^La{qLU}K7@9$FYzVPo@MO6;|~9@ynja;d0Th#qx{Cfof`>xNEH#zU!QTwTX@;}e@Ti)&JXZBk@IC`Hr zaXodtdCKS5Hxu9Cb$rM(=P|Trzr%;bpMI(zG0(DpcYewbMfWe*>pbUXKk{twaPnVM zR<3!E)^>(BxBuY-v7>w;`^~9WAC}<(<)PvMr|f;5^E-Jj;!b@jALrz`KSX}zH9kA% zI6NTp1AHL78$4M2-|%CeKlFEY)_2GA&#(7L+2{S&7f<3oDCB>7*~j}mL(Y48z6Lq{ z&K2hfJ^u+0K|MU6{NIW3f*|)XKO(2^@4_d~|BYPFA6Ab4^F3j|JBeR-{%;VwZ~hOx z$oq-RM*q`=|NGldo+;e?9}}nN{zT>hcszMG`8>|^G0$Dk^O*dUKxpyYheVKk{iJ=XgB-2=C{90K^aA?T90IKE5;g>rZ?B z`eirl{p;8DEAn3RuV4Q2{Y!4{|Ng~e{`zA)fBr(+r(XH#2l+NKF3KVNAM(Nf$p`v> z!oHV{p7;CN+S~6N^8YQ&$LJ&dupYrv7|;Lt(_cIfNWK#9Ck_vT-*65p-Y=B*WBu~~ zK|I(51ofqX1{5_g=!STdT@Vm6_E9W(T^;}#$5b>>iy>~A!gk5-^{j}|$=isjV z+7tf=Z^rtEKcdgguhBnc`T;4U?{8oB0(sxwdE@*JAbM4<&IMX#zrW=~Zv2`1IcLl~ zzU5FZGNIS|G{?2C^)IMCtZdX+P;Q=YrkMheK=l|J*d^&$I4|l&#{#yCm|FC~? z9^*Rgcwh1PjIL|Q(>~`!{0ccve{@}+yv*mlPrt^_mg665=k#Ov4gK`W^PM~@@~O9H z#P852_AG99nfzbBNUz|IkK|GwW8>?cp3sl&%L7&x&1;NT^2G91>qn32mHvJ+ z{sj5*3y^*{)?T=;qX&7vkpA7D$p5*YVSJry_^JF~a^<&R`|XX~$G+ri)Lz`ze$%{< z=jQ!0ugm{cPyAai57>J&!~c<2*}nT0%GhJ0`J-|-j?GUfzt=Y(p*^Ta|Kji^j=O!@ ziSkW6Kj*rTll|kylmDCkuygY256&ON3*`{KJKuo%Vf!}m%KbPBER0euH(|~@fzJHGLLZ```G@pmpxC+&VyUO#eI0S!&994e0m`cko(ln_}B0a z+?StsopDfqMaD@z@d)mCr2pg!n@1{#ji-J$?snckzkfebPW%IT^_w$)Djy1&XS}a< z=E~1~&Ho|qj?6Rqr+(zT<2*+Htjqon4t~u4;o$Gzz1qWW z-~LN{u|Du?EcuLizkbd6Kl_JY^W5Lb1A6X{_iB-Y_f*mUeqY|_PrmQU|53L6cf8-` z2j%tHf5GpuANx)Dzj!`q4l7jtA5( zy%#*^06P!3vGao3i}wBA;oz@6^$S1YdK$v_F)w0A=9}UFI^gJNz z%;x{dt2igkd>yK<{3tAbVM{ST_1UE*LxK2IL-x=)*a;uqV; z?Qs?tw7cc8ALUHm;s193^kexKpZ>1=v`4*2KV2XGZ}Ld*LvP&wJP(}u%|EtYw|{V5 ze+ZjLo{&78`i<}=l*Ks*=y%r0!}XVNx2s$$F6gX-;UXZj!eJO5dp{r=q!w(t8l!z*wfB;`w#84$B7-T<@C7QHU804 z`(Cj)qpYEKwqEtu(?8L(_ICcI?0G%;>aJgrc5RP1 zc^40N{%_*sjIaF8_>fnj-T1$Fbnc7yk|(+Ieb&ogCif|?ey@H`{!d;?d#caQ@yS!2 z=lxn&o2P8o`E%x_dpSRL-O!Jl=j8$A>9~)043$fJ^?g$G=)S}HiQgHY&l@MLD~?-U z5V`GF{*V1t-vg%J@lBpc*?o@upJn|r-dZ$%kURf&-Z$^K>aTV}aXbi?VL$wI%JLBKQ@{MkV}ARkUDg5R*MIl#L$>2N zIDgk%?y@ zi|pIr|KuS=<>|d*dBEN~Cf>LnlJ8Ll zhX<4og#Ws~2i*S!%Qv0>{~=$(IkR{V_#O8(zUN#0oTGv#@_#AVw{dRI{So{h^U0sT zkoNqJpJjFzl;I^f$L2XhzGuh(^!7iu!}rDiZC>z?U+4Yo51tIa_8gta{+cp4ykBMG z3q7$f;oP4*UugVn{*U(I{oteE1L5I3@AqdP__Nn|EL$J%2XEB<$Z_TW{9h3DE#Jqu zD0@DW>;7*u{}Y1TybsJc`oEKSz<8E@KFM{J`3k;i?@vAV=Xi$ii}$Nuy^?=$zw>DP z%gN6WU)nvsDBdINJzLLvp-=A@}Z<%qFzlE$H zjxTwy{|7PWS-B6s6J*@rnK$ZJ=55R?>i;Q^oBhnmTab@vuM^2nh%?qx`6l@`@3&v$ zuJ>2tD`q^(ee$=BgZb9$>0@|5<2e5Aiuv92%l*hJazFMw&jZr0?dk{l5pjzgVfD}G zx`M*{ab&+|0s_iy3c6e zfu79&-Bahbmn9}_R=&FAw^?b>%6=@0#elXsPWUGdI~?dS9V5c%~Z zF+T_O>&=&;cgpzhZ^i?jaZ=pTUj1IjnOxWYpX03GOPoKON5ka4V%HlFdj7F|SAEZY z%H23lbbXpU+q`MY_OJcfUoc<5x9}Y0E0$k}$Scnm|57>3Uy^s1>6d!?mES?0^IRz7 zdGc@kas1rprmVkC{#;&-{)>b2oE!dVeC&2>XApVn=PDQaQvOi?I@>+@74%_y!MAn$UYR)6R{xwM1xO7l#3&NsF{{9k4Jvz@)aW&Hbm z#+0qk?mvb+=l(Z&-pxn(S-Abpeb?pzvFp`;@ki>@&&iijf87`FGX1rG?mb1WTmMs0 zedrJJeE6OH#9KcjcH_SA>=!#Rp3wNlPl)&YaN{-3+@DT7{cHKZ9Z&S@zKr#J;w(Si zczy1a6Fs;78PC`2l}|gXclncfZpR1hp7|R2kMTbB&KG-K^EvHree32Aul0=QTW2V9 zAE=%5Tkbc17}RcEH;?%Fdj8s=lk9Xxge(s~3eosVy_+O|!@yGmx=Z%MW zL*nHgZ`lR^-TrtlH?M`~{ltNON9g_uJJ&g~& zS%1#=j?X-Tb-;0)NIX&h4)OaP2TyuQKTpW>)EjT^-|~OP=ODg&A?JX8{;KEv zlIH@kpZnkL3zcJ@uPn+xGCxuVukY{D4!qy*zNE&^uw1|OLU!@rywLyunDc&-o3X zApZxC=lQGQ{qS$k{lR0=o+#fZkM$?7{^2P-@Arhr3C|tUj9G&&i@(LUgth}diX%{q|Nii`*99ao=@bxUdmUD zH$cn$1YK8SrRt7myr z_2_(m@@2#GaX<4Pb`Qy4h-3DtAbv_*#fLHf(H?Q&xZ>$Mw`>2Shj`HVJncB=;o{A* zFMj5F>vt-D_d`DALQdoomH+ey`c)6TA1oh;K9u+52S?6(z3nGgc=m_gl_xZgil^|K zm)^FX(>Hkn_1Kem;(tUP|L~p2&A3J7%}UVpq21>967JvgPj=0Y-@Wof=C61_$2<1F>ZAUVtMzjF zH?BOFhn^f~>%bjnU9q2My-fS}@jAY#Z~RxgIo|S*@~qRZ@w@Bz(^vRo*XgHr%0qU% zx?e}Xn-4cW%Nu7OW_@wH>$Sf;KKW&3`yYOgGV?=-o;UwDeyM+=&-ops^M1oidp-Vd zcrke_{`Z!1Sk%LNz>|4SE|j<8{2%YDZr+c5u;&3c|0f^fd%e^%POmfX&Hb~4lQ~vRZ2gJUd`%{lIzT^(!C*c3!`QX(yG7oM3k9iCI zunxfMkZ;O^V3*D7$@j7UMPKZHz5X7RH9rtcvo2^eaCnnzxys(LQk*A{TM1 zz8nYl%L5MICy!{Ed5tpp0el(nk$(T0RruczepUFJPd>^2`-Knm{9C-A@B2~@f8@C` zk$r6E$>#ja`F<|v+1yu$`}`|4Ae+_s* zepi6k`}ULXga7--SNXSI=PytE(~mOzAN5xrkZ~eUJfLzbuRLx46Y?jo@u3IH@q+B{ z(+|8TaVj4HPlR9bU9yev5`IT=?3CTqGxkB>T<5!(CtoCQM8Dn#pAt_9%G+=bgX_$H zU!i=I_DCM)SNKozqs;@FZ^2tIk9scb&gc0*B={-o)E&?N@rVZjng5Z8{u#G<)Qs2l zK|YZ2cRzB)1IqiU2ju+zgSQIN>os4)9H`*Y5Cy@s7$hykF(*7py0i=lQEX(l?mBu82Qy9lVbB zU0HeL|9Fn_do;d~*XPtXb{IQmPu4f`1>#Ts*YmdcW&B&`D>rKA@>u+s{>;11^HSBD zXV|XK-Oo)LKlEe!=KJn<+6UmD)`RAqQ`V1c=elpO9rSRv``jP*VW;*;5dBe)dbXv*l6_^+Ww#uH+NBUOUsz)A-X%^3QxRcE~Qy z_u7fP(|n4u=lpEnd60dF^@H6Xj(xF@`yiiV|7!p2Z|Jx3_=)2~-sDp+Be(KUM(^V3 zN8^X5pHuHRzDDJC9PDq1k9TN$o<}_6XyWf_zkkZzIGz!^H-6)H_zBDI(`NrBZ^M4? zzMsQR-0%KquzK~)bLf}$8JF@pzZ9S8dE<@`{nfmI^^ktYzVFke!5`!QwA0D=A(#Gj_G7*A!T#9uq{gv! zyYkiXfG6hH*m?TLUigjitbcIbxX&->Y5e&#Fm!a2ODKkwIGGrwH@QNKOc%klejzSb|1i#Q1B&p0C9 zi#Pk(^Qm$TKT`bZ$Fv7u_!J-H0bGY)7{u@80gZp;VO|K0U&nXOSIr}1U-|E``+D?rt`qD#up@c+__^)tPtX2^+}r-s?m1s?K2m*sHQ!{X z?B}^Z&&lwd^@GZpKjg>G6O7Zma_YJNPB_j-i=jITTYUEa9!HvI8@dGdMY5B4R* zHTgc{3+rFMXr7q7UOQalWy-u43a_yFKjPN+)BS&6&g;mNiSm9d^k4CR@>>2c4*x^@ zy8X4!89vYXV)#DSr71g4%>6tMALx4HdBI=)3-34lAJ?CFzv|K7{NIP~_455rX=zkKNv{ag{gNS=SrTjEFYu;=-w>aU1h>_^^&__Qp~!#Yfv`RhGuFRshC zWwn`;k?~DJ`F!$J~m!{b-~~JEYlwIJm=WN zr}4z=F)prO<;l+6hg@Ox{60fH@+*%x@=ZPWXh&YYKZ9*8H{&+mS{f7&_wPafsl&(+@aH{(*j&vNx# z$n)k~dz|#EUQgV5l&8VpSP$9Hfbb8l1LeuX|KYFhUk0!Hzn%Xx4$E`@Jb%@%eqnpa zfBI4N&wj+XlpAb3>T$;bcGBDyJTI$MgDS{KxQpyMFhh z-sG#lI{)`9&&03S&;HQcw!_t5^+Wt9{fOzCdi`Z^_&@dg)j68|{FA-!{hsqVddhC# zIlsG4!!O}?xNe+?@qX91_k2M-+MU1Kyn^Q@%v*)(fOSFpUUStsC?OLFgsrTV9Lx> z`q8_7@>9>}(XV>_3iYRbU*lFE*+GBczUw#}pYv$?cRY7{{8&ACFyou^SeC1={XuqC z-0%C+o|_~t;FYfWjfeBROXn)c!x?Ai3if#k$4`EbJ~pBU%RjtOJ?`t?&v<8lZGLCG z6?f&~p!yx$^DBPqI^%c#D98JSoA-+cJo!I(p?JV}!g+so{!iC^5xgDmhuz=*l^@vk z@FenoeK!!4Z{R-i_ISTgevos3o^$(uU;G(%^t>OuAo_#C6&XpN)6^k9{OOAgCPkek6Px`zY%9eWiBwgUPQej~_Fi z4bN?T^P71taV&2r-^YA<<^O(od42y=!h4PK6!L$b4};f`AF|AQrk2Gk|M%VNI{RJt zH2nKt$N#a;pf`CP;=!^=9Kiz)%5(W%?|JSIIphy`AC~y^{obE_jECnKC;I1mhv?Jy zplP4-An*Gs&+vde&;R)PoxAy-pZu=>|Iz!vzx=olKjS{;5&z%g_da+&cszMO&-r!! zkN2+6daq+2-y8OOfbo8w|MOfU=Q+Rs;5Fq-bYi<$?bKjL`vf6ZUv%vZi2 zO5DK%^PaW#SKn9u^<8;*S^C9qe*e=>zw;KoZ}=a|_{X4jn)lGPQ|0k1@2l*3(0RT2 zJ|F98JYT$@D6i`N+V|SAgJt+q!x4yD>=yl`!_dfJao=5qLv}1h71IjD1E?FOcd*YSfi{}fwJ~(_O@}n2< z$_JkEC@*p#_sEIfe4jl1(yw+B<@vY|z7KtzJRsw<{s~Hox5bpY`Sqo1f6`@9MAZRNngl`ZM2rzi;=sli$1M$N1~@ zz8SA_KJ~l%PfzA)@pkfI%wJx&%zJ5+!yRWnKY8A@tX%DTp8H{ZwErGYK9KRB^6&of z`+c1<<1la9rM#fEfiK`uj>xjjM59vGIiZspB5M-|^yp z3x4W)ecO54>7D)5-^45XJ@xH4=Q{eB`|x+}8}zz**!;HlUG;zEvD~M{8{PS{uJ3ln zuG)$Hb9Q~_2g-Xrmv#E1>&3}W+phjC-*3Fv-^k^7lecl|SMea*|0aHlBgQp+^<956 z?(LWAf8^9(wtV@$&)4o1=Q-rL+mq|3{OH~B#`lTZqxO@J^2`t8m)0|Xa$a-nq&!!@ z-etyPdC!CPr$4g}+b;Xb?>^=e$~;$@{#ke2Hx4@9a~+xWX3H^gt~?`G^H=(u`SjUd z&-@?lb3g0)#_=2G!Whf zzWex)e&+YDu3vd6*Jaj8?KtT3Q}(*!*m9&Fuz6(o(e&iFTNh5u-#4$y{daxPuk-6E z$JT%2e?p$8J|urgfAM~mulYyqb^VIu;qZQ;*VFItf7HMGJ(c~Heq!Dq&lmp(->06R zkhq~WTly zh3DWp?^ECXEx!}*^ML-JzZw_hBi`?P!}_nBjEnvT;XmR1;sMbv{1~jNeBZa9{GaFJ z@F#h{@MoXr{=R+vA29p!??2xI{`SQ;$v4Qu!IR+U@F&Cz=g^FY&gsDyQZH|){$6VN z*e{>FjeH+^yz)EpT>t5l@1lRszg^LDeei$reuJF7du`rSX| z8y?Vj;5qi=@PY8ogZk(E|A%oPZ}y^(X)L=O5*teZCjWc}Mua z;Q@XBR~}G(@*X$;i?YxE@ti!U{9n8r`(XGZ-ZOpT|IYc!@!-Gmf4=95zTr8v|9+ns zIkiVo@AG_=Pd+dn zkb3i`ct6qkz;?*9uKvw9jf2iVG7rdeF(2^VR?EXv7)SAX{$9kn2kZd;bp8+j!#?uX zJjeWupNOtMcm7YmRqo9Ls(hVSM0^A^LHDviFDTiS>lv1BeUsM!)fGS5z+LJ>?u;#(mbgKj1m@LwUrrof&ue zQ2n+K*=QWHZ$XZem!sXej-KMzo_V_K{b#xMjXT>tc}C=-{t5NRIq&&YroUZpS^cv9 zF}~uya&q{b`6zk$ZYO!p@#t5hALn)R4(vx+US#;coyT*Xa(Or7KKC80ANra3yysaM zN4)G0pZe-t%E^x=cc}d8W8_ZX%J1*@*qQw=_-rrZY5a8iFa7K?{XhBfHI9nA{8gMd zI`ywTv)?;Zj_bbr)N^`&!gu?$r+Vyl?z2xm3Hi0>=p#LC`H_QiNV|>WypQ>~`T2@G z?|hv;u>#pOZ(~@+6n{F)saOkT{9=n|TcVsjorC8!yJbjQ#SU`k3oe zo_6-W+xXi1^X#iU`j38ze2!DOnb)01r(S(>Kl)Vu&2zi&_B;W8VEhj<&MOZlU#9%_ zzuUz=`kBam@@a$PZ==W2$H~9of4e>OVR_4OZ)fgHj_jCS>qq@>p5)~Jw%pf#8h>^O zvjg|n@5Isgsdl0KCHodCwD9KX_MW-1(<|+dOl%)0DUW4{tR5k?R@1FX`XJ1?!s6jUBG?T6Uggyw7Fj zV?6u1@oD_-^-;bLzd(QS3f`wZ_wQoW56bKIJc!;y?9aHojy%dSh+iw`6aQyF#yfFP z*?G))h&a3Ik^Aa*uNTRE9jEP`b~%6lL+-gg?T~N4!@v`vKfZs4zdxPl8~sjyoChQy z;C|0%5eM>3!^e2;%lxW+#Jjxh7oYk6FF)~z4@A%G3qtI^^E1Xr`HJSdlYg@>#h#$^ z+!Oz2{PW%~`TC&yJovotUi)x(JI*cb|NEG8a{IiTyb<3Mgr^#${Xh6@e|SXN<-OP8 z39%1l<>~z4@R069;qUl81fG!fSw8XP|FHM)ecEZt$`|h_Z`n9P&i^$YvH#ia|2BF* zcHZ}m_ls{6J;z5rDSv3*(s$k2|H>D^_kH`pe>qO=&UNM8NZe2c$N#QnaVNhRGA`_JfA6>YcpG^@{PnvRuK~h)iGJtLbAMd_>yP>{{_nfj`8n_Rd3Z$h z@coM~9K_%GpAh0gJ`f(ovb-SsZsP(z6@Jfl)Mq@Zyed2fa?0y@&JX@i{$gXi9?1K$ z@_*ph{GYro_no|-aRkpsT!r#}eh-kif%iMnc<6h9p6~mU#s3ixya!A?!26*mk^ftv zEbj+z!T$sM9yEL;?{RO0$C59J_Y3)7W8XLZPcQlTzaV%&cqi@e{uAC?J5V-0wUd4< zk3_%cxxaXi_(iYB_sNIJODYf7m9uk+ok9}GM;!iP#zY&%5TZf z%3JUpdB~u4L7&W@jvu|HALE;Pcqq=he*4nHpz}05H@_3eV}r=~yZ=&F&nIsekB8os zCw$^(k>}*eh8L6n>wF)1t?m8lb37Xxr|Sm#V%&r1IX=|)nJLSc$Xmjb;Ro=4`gh+c z2s@XFpBN|Hm%Pa-U&(dHWtsj@J;nP~5C6ybXh(k>#E%#c^E~TfXnxoJb$%ZtFQETH z{6jwPMDq#mn{$KjzaPlDa^?SMkNmWKNr<0P{|+ZFE{`YQcAWiQ)%rF4*1zM~{kHF+ zUFv7wa^>OTAI|*?&+UE9wM_e8?}O+E`D>?s!n42HqaW@4uR;5DK5l-Vaoc{pUpW2U z$4y>=yc@}@%{R<1$ivM?X5Unq``AxxY~Lla&(YrQpU8u;+q?beJ9|{GK8uskxHmt- ze&$8P|Bb!Kx3#bP*wdeEPx9{|K~UV*N5K!zZbG^_}^ZVZJvafasUKh7Mw_U2g>ZAG-)g$AlK7ESnUEZv5s#os6 zjvM``FYQrz_&wv|iT~rdc(5lsXdj<%AMW_vzYmX)KPsno(Z85q{r^hWlbLt3-w&@@ z{hJRz`S~Xf&tH4;V)+aGI?i~q(~o-pm;BLjorrus-+RI5^XU^*-%t8?e73{&?1mkN z-`M(^`ZJEluJ`_wf1j7i-u74j-sd=WTx@;guga6XhIi5rn{Uo_Hb19b?rYr*y{3e7WDwB7OZ^!pCEKR<5Wyw11kL;jO-q%Z1icM$#1PRM?R z``Q2F-&g)Gy@rlgyT}t_5A%b~`^Eo(__w(8HO565yI=Dx^Z6(KPdm9knS5=07#I^*~Mh#S8v0bl1j%J%@-@4?H7@qq3F;>9+?Bgy0OKC%1- z?XW+z%y;xC$N#~vdEcG?L;v&r!QlawZ+Jh(5C5m$J^#o50#p8)|2xnB$!qn#@8FN| zfAV?rzAte)DGbQ`(b#WjurY(3Gbho>cx%M1J|d@>cxMICzI67jeM% zptKKp3w%@f#Q%N!vg5oL+`cyc5B}lbf9$74uK&%)e)VVH#QXj2NBO&NK%$U(qSEt# z{Er3kAYxZ}L3ls+^}a6*|7YBs_3(k#gX(cmzJl|9?#JZ;;WO|@cn{9+!FOyP@I2S| z?_a#e=KuKKA^HY=e(tB8ecrFK_8i`X^OW#_+GBV??b7?e|M=>Mef2-Sja_o@v$yzup0rss`~ z5610y;_u$^e^)-VamN3}A9fBf`9S7-c|U$P;oPC)Bp;%lynyw_e8#+h_RJ6DAL1cI z$4MTHUPS-b137n|jeaPDv>zgu{XHZ0<9htxF4G?N8f-rrGVij^hT7-sFWwVOAGYiM z#z4+%e5yu4*jpZQoKHQFT?BcJaUETExzx> z`mLQUf8!V=|3`0EEdMqynf#pc-rxA#Tt`0g^$@#hue+U2dyU*@{8s;r`Vo0FdF<9t zdHY7jjh}BsPn1FYkbX8^>xnb{UnCy&-~6_H5QrY^k9O_Hai^De*uL@!jbrzFyx(NJ z@!ccj|E&*1Bi=Xs$mT6*cklDy|G1xc9&8>Oy=;9jo+tT@ll=0GC-m?2)6Ugz+;*Z~ zJzw{i!xMOY>)$w`9yvFrSL)Tb=l}Ja|Kla`fBxC;eDlA2;7`?$^A7T)m+*j)34Q2er`SypSR~>?umKD^IYJU8EAqRX1?-Ni)e)lWa^MBX< zS^Jq?ubjJG_CK9dIOC6b!93pi$Mb(r{2#wFdH#>~;Q>MTI`<93&$;g#-cR0azKe%` z;S=SPJSPX=DF5RB&+`8`w!?R0&vSy_H#}tWobtgNqF3Z%{K$h{=X@XS!~aze@AIoy zS^n30_)4yWSN_lM{ZY?*yNvIAAGR_R7yGFESoHm0@(kshbAPtSd@27IzMA>u7km#@ zKFR$)`+xj29>Dj7=~q5bln=!3%j()ifl6^sXLe4%o8-jTRI`I7j* z?_a(1KOgWK@_j%1M*c58F#PUc?(=@ms~H!Y_an|JUy=Fj{oi;$&h7EPA@P2m+eBW@yM@?6KMb>XD4#?A zjePD$f9e?-nae_uXg48Y~Oyb=ON{X{5=MJ$s^I8=jN_u z@@d9T{tPltVqeN2`ne-|@Ejj@)gSoZ8rOqC=M&@LY>)h{cDMd%PkGcY_wDOfd$CS+ z{}Xoqv@<*({U=9Ao=ZJ>8|`g$eqnuPo{>+bednWR%wNOo6=o044L;fH-hRC3$$Q5C z#Seb-vX5~z``=mj%}2|}&5z{2uq$~U{eqi+Fz+KDbNu9I{N7+*+y3G=LH%g=SHB_t zXx@28`fcAAnr|oHjHC9hh}~&F}hsxlTJzh=2L~PsQCn z(GSl!Y@a^Z zK8X0Rz2W(l!~ULmK>Vre^f&wb;y|9NeO>&Y$a*9X$cp3q5HI-MC-1a*KlR0aka&8E zU*Z@!!Y$9tU+O2hzp{6FKhb$-+nwvQx3PKP#L>rDKl;)R%~$e(vtK;-%lM6YdqVx) zeFOT!AK~?=hbId0%k+HmN5r4|x+@PD9~e*Qex7(jo_MO{M$SFn?D94K;VY|$|6_Fm z^+(&GJ;yhwf4tYn_4@cxdPJUcyeHr3d12PS^nH%kcAnaepBaAp)RX6@PJP+V9=F%4 z2lEHyxR%wI{dC{gd>`ZY{_wgUpZs6zd-Dmu8)_e)YdzG?$Y-ALgyj?WIQ6-Ez4Ohk zryt5;@wn$ruRD(-U-O-MZrp>8XU~(izwM%bBd5>hPaF6B+41E4Trc$J<^#}t>sgL? zHRIvrt&DHx6VLaF?$4RGc|VKwk9pYjj~ev}cE9bgkKjZN&oO^^-+ld5zq2mv^462% znfYygr!cPL>zt>WfAVAEPu^pY=j2Pl(WCY1|MZXiB-9_azcF6z>bM*K9qkW3)%kSF z>dXGm_^Dsfaho5Icfco*A3Wpmb3W(3f;>ujcbw|>rZVDaz7`Q-8J zznp*PJz)8C_&L|j^Bf@W>$=~U--8c~pOZHm-fws^__Y0=EWFu2fAVYhdikX}kEk5* zg6u!4AGxeYF7(fNLiQ2L5f2FRzq~)Z@aG?SoID=?Yl56l=>OXOKQA5zJ;nQlv@icB zPdMMjv!3&Rtb}2_pMFLhAt!lAD9>d67%$>`W1K_NuJBuob0cxj`>*gv@6Q9i^9SO@ z_p^B0ga0k?JlT~8B)*^d&c;t3cb@0*oKoM9V?F=N&;9*he4u*OX6yDEx z3hFm{NH!4sQJrRfAW5Q5Acsa%J6OSBb|ff zoSgE`ci-ZldcQIB92@@Z``gIV_Zs8P;NyVTp#@nFNi*#_yplYYJSTbHE~5|Z$$cR69`=S8)b6}*?sbqn zY$NgQeIk1FI>@|4d*S_g+M{1kxsq2T|D!(azITW`yB(gR{dc(gPmU0MlIITo6gf_Q z?mGX)(+$cSVi*1B$M9@FzVAfmEB&SSkcW3LpPRCI&2^t(8Nc8KzC9ruQ{2(DrwJT3$MM zjt70(j&jPQIUl^w$5|iQe}vp`9)H%OH}@&%zkSLnxBb7@?>YYSKKnIKQs3qC_}RUF z?34b|FaD;U&;1MfaeWxS%m2V@JY4tZT;K7$+q3@c@2an@H~WjXQXYN}H=g24;P>2b zQqM~0b@{)OA5yx$9rE|_&u4v& z{>CoE!RA32r}{#^xljMJy!Xj>yIma{S ziEQ^-j^ulXS9!ay^IG<&T*%S&JL*q&zj{}HUq7`=@#MLG_A}ITo&Y2tIqxeDw_oS? zcYjAd+d2IszX;#mSN+D*k6c%1r+Vc*``yp)>reGt@9*q&wMX|^kN=_{)+y{!ImE6z z|G4Xq@#u#j`&0Zaq#fds_T`tEUs)IB`+h3_=kvq+*{=Cb>*wYHk+b?U{?mtg82_a_ z=bPXeeNT}6=*h>Q@#=HUhw9Dw4Sl4?&^Z6v&+^+4e^l@9^9|Z(ehGUo6FX#AuDj12 z)V}&z{Y{=UJfQ7O*>>R>$j{g})6b9dd%U;9{$QUI(2ktKK!2;-*@$MdHVcmpO+%;&-cmCeJS?pyKMdsFz4jh zuZR5a2W1g!@ZK-8;9q|F^}N>$FT?+W$jiy|4eujQ1+T(>9{i6lp7;BY_VEXKK;P$; z|6`xe`;+1DdhvTN_j|>Kd;;kGgSN}}`u6!h+QBa3pMCNnqW|-2JMeh$LRXakgC|7K z@O>M9|HbcV7m#^((DnTvKF0qCuX^?H4=;J}pMQ9@^YfQpt(OP<_N5p4p&lLwo=tuS z{*k!%{2wSUbLIcwd!0|1hwu;9Yw`?`_gKlp`Tt zdYbo&&-X_=KPK;|U!J_Bdb#p{#G~UBKZktg z%jdqs`)rTv-FLUsDCo{N7Ab$TRh+JWzxucFa>l22 zcD(!gU2nrPIIgWP_Z`fa@`9tklkZ{t?&GcJe)JOZ-0*S3|LN~n-p}itN8|c@hYLQC z{h<5q-5&kB|7P5_$94VOamoKB=lDr{z}NiFRi6`wXPg=*_B%ZP-9N7Waxb5J!a2UH zJ}JZhiH=uZ@!qaH^|c%$vw#&6hyqZIJQv z+~)sy&iTgYp3eW#A9C$+<6rJ;%k#C*zx|jW+270i$pf;#^Zef*e4e+Pb9bG;gU|C^ zUkESZIX}_&W&inuALG2A*XMh2KUQ`h`CniCcp7x-^J_S5|T2m5O42e04zIC%1Z$~(N6^NIHEduHQr_#gJ+`h2&J??ECr_4slB3v-sO zmk-0<@M7{X=lQ>Q$-$E!WZ$Hp$=h7dixCH0e@4fP{C;N-dHtSbJZ8B0KjZ2hKPdl4 z{JM_CbHa1axyg6u$nJ99`LNAz;Ro?;AnnS>$>(vMa_IZ!%CYNv4*qe@s~YFS13F*y zeM;-?2S25~ctqB{plB-pDS+61CWdP&hw_BdcMx*#?SD7yNo?q|M{Jd^`rej`Dlnfo%hXK z(L3u>$n~dns^_?m=TDse-rZMycs@V`(YObP|1)mgx3VuVKI3^# zByWDYpMBHhpZI(H!=2yo`SNYAlkZKt=HKOUQ%}5h-`OsD;=T|+ql}(H{Um=oc@)O2 zpS{D)@6qnb|5X;vr-%PDAAQgNHQpaX*4gxY)m!Dg4^YnHVCx4t)rSAmaW{O+6JOSH4?T=|wApUmf{|89Her|pwYKjS&(Px!a)!;aVX zerh>=aX)(7$T%o(OmFx4>v%W+hrZA2l--AYb^cF(M9-|ugV<&GSM71OpL~u_yR@Ho zobkfpX%C)Hzh@kucA@iyz`Q^04T4&QtAkR^wOWZ^rw~53?R$$4R;8#QXYopAW9>?fo6{!~@0`j{nP3 zyROn-{=em@zm0o-#ea5Owl0M{SDv!tIltSu+o@gkAP<0C!I>j`oPZ|7ifH=4|qW8iSLcfyp+SqL&`@svTubC3~f*S?DvJ8Uz``X zf0yxd%G=+a$7bBDi}*>%JoBvI{7CG+XH?E}9pgF2FX}()-E|v(vptb{hH|*=rMxo^ zpPTZ;M{yz&cla58mwe0<@^0`Y{_blzUXc0I@BGE*>95X@=JAYg=1b+Cd`Z1~-SdCU zPnG2v(F^C+h^yqWo&2%9_=*2xe+Tc!epjB2vU<3FpO5R?yU2lFk>k6Mvi$1se)J39cSYpb{2y|{7a~9B3giDg z2Pi){?>qDUGV{&wlgbSrM*Z-A?u*s8=N9l==hNYrormT-VEXx-D{_9IjD3a|!#{X` zaL%FVpZJCQNs;y_4{B%U8~(TSb;HZH3zIRKU(~sBV z59Rgx|K6VSToeA!IVSeu!*7t!Z~jBQ!_)B|C%gwdqwhb$r=d^&hhrmrpL&LWqrE}e z`?nw0`5$85@1+dChdi9)v+Q&7d+>bPn=-upMtCvr6XpLrk4L|p&w~f?e?Tb1JMuk1 z>gDa=N90-g|76ZzisNtafY|-+ckmGSVSGsE*pSou&h5qPo%|j5ZT=6xLLTbnZRUI; zW%N0yJn}lWiyZo!JdW)X7xk;W#m)IXGW`z!$9OrP>o`tcGk&vkj^}ge!~5eu!{LdN zZ=>Upk8&KysUAXkHs%-kHu=8zJ;sUM-y!<=>iX%g%7Z^+|9||PFY#OEdHQEPBOdsj zMn98xWB-cW$Q8!7X}`V~IN#^wc|Xr{v@7Z-@~iC2 zPrn%+aL=>(dzd}P|2y{=#>0s8qd&Of47c8tkM=zO zNB{DBCojl#c|!L2>LWzI_KW`R{nf92iJ$5RmWzYI^S!<5;|V(lXj#9YJ?y#>`)q&X zI`I%N|Ti{JDRkMxZC8T#}*k$zDQ zS-&I4=?B##kMeK+0e?N?8ojyhfv)Ql-`>x9$$T`ZKKD9~pS!+$o}PXx8z(ysZ5MlR z-`FKT3GIh*AZLCDUiIC$!^VFtcOGhR^mMhia>--Tj`Cjhd9Ek-`C#wI7>8xh{+b^` z{LXdV>-u5y$Q7UZ^EulmpQ9X(AEQt8tX_xD;ePbJ`=5B2`3-#_&l4sW?Wo7+c;Ei0 zeosGXoh6=;hdfC69A9#V-QT>&JmmPwBTn8JKhU2**CTl@=2PQg5Wj0)7*y^(-;H16 zhh7Jb_d)L4eBN(bcAmgrm@n?gesZ5Tw139~Z|!)$M*KiMY(GKYPi5>m^*#5D$b0@@ z!I{r)z3NZ4bMk-qm-%j(ymuVG&R@v0_49D-s-Nxom45IG@#GzwC-8IQ%JuBb`{{Sq zImW;9CgdBw&vuxvX^*&wZ;XEw$A0=JaV=ki{r}|i_ax4-5wD#8lV^~pi+|(2ZuR>f z<@x6SAcp6IAC@P(^M7+*E`BML_wzkd__XA99G!PZ9{4}n=l9xBe)5M8evmv){_>X( zC=V!a$@#@!y;_0ymxvE|G5JA|^L_G@zy5sR7~T)Qk$T26 z@Ao3_6aQzt#rMId$p3+y*Sn(Q96r$J<@q=th#o_EKm3V$?Ckde`!1mTAN;F)jeHvY zYZp=ePdVaI^)J7R2XBObdG7Nax<2zMiT{b6!=w;j#dT@li&8od}wmW1J*u>e)E%%cCE)>$*SbB z^JnhEp4bh1SMNOinhsv$;=Zuw!zcT5|L}jtUEjwfZtcJCRL(ju`4ajbUa)%B9s1o^ zKHI+HUAcPE_G#yyKb1$7pPNs`YlQI|^?Su@KiBJ)}{<{hU~S z#dvnUZkcwu51f5Sd13n@_d&>wzLU58*5JK;^MJ`8E$=*${?9V)Y1eo?uOlD+0UwGV z^S&oY-UKo}%fI{r)ra>DKfwA)p6B^@;@12%ls6bY@LqoEU%45NeosEEz6X`ZJb3du z#HZh*z^~Ltb_i?NJo?PH@A)_TG5hV@AJ3V8PM%f1g`D&I7yUD@g!+qdK)wFyIh^8v z`2+uDp7H+k`(4F}GuDT zGr2|WyzN3emhtC4Y=RoY(if;kX*l;MA+<<^j-r{>mp<_B#71 z?%N38O8FW6e@fQj%>!1(9-Dt1JKyDGeqy}wYt1ivf9dlR=kEVD4=C@a9*KMO>ALK? z%{)gLoOZM)*;yjyvp|MC!Q~?pTTp!z%J@zw8wn$^#GBggozj4NiacZ@=-8jZeRpcY?=YJqJBkzEM5T zxi#c~=TVRHa`HapeU|6DaQCwIhA$#M?$_m=tAGD52*2xjq90zPr%yigKYx}x@2j5i1K-osuj4iN4jy^0{9owz^6+2(AJ=nx z#D(X;c#@n8Eul(P6o|W;^?#A*c@@Di1A~%R!Aou@|;dOs=mNy?_zw#gD z=k(7yctzwXpLx38{pOpK|F@rOKe&6&leQF*zK zeU1FV4-e>guKhWllMiYfj@$l?7xI3`Gk)!QPJR9?T7SmF)@OPSPkrYv_8V_<>bv-# zxRQr#9~%D_=Jz4b;U}~MG7o{wL!$mR?|H{FWdHc?lb^0X=3(0(e>D#+Ki&Ib^!!u! zKjh2~&+|rh!0*%}_m3U(=l1<$@2ek-zi&JAyzx-GPbeR*yj*9#YkyvO#?!b!?Xl5) zh5KUljU3u(Q2nY$&;9w_o%eI!VxG$|?YF8=a!eSAjj$9-R+@gBch9O=i+e?Nv#dRFh}_t4-|)PuZr{PlZ0<)EL5 z`}7u`^MiUF|8kx=*JIXk>cjGa)?do@*SdL)C+f`?_I=mqD$@`Czg`cd~ix1SvS-sAj2Kgh@W3^wnf7xfU& za~S^-Y>fiBv z@9OpUomcAL*5@Dlx^my!L*MwD`Ou*Li@f;t$o-UuFdqDaIC8#*r}^%q9G>mzAFjK! zU%&79zn7S=`GEBZ9R5#U;dgXbge2aVg|1Ft+F{lgE6e&-H;^U4EO{{D48Jg68y=DObR3Fmi2 zn3vE$_7de|InTlS)MIjPkp>0`+0e}`F~xWhZj(9 z{m(A#{_q+P{2lvx&OKol`3uiW!TVVMr!VyXhzIdI?o%#!LjTW0d(f`urkrPJmpHuQ zd;ZV+;aPa@iN}fW36&RnaBgwz!T0D!Pqc^L)tl!f;kg(Oyq5LOU!9NZT%6~j=+EnO zPK|Y&ea{o(XZlUN9H`!~3wl&u`J4DH))(u4D$euQ{>&@l`FbDuT9(&~-$PG47gis} z3s#Ot46z$>gyem+hd;hU?&m)C*}R{5j(^5?)fax1AB6FJl&}5+&llf!MbDG!x5NKA zzrsuNdl!DoegZ!iUC)RI)-~jl*BfO1q#l3R*X7@b{~JEu@iJd=|Mws9KgfJ!dz}aL ze&e0-4d19g=!eKfnQ>oHyW}6(Nj)&n@_h={ZGQK4oj2d7Kg!>H*5kj%$K)-=%ZVr7 zh@I$PjQ5l8L%K7@V6&eK>oEt|K;D}>20<((fR*WS;ex06rcy81kMm7Zh$p8oY~l;UTW{AA{&xu^uuTOk;zxC#& ztP8&1Z`^zS{a3HJGrt;iAHq7rendWD^MH<1IjDDhmgOO~JdXR^UvgbP3!nTjKfT8* z&+m4#|2s_2bN%{!`+w!g?qT~;_&DSatG~u0^R?rf^FfyL7sid>IR1E({1rRLZ{er$ z)xNiczT4-7+rPDk{_Z(8+O2&0z59^jF1*`k+fTXk=hN=-(A#glzx#S_WA=HECofT) zs3*poAEnQ|zjD4%|I8!pv+?`*r8^IJ<^PC(ctG>%-n#>hfAwlTnW*PAHt$ECWO>?= zmmn_L|MCBbw&(oW_|(hjopSoTqU)pQ`gnfgx;R%KuD8GZTzCDQ4?R*3?so7W`nlqJ zd!2k-e8_Lk>t&yf={s~j!oKx`T-p1l_!;BnzWnOG9+xMJSAWuiq6|pYS)AI zROtQs3Gr|JZg1-sxyZA?{QN178DHaNJ~qx+w{73@{{DgSea7h%|3^Gr=ZTpQ9e4ar z<0tPhjs_X`*XRGXKWdL_ezTuH=O=lq&iRpFcpaXA^HRz&*S&x9f66=c$UFXl9?66C zqbL2Ur})x+-)={H%G**u`m?{U%K3$uUEbl7{N|yvF7ENw4tisKpp1UZgRW)t$$Y&1 z_UrLDZ_jf*A0n^*BkH&GOF#9mzqSsI{O~sL559lucYc@$SfAK8S^xVVW#pXyxnZA2 znQ`(vVJLq>8Gcu!UHOhV4=2xe-pBpwGmKyIdy4px?=ve0d>K5Y@8!EL!upYyz{7AZ z(ChG#T$jIuAJo4s&;Mb09+5J95a$U)#$$W(kJQ8ST`}G-OfR8+()do^kMYQNa2>vb z@x!+eADokW&;P{(at=;@PgL)B-VeFu|HPjA;nffO)?dA}1^@TMt3Bqe5FU{Ek@2xE zs2}7*KhBrFFA6{4zPa~%;r|$i-<9*dS>|WX|H0aFK9KLud4K$0?QkCO*DpD~Kag{Y z?E8^}eLd$Q=exF3d-4s#|GCe;^M8(GctG~$@PUjMzEHc$ z|NZ_)J@Ikp16j8=|EC}D|Gwx0e#ZBA>Cg9h;hp6F`o141FF-x5i z#GT(Q^c*Jl#h1c!SZ00Txk2V1zke4Zm-Dea1mj`d4w*+?$HUH__?`&!jD8bd`K*)Y z!ynBz%SS=yC-cqoe)_jwo{_TsiSgIro&P!cKdv(##{Gm{5A)~RjrR+c$9xXCb? z<>&Y_$h`UYANuF~AL|gvx&$BSdWBrsE#59~E`d){wfZ(quD$cZ0=Py36xUS2kOjZd9@2YH!sV*Wo4?}_GT$^#$i zJmS7D{zu+`ejU&02gs>D^dJ1r{WSip|7y2uJoX&ucn06;ch{eM(#Y}5AI0;9cm8kU zPkHa}2kK|V$?y~2f87rbpJl!lPc5>JxDOMtKjjdA^117Krh9*J>K8e9UU{bf%G#;; zo%3J$=|=pUvZ!Bo-8hLS@BGX=UYvf;xY%-Fx8wuyvpedS)}wd)h5fdEt)AqU#R} zyzlr{e%EXHKlEtX`M`Om`3Akl>u^l9)!@WcDOrGPM zg!aGkfbs+JV#R&vJW7AftMPu}o=?pW-G8#L)b9G#%-d&q``vxszs~oR)noJj^gr=x zzf(s3;$ZlYi4*T1zu^AuH^ukFnepa6pM5d>h&&MUp7q*GJ@`kDSDp>#hGIO1b*(3(50|1NO)CL;dChw_nV9OFYQ~azFFv6|eg0 zy6x%z*>&P!*W;hNT%M_aXivwUHD`w7)sem(MMw|%|!?DRj!Vf)BaKOu71FZ&|p zZ66%^T^8hbfAQomji>n~v|hhJe#Up&2YI)j^Sgoek>_Op#C6g3oDVzi<+?KdE)V2+ zTH{?_i2MP6p7TgU$o@>e55A7;*Y_vk`KSjQmwFi9#r67` z|BDB#efS!A9eI-Ld%frP{O|{P73=YfYgzgBdByatecY$P%OXGLEY_UYw(id$^XS~Fu$Wh~Dwj z?xP*%Yuh{dAN;?1`j_{UKQ-UIzW;gW|CD>qsUpAsN6q-WKfLpQK8L<+XLvsQw@f~V zobg(gpZUMW4RSx{QGfX0j~&A@|>X*!Pb<>Y1PZ?xlbDzYso< zb>Z({^8x!=c*1x;@_hN|-V63UV8(%*_`}A=88-fHFURTg)#Fd-DZUUnDU0~0=K!Z( zzra7XzUlXFSM`FwqMv8}uXX&Ir&KPF5s{NPiFb>?3+<==!1%pq+|QX`?EZ|G@*S?9 z`HOn9-uz+ze{lKxAoA??-;tS#f z$1bOx@}CpYyY|z6$3IVhE)Vg$@AMbtE)I$h;>Pr_4CjYx)dFuiB4#dEUMkhrb#RgT|wN z!29HsJumtW*+0*Hw1@xH?vq~?Z}0qydY>o0@Kg4Q@l);F!IMXbSK9k1BW|zg{d<1!e&yZs zr}-h{Cr@--Pw}lDxt_ma=g}YfZa$DVY~E-d37cn}$9&GXbbjPMF8rNw za7UiczrpK$@_r}(x8-Zz5AiqioBT-qJ8s8?yvW)7dD`jpXZ;?z@PFe0eoQ|#F3B%P zukej`J}y1O6QCbaz6?3IuAe-|hvPC1_WIy+)1Tv#PeqQ(!w0g@)$cd&=Xj{U=Ow#8 z{n&YN@{Z&hzw^GzyBuh8Og_BEQ>tzv%y9cpj4XQQ_|xzvm~Ai|2ba<@4$Ed{^67V^LurF`YOwl z$p>&h{w4nG<2_W${T~Iq9cAC+J$WJY2v3AP*!P3O|Mgu!&;M~AkadXrHg5i}_FS*r zx9sy%$l-Z9@j704Gtc{Z?vFScoW`ai11BhOvW`(gL=<~cw9A4L6t z@B{W2^8G>Dk#F6I9^he5-2bn__@4MbpBw&<_=E@Ke5C(xfgI&8&Tr;B@_t0A=bGXH zhi~!x3G<%%Klxbv)$u*?f6gQ56W+c1rXAN96%ebR6<7owth56CFSK zt^Zf^v)6p!cLMoeWuHIKlc6W`>hQddUn`I2;_y4=e?HHK9_EkUGar-s$P~Q1FW%}FLeS@>^yN(+d^l$t68*)$%pLsy- zNZyQHeSX^adGdtvBlIgD=kKAk-#&fk@#Z7fJj3|*zR6S0{N$Ra*B`&*@jUw4SpS@l zv;7n6Cp7PGf8}{?#tHxDc+Y(nd8XIfN3g%uUkA~T`#AR@=tUmR{wSMoHNGpF=icwz z&y|mDq#eo|(Sy&8-D+p#O1_QEhvfU^|Fr9Vp6B%Mc)s{N=3nEJ>&&+x`nKGC`&^Im zG0%`M%w#cG!AypBjH=zTRsqx75`@Ua2df)KZ+FM>PelPs#JYamy z@Lab0u6)jK>N!6E({ty=;0>^UC@+WpXaCdw#&+DFc|PgRAJz_N+}KX%40rqbUHc5} z*uFNuQ{Maod^i4U92&3id&arz>E`?C|6ZPU9B<`!{Zc>vyyHu~>er)h{qN*S(7%5D zV_00=(RQ&UTfA|&gXT}N@+CRUT{*jaUWYBiv zcZ|!E-{k({qzq={0h7f|BvT=SHF_iW**T0t~~b{zY{04 zqnxw;SH9xp2lmrE=KSJ5kAB#{g6vS9)3gp&-1(8+TX}HC^IhPxIS`wz z^LrDvZ$7!>N?!5Wp6$p7<1g~1!xM8q>zw`ylJVaWeuDqCj`s`oTlqNO6UOfHb;Hxe z*Kv-J@qdlXkDmAATpasV`i0*azEA%e-mh|Y&@SkQ`FPNM-0*?^-v#_C`#}5Q93T&J zp4<0$Pb7cie&%(*;|G7|{_5wi=a_%u|GXamXIyaI|NjW(|7`cp|G|5~Tf*mYPV+Bc zyhA)7_3(e#}`>)7-@`Umf&NK3Q@Dtia+pl+oLAZ}DB{c{avHzPFM7)VK4{*w=FWj(YUGB;UQG%sj$%=0o?BpnlPFyFL1)9A5b$ z%E%YS1IEY1zsUcoFZRoxo1|U8TgiR2gWsW#@XGgL5BuwTm-b)3%qO;U@>t5PA8IG; zr5?3^{&OPZ82%5r_oO z?1`P@4_Pm#p7C2|e@Z>$^?L8st0(-|$EKhUp``{et^ujD23&+Sk4H|<&8`Go83fBcw_sW)#JRDV8a-tm-wa2v-WPw(&W~;U5m}X4?>*rZN`DeKPue$Rm^Bm&}i7(27`+Asl z5cfg*1BoktC*!*E+#~BY?u)JuD>E*xe}uH}_(k%g_3yFxCm$%+a~^dZ&AY{EIDWS3 z7ke;n{EPJo^9lF8KA8XF*Yz`UxZa5m8lKMUj&tY#XfM74zG{7+pZfUeVDTnC^G99h zx%jL#e>~?)#;5$`Ysatr>viM9dV4(7kH|P#4>%6nA^$n=4tigGfAs%c?2EAn`(@h6 zF0_|Dv-2IQkA1y)+I7wU`n`5t>;2x|`~BU6KS6KuHX{F@vhsrQgzs}VZX@vNY0af^WZzR zi@XuMk9la&yrn<&UYh&9>UJLclUq1Yl z`GWF^tS=`XiVNpiYVJKO65C z?))BhaGu{WK9KQoKU~-Ot~2)bI_DRkoL|NduYReYo$I7^9j3in7bz#}FXm;}CG7WY zXXpQzFO*x1hda@AkaoA7b$v9~tLO8^JN4@y`%&Kc!Kue{<`?%@$Y)%6efC%Gw`hm^ zt*Zvzf3)AYU#HD;%H4X)@vQ4`?o$rw=cD`7b3bv1+G|~p)@~TD5XSd~@gakZ7x|y< zqJGlTAaQ_x?+`hR6W`}&yc3VgPrP%EL;Q9@*K_9UZ?5OuhsZ0$56B~6AMLv$?Ng>5 z#`A2Kc&dgLu)Tg}i4f;(y?yLRYE+6NMc+T^* z_x(Dq-47ebId0;H`otkv8U5MLAo8b|(Dqz68UN-V?*Ej0fS$7B;Kr@Tc~*uh4#WUIM>0uJ-Ht=kq>Ze;vNS^(*?#uLftorvI$`!|p%% zmv(w(@42oX*8Qk@HV+K1ZhY_j9`PtozoL2=UQqdX9y{4iy#C$$|BOE#P~^GfS^dX& zqkeX0Tbo#Pb`h@I6>C@)SsYdo%H>*rUi|K*pVafrOH_`c?$khpMs<=Z>{5B)VS z$3xsB>k8z(L*w=T8~;aqt0xipE2DpY*BwOeb^YNy@Vx%eKeVrUHm-{+<4Av9^>4ha zer*0pj^a=JDf}OHcV7=@NSFFc58S}C4x69Y;>w@BYmzVbY zJxYHjpE&PSYnR>L&-QnH zR|wPPCtAz13dxYjTIgQTZzz|J6Rl?>+iEi2knro_V>h@A1GnG2&p* z_>k{||3dHNk5C?jxZ}OZiPyE=;u3z3es}cTA3Tib<3;wjo(HrHkHveye#dTjKIKR* z-(!Zi^S#&qe0&EFz7oC<9#S5V@nNs>z{rh!(edrs0igEnr z;sHW_mE+uB$okTAYlHHC@PVusxDI~0_%9G%&g-1x^1Wlv^|3$Ee)4*pXP^wA?re-wp4_J^_1L4`hA_hsQH+*5djEDOxGOwL>-OJWTZ$4K$_xvCB!0voXzZ0>G>j&2v`c?j=T=|cFu=CTO=l^ECvK z>x9&$*7N?0Sar^_*D$oGY;1_D4ISOd}edURVn024)s@YfnDdkzG@x1Z$8plqfzja@VUF9L}c@XX+e|)cgpuN=_ z_E1kdrti>vt2}G`p;zM$zR&T<`&H&UpziCOzvTUp*LGHZfcEcr2d`@%_`k;Gc+h`( z4UvoM$gh2d$C|SKJmu&5>3zra7}~#j)nDT2k|#{A!RPfl@}P&=FV)Yy?;dYH?fg`K z-1QL8ccSO}Mjz*bx=?yvayVtn-Y4zJ@t~>$pNtycIAD-{NzWPM3 z@__Px?SJuGuXkV6Z{0s559<=J>mko;FZb_WpM9tIpW{6LWgO^{^7FY3_X~4AZ7*y0 z)4wXOsD0FH_CSy3#X{ucY4*Fw9mWGzCQcmJKA#acTqlmfnFnY7cAO_4 zv6optAn%T@`y9vof4Jk74`dx-+)jJkFJFdhd|Q9@x5-OC?RT{FS^SEOAOB&W;qN>8 zLw4R#|DC)t`R8--=JAS^?=`~zZK;--2dDD$vdw8W}aqTW8(X zA9vntMfs=rCfnWPk>9`Ycg}Is?niv!$piBL8SsLG!{fo{o&2A?-hck_J9wP`W1f)z z8{RMe?;QVGM&5oWaDHEZFOm1-dw%5WkbG_aR!{zK3j5VL_cuJC=O#Ok_p56j;vDxc zF1g8b@O-S>{`}&@;0;0AkN<;L0vnbp1d(tRH6o=(*F;m-B#S z&$*GeD3iYjYtKC5{t}*$ayajYx^CUi2g)B)KOS!7U(^HnTfJZ}|Ho#|t?v9$ywUJT zod4rjiU0nX=Xg)p_21eL{mb+59YOT(|6tE`)^GY@yw}dF@%x$n5$_km>tWxW*W1qn zI!<^#_*&}YuWy&!#MkhDmi-?P&;MZ;dB2ta%kQ(J?Zx}8DF0VI=Noy0{$Ch-uXfh1 zte@3KdI?XyZ!fRs{`7~=Y4%>Xc8M20?RoNX*o}Fe`p)nB`9A!L>#q>Ia36HtApgAf z!}Z~-eV-_QMSrv2pq}q}4zA~^u*148bKTlflueRO^2 z>DY%L4~Tte_ha07Eb2R+9Y-I#e%AWPHREV~wXV0l&w7e_KLzP`)?ep(p)%{8X>a7f z?~#MJV4X%LLHU#~OH+R;DL_s4NiJnVLUmaF@x-*mlp@;}Rs zJ3Zic$tfoHiTgT##!KF0obh?#+OGb`xP1=)V?O6Pd5oQKM--`(-TQxEy`&pSN*CqKHwu^aljy!U;f6VjpLGg&|zF9r%pW|P5^2PJT`%N6=cg|nL)99J@DH}(F z=y~RE{df2|?fh|>bpZAFo$(Hb_j~65s9)ZAl`rrgaSS-U-9J2#vaIrKVi>sUvJ_M@qE0u zQ9N|Lc%VP}so&-w{S5i}{lsxFPrEPq;o5gQKj{ba`%QWPMenHQ6{aVR(AW4{_wzdS9LcTS|=ctOTF@rM3ZIcTT&%zp-bj&i>@$ww*Y)Kfp> zzke$K*Yoge#DVzCU%8KF{)1mo?wz0KcRKk%ctF}6KG5@koZq!S&hPaeu;>1U_mcqxt@?-_auv#QS}^?AY%E>wJzJYuWQ^j=y!=O+3627QV<|JVO_{PN-p-~r?R;sbwmJ;(g;%g4BXe4Gd5|68f| z>xZ4-F|a%TGeW#@-jIAne?MH~_xy@HAo0L+@_z7p@IJr0_yKsq|8^ns5a)~VFZc$K z`uM%Ppy%J@L)hoT|GD4qe|Fu+v!C|+g76)jGX>A{fXK_a2IOVGs2z9Suycf*^K*QI z$|Yaq|C4ym54k<}_h;|?-_I`o242hajbB|^lkXn#KiBYW+Dl#vUdDd7&N(i}`F9UJ z$p5j9?!4dY^MCSy`~UsI)6oz74ej$k8-uO`><>Ojd&%FybH>xf?_FlU+GG48*XOx!_DL`BHYbmVzW8pOc}act9XZCqb)G-($2Xd9wPX8K zad@-d1D5~e_bT_pmRpAn&jKIgxI%f+=kt`#ckwqT#w&Slu=eA3h%cT8k>^C}DQEna z{2%g=nvK%UsLJjC#ymir$Z5#H7Pibx((e>+aSorldX*(o0IyiVD9ct_%h>tVn1 zhbRAKJ>yY7n)9dn1^#3n$xpza%Kx<=MxXw!>ie?$It=}Lopqb?i?dE~y(F(h|Fch0 z4|ARb`PgqM=gJe{-}T@AsB?WH{S#-%qkWBIu2cRgh`nux{_4N|8K_^a^0iNPy!xBt za{t41)+^nw{))2>WBfk1W9y_9UFR{6)!&NgIrJP8?XwRaY#%)JR{cBPRWH~-JsThL zfa#a}tNtr9ey)S$dE_3{FN|y61EviBH;CNy3x7H2earE^y-zs&gZ4W8?$qJzv~#eU}G&;qP3BueVJ9#`80(k3BC8|D@cfKhJ&h&G1)yJG(+s~w6b?V!ASe$Kw(@O_TU zGI?h7>?A^!&tg*^N38{}F01(63NPT~XO;XwNR>O$(l8_NH|-|^3! z|9O?s%kX&eS@RyPypjAGe4X`Qqx)gUgMQM7{04j(dXq;ZUh^~LN6+#rJ90ixUIsbg zli~r*TkwGR6X>};1 zK<8igJ@6jdi!%H{==eR?$NwM8m&gOcGg|I?xblCtJA8?GX81DWN&ank!r|vUzqyWA z-j8vjpY*X}ydQ`{Jm)tE|HpMv9?y6f9xy&I-p6rpj*NUVsQl`|^OEET&zJr6JHkVm z$Kav(pAepxZ$#hnh0G_~!}nwHckJ0b6gKbhocVkBHr6ZnJM-1x%Ks6!@OtJo^ZCjD zo#pj>mwKQd;+y`HXGQ(d_tepce!230>D4?UFHgJ?r@y`8Q8|rM-s^QdUSHq)wVh}F zFFP4m!vkiA6<51)eahOy^L(r;#y`f7SH5rR+dgIZGmv$JW%C8UJD`{0^>!Yx>-d3s z_Pph)XRhN1*pYP!7!SyEmV0kogkRk4zS>uLU01koKlwlOga7cm5A6_#E9RFco^o4u z9-e)f>&w}{X%GFJb(VU!?7EHl((#C_H_rW-_wV-0jQ8A6ukC0z`}2HXJl*h4zF$he z+EYX>{r;W@B%ZDRjP!@zXPk}Ob&b4Jd}RC6bwA?#-Fn`A%(I?aKfYeCo$Is8q4t{f zKXT9h*7o=PZ~Nyk{fF5Tea`stv(8uE^L*(u)IQ3|{K5RoxpVeegRZxYOU?n}Z~Pyy z;~1pg-TS~kuf5{^hF8Mx7?=7TUe0x-`+4N`K4@M=pTrmFxdH92KCv_HhR^MLU%wu` zj{kRmZ3n$mMsMprV~u~~Xx~4b@s|C*f{F{ zl+QB##QF~B-Jzu5V+U4W{J6Cvj9nf%3d<25XfSs&m> ztXmj2AjJTydd2;-0;s(1gu2BErK7QhL;!yvXdez@??caXAul?Ci zyWSbJ-6tkulgzv zo!IY4p!(m@cu=2{XXGcaOZ|oNF3QWgN%`?({Phl7PkavL|L{}!zI|Og>oVeC`sup= zql~=#-^BQx_B5{07xnP#u>6x97$^BiK44HkFz>DFCHrUnLfj2T`aG();f2`Wv!3EQc_4&ufk)#$zav}< zd;A^&j|AW6{}nL5@xP_yBYCK++Izk#ADf@`$DhvseRK5#PbhM(4}HyfKKZPl&j0!R z@PYD7j*oHLo;(`)*Yjt?|Bc>QC(HZs`;7bVka>xHA98(r=?Nb27aI?#e?6b4^gJBn z^ZeqkuGO~h`x0O1fq4D#j|lHa{tv&oo{Rrup2@E9fSvz~|MNcI5ySqx7sz?Qe|?PS z?=NKD`MV7{_xE;P58>0`Z$i%7!QcG+ah^{8g7b5{PYS;Vk2m`Z;)wmAc7S&xj#q?# zqAbe)d2X=tf9rjD5$eO^xIdBioAZC20}SPp;04&WTdBd%+?4T!elzViZ#0iMu9;uX zvh}*Z`WbPp{m`%S3{M|l@AcvT&hqG$_S8Gb^}o1~{{M0*cYVd-`?9OgukBbLyU?!n z;B}2>{D-)H_HXpXI79VGz2Y&RFFeoxX`k$5|Js9fjpJk8ML(`5c8u?%eea(<;L86w zFTYwhyWW>?MBlV`BL1uYbUxH`jO1DU$@Q507J6fy;C$>l1|FsBw(odt7yZxpx!?XQ zT=!|MQ(5ow9$n=SJKXQHna^9V+26ijqF?=5WZpJTcVvCZ^$_`eF5b`QS(o^{{ZLk4 zci8#~`Dg#xI(|p)Gye8{GhXey?jv1Ke!RY-zV?}Y1kZ6@y$&MZx$m9+XZ?#Evs?QC z?cDl1J~Taw`v0y^^{9Ou&+vctWBkeYAs=}Nevde1Ut@icy!q)u=396{{Yd_RbAgU~ zP=C^H@qznz8RxpM!5=1mooBEY>vZ)q_C3pEC+%Ci#%20^?ti_1#t(YsKB(V|>EC!| zocgKj`|-n`cUNix`w;g@w2wdDp?day^+ESdgXIVP-@IpBu^t`2 zDUS8yiD&%jW8N=6MnBJa#5mI*hlg?h#QI+UI`7-g@HE{=Z{w%q*U$D*?wLQDR~)B# z5c?LlTvvbS<oiy|0{&4=i3l{GR8#PPywR+TQ4E@{s4o<9EXJUs=B{&XViI zY5(kxGJcI*=0|xs{n31}`+fc&&b;UP<1EiSxUWO4S3kx9{XL(%MUUl?leoJ@bBn>b-(et%X6+Xr!3#c|5o~)GS=ztd&!IPf9{LPhdZz7Jbw0vT#R4& zCeK)J&m+Z|@p|&2>0`yac}qLbc{S~=pP;|W@;-A;OukRvh`ay~K>e=E_YW9{`4|2Wx%gctM2@Z#mz;ki&-P zInU4WJp2;R!=L?l@nqy*+d~e|(am*vC&!C_4KD`YgkKRS^2wv;{0%+gC+LIUqZyaz zb$G>ZE`4zQt3TdHF8$Ix#P2%zm+uGDuj2ya1H<$DAG|2fhsclqaX944zJs(sOCX; zqT`o$MNaGpUx*z%_a|y!^h!L-vm%%NICjV`p>~nq!=C!{GY{zRox}I3&*w6Fmrsh{ z8-)KduYg@wf1WSEj^rtEKX=#puyE(|)Dw9)9tk;8 zcwO_G_v8NtU-N&(ckyMvx}m6qVsU=yYHL-c~lR6&&~Hd>2Kfvw=P^!dH9YT^*=_|Mb?w=W1YwIA@e@vkoIby zcw&B6&VAiF`yJMat((=`zCOlo@u;^Q(I@%|XI+bam2*%&06oHIXos&a{HJU7{$C$uJe})d z=l?{-Fj1 zxJh30YX73wJ;(4LU;fP(|9q{J(Erz$g!*l~wes}*J}&Hg<_*i_3G++8C+z!k+T(r* zKS=rHg?X>U@y&Q9j*Qd0GWPJg=R48M$K~>j2gQJj?ox{+$2jkKyW9Jg*hWB8B=mX5^K9SziF}{Gt@+9MM!O@2`@NYjeXe;^ zUf_=RvmX0o_T$#`{X6&fuFJGL_my}2K!2R}F4A% zW`ccPMgCDQGmk6plpW8RxAf07o|A9Kk<;t@dW8Pfc11dlA22J@7ds zfBBq9ee($O+PWS$AJfm|8SPNMa6Fx-#Lpbp^El4+zWuCnBp33yALIPct9tPYq4NUu znIE3f{@4CieLB9zd5_e8_JjPRao?kQVII?-&*;9L>+xIc3%`Gy1LC_$+-E%@-z3jf zd&IB%Q2K!{FyF1`Cf4s7abLNOC-RH=V&cj;s{G><|HpUk;0O8c9q0Z!{}vA>f91J7 z_&4RJ9eBVW-uXYy@$o$9`_w#7p7ecN?~}K_y6&@n3eyMra(y6_~k@0n(b6@a&@qqG& z!~b3Cc-+_S-#zjJ=K_ZZFY z{9o_+cHZw}?7dZyJOclxJpR9K|5GCW*LgqI$L&Lr1A9L6FSbWL_(b`r{?~(ZfcW={ z)L;2O?LR!3el$Fw`Ij=k2hsojJwW4&>wSk1` zpZ?N0zgIkYT z0eXM0rAui*pzJ{WZu2roYMeQx)Q^Lv8YiFtV9jpwpob`{Y# z`hsUozuHAR(!c8o^lqM|9{XRPJNdrdp7FPHo^yZCc<29&Px{~IY2`u zW9!lVxxHWI7{3`gl`DOR-8Zg2T~TB_u;N+cu6jKeVlVyn6~_C8?yq?se+p@b@-zRp z`%B}?F3Qb#_c-o)^@_JwIQ6pMPeJoQ_CS8m(>(Kk>Cb+6PI;%_^1?^`*5BZIe#7{@ z<1dWw@<96)_BHgsBKjHrKtKApyz@ZJ57cK~h%efCz~Qg#cjs@ENByYJcp35*FnSA3KGlE0J#G(QZQZ@TYz<~%gxru}CgN4>`DeS|*0+F|sk zy_FaLs_eL5`B6MZXg%V^afoYsyPbA>6Sv$Ko&Tn6Jo|k0cHWQuD)+}A82lcDd{*F68`+WQiui!jkJYjd|kwN{ncpKi&cpRS3-($JYdSb3C z@A#4J$s_tcBl*U5>0kdGw7xtFcDB6Z`g^I*8$bPSx6W_M?epYi#)}_y9e>~Rb$L%L zF2m$Ik#@1KxXa6YY<-dS0PUUYtk-4N_rHAX&yZ^^<9D-u+t+i&2s<>p1i^`osTM|D`*w-&K$B(YEtEpH3Vh$C_W7 zkMv*T3%}@kXg>7%>W{0viD&)l4(0vgf8>4O`{047FTWM<<@lU8$RFO8Gea;#P>0W|06Caqi1+a`4;Xo zzIiX${^va4J@5D9L;m&r;>b&T+BF`qbB$a_f1K<4_TnjjcOl=C``s76zuNoiIv@A@ zOKy0k@2=+HGeFLbeRo~wJAst>{}0|5=Kp`;4|e?Wst-RAk09^&_82cbgnkHLgkL@* zJT&~3dfLyW!FMsvmEV%Tq&~a>ycT@iihk#harho>{2%LP>fxuz%RKVTKcNr#JrTY1 z|H!--ZGVGT_g6n}i22|F@9CyMkxa9+df?VD$Ah-K&@0^*i+Hc|Yet^oswlh+fq< z*KLO~{oNtsvOabjJ8@k& z)BY~U$^Xsz>Rf-{tsl`t_FU_`u5z8euD7rU?Tp>gZ~GvxcmGetlkYprvp>*}K3?Bu z_wlFv3S`{yCXOe&YKQdCc|hzoXum7Zclu4`?8NiK&-i@)gB_>dY1dtT{bwCF_g6cN z-L)s}?e@@Lr`@%G=Kbz_J-@C#^Mw5uXX#0#-s!&+hx$FwvkyY9@Hua|FCy<+uYA|_ zo&T$y&Vho;nV$D?6-U{H^2BTLsDC#e+UvQ{=hr-8Kk02n#&OzbEfYVKjU(;4?iZ*3 z=`Z<54)`q}{4;q)eXcwq?ZyM{{3_#f+#jF2JnKz)^r#*5xBPDPN8`>oEk3am*Nd~Y{#|?M zD?5Ss^NOn-*Lw4uydV8>pZv38yq~Cl zc{1K*jSuvs9`5(c^3VF2&)xBE`bWH9C{NdS0zC(~^L@sPe4p)oL+k6`ck!lt`p@VuJ^Ebh4DQq3TBe`#IpW>^vEM3h*H1Yo zzOe)O(suoQnfa@-@|ORbAKZui>ao7Zk6h;u4_H0g=^RaYcg^SKi}DoXGXL-RxqL-@ zj$YtlD1&}ijCopq0rdOw`nhtmkF9*7?Xu5C@A4C%{Fv8&ah17$hv<)awfQQXyo&y2 zebD+NY~C_HS(o$ORqN*$_@U=hLHT6HyZVWCW*rO9G6+w?{w9=v@;=wk`tAquOZU(2 zW6?K!Aa-lN6f%D5`+Ea=BF`H~JI_xZfbSt+^8POQu5*52|8o)U=l^`3=Q{rv|L6aJ zaGiNcK9Kpt_k-gH;s5-fcky}r=}~_$zR07M)feOP9G?Ea@_~E)=03mo;dk(Xq5O&b zV0<9w0+HAEo0$*h93bOlUg&#;`hmP3e4p`v-sOMc``~Tk|NL$s=l;IFc)j0W?fl|8 z*Z2EJ`JXPH556hB@3-%~pU8LbJpbo=ztnqs_yPY@pkKsGcpiy!N6Pc|uBYMskQ=^0 z{q?>u=g_#$|MSKN##24>e|!&*ar#}nKfB~HpNaBb_^;o`BQKQ~%2$&Qh+n_+2k%3i zbH361*ZIGl|KopkOL7b$uew^n5OC_$2$s{_w;3$=f6U%O}Mv#s4*K z{lh$?9o&bpZf4&3^sp;@jl5s{pQxOz`^j63gZ%Un57_bAd9%^$?8jF-wNGb!TxWdV*B;+vP)Vj4MRW)y}j>*>x59VO>{{Cs=2N+Shzweqdgp%sf#( zsXhDIc?#Dj^v62Id3n%vh|hDsbxG*F-g?CG!cW?s@wu-P@w;8#SwG&%$^K}r+h6Oc z`U&aZ_0%BGcYW50&EsP0U&bLHrhfh3Db`u*y1#W5>l*ym^=s&Q$MLuB89c9}M|dX2 z#r~RpLF~@^v()!Hd)`mqwxhoDvsdW&S3RVU*$3!n+3{Jw={>uz{jcXk@8rjCdYhaZKEOTP-^rNotgV4ux%?YH;m^oR1*yidRDV~rQ>C;d=w#od0ZoYqHQ+HK|i^dIFWKRf@N`Xg@Hf6w|}zgNyV z=T|x2ZE))2hf}ZXo(teQa)$Ci@jmfO{NG#`fO z?LI!nuIqjsdsJS}Ntxe})ANDWn=<|Mf9Q@EIn_(N;2qiyJPvu)`X{o#)KBQI|ED2N z?7z5cJ{OC-_OK>xUhY!#t@x z$~X2If6)(4{-yCZo{3N9&v-u(`>pqt({_2@ecp=xZsvUBe0+B<6o2b|artxnP<{^m z@Vt7WfAvy)6fa!I&Xw^4`{lar*^lLw|IUYp_ zw(fKO>v!qr^~v}t`!MG><|*VauI|tOX%D_v&wHNgk$kUS!p1e{Y#b;1P4xKo9#@p< z-+e3lCF5u6RiFLwFR%L{`|Dp^Q_CmepgSsURxKf^KJFCm+NixM;Vm=n{{}4 zU|h_L$b}wul*htvuP^;@o#)Au@nG?L@qe^Oo)6>u>Zfym;^@itjeqrYCm;`Tevk8L@_GEfGI=4M6W-wMF<#Ji z2h{`j;s3;y-!iWZ|K~aO_U+^kc-<9=GxJL4=;F_4Uw+B{xi9}W|L@}Xhc}GZ>wKT@ zt@B*x_u%!XJ^8Zk@8<&V`9A#L{K~ko)89V$;t+rL|7N(3zVwf9cq#S3y36rfZa)^n z`;lkk|Kfk*aqzoy-QW8E8830KINI}_@1e#Q;b-Q-u=iAZZ`JSfi_*inCFJpj+E-A~L;+12@s{Lgn9tU-z)!zo{Wbu{x4)bsh(C;-kq0WJ>t5>bs_cd)+4Ml`W>=$C3YIV zrRUZ>#=Ofo(BF#4=lFJBXyk5v)cQ1jQDi^r_}rIfpOAjF^RZT;omo(Fg1Jv4i8mZ)j&l?5aQQ{NG&ne$U-q*PiGn zyCcV`m)WPT`bPdePStngnsHA2X&3dMK2J=KAmeMl7rM_TuT9))zwG;r_N%@}uFCm| z`_J-th&^q;JiqoUPvE}AxMn=sMV<|P${T^k349^^h~?^aj+cB;J@a?G6G$Fse-JVr z%7Z(Ph&_}iyw5+Y+{q7~{;-!FKmKD}}wo?9bp z-WRbm<&gXC7pu3PuS2gN=LgzxTsuDdP5yIlPuiJ$qI{Lt_V+yWivMdKWq;zlDmKrq zNW3_oOnm9L=`H<;>KQ-X^-kQ>PN-j>e4zF4m*il7j~x4YVCH4(sSon2@tuBlH2)fB z%3(WuUgo}e!g)bEQXe}ahwDw(o!Vo!L-t(bb?XqvQA!+ekqIU z>+MV12T#7w^6-K8{Ga}+e%E!b?asQ}{-(S>*Ln!dzq053_*uv5FYK+5upT=#t6$@hJG*&Dvh|Iwvi&Qp)RJbyO4JMt2L@_wEZfM;|6XCCtR z8u%K^e%FJ1ZCONrj%P*zz3pN&IiIL z!SgVW!t+La~dH8wr75qSCsD@x$z776}6vo#52L4%9p-<`HRcC z@}ztTiT?KUXT&xB5T5=(zv(?bad;?sg8J<}t{k^Q7m{)#& z>6Lkk_@EueZ+kmm)c?!$e=^u-ujjsE_`moo=0)wkqUSNy8}k6X^q_G=ed5UZH6Bf* zAM_-DCNIFeOuOpO`7OWGKD66Bxbv^*M>}E<`_2C27wX6ByPpp4M|^6J6|uK+W!D|! zNvY@jDSCa?L-s%SbC#)(U1(>;{Np_Dch;*MuXMlf{)mTZ9W-(_o*BRXu&<+5{*U>R zxMJR4f4?02F~4aC(e;Sy8TyGQ3|S{@5770*Ao_}@S@|2+QLRH9$E-^n4{|pir(5j z`+)Y%&v-uXKH2?o@+7BvG{5*9da*yyI457Qp4Kk2-kf^cb@V_#KJPw%`eVFfU;1C= zL$8cCRNh&?+OGbj{j#H|AL%dISAXFCt@bNbhm&v?0uN80gvIPvQ9 zuk<+A(>EBe$GV&{`6)E6+P8LH|0aLf&d#fHeH}+-^=-b>fAg1FANbsvk0)NR|ITOc zezfL+*{>^qd4f2mo=7}U4tM*-XAJ+NpU7jek8z*veR)8}x$^|^2CE#jL)qu8Klj!D zGyh~k4c>p}Ey{>z_7kNQWvok)B-&Un22KKk?i zp!-G3@DcFl*Z&$Pp!{kP7#pAXjcqT{6=?aq2{ z)`!enj1P2u(t9}Z*7(cF&wQZ2hOW10KfQ1^ucg*CDJcEGHl9WBi|eGy87O zolrJ^t!4VP-Y+l2Unz@kpT$$3_NTs>XHNZF?)ozt4~^^jK62?FJIeQXE|9!N89Ts} zuwT6f{@Ca8JlBa|>V;izKOFz}jI29pmveBm>-);Z1^Sr$KfE9Q9RIgs@8J%*?m786 z#sU8ZuRvTo-tXV}uJtF<5= zHRNaZ;p7j#)3)+|%o~(L)^p5P@MO$WoJ$*2@0Aa=Xs{XSjR`sW8v=yw9CKfK>}kLOnYPk!&22PE#{14ZKr zp26|Lhrt*9+q->yADA-Z<9rYp?{|;!ej)xo{GWQV%=*@{ydyju{<`uX=)?1V@^I?y z`P^OC!S#F|>lDhNd5<#Z4F|hUfAWR!6Uf7Ps&IHe{ORu=dZfRu%lFY=a!}9njJ~J5 zw@171St~Z)ctQM@`(kp2zy9KX`GWs}{^FX|zj~l~mVU^u*!3?j#1G+rd2Z}a-X$-E z$}#*OWuEi8d=~k@dCGkm&ojS;b8bu?4|}@4F~4~(OgUzLG9Jl)@Tlv0FMbcb*iPsE z{^7m+%>N+|`9SPE)4FeIzEn@n&(06>f9i{TkG#&OjWgah^xPcdXTJODT|caMns?M= zJfOTEe9)?2^{igrzMS)*^gri0(U0d^@jvbIIh3EoF00*)v*In(udLVp6MS{u=g=SR z-64L9o#S=U6Lt(4H|22m7u(hDtY4I4P~Js9I?rLX|HMz#E92sKGB7?a?ED^azJ z&-q7v7Y`!qOs~i1uJ-kPGw#!`^}c-|>m2d~`$Vo=X1ufCPmUF-r@sz*zjfmI{Ax$? z$ax;n`(1zTzjnhlj*6e+$@Nz8q+MAbRgd))JjFd)Z}xNA{ajB^dw2I=@ltbr_5(ie zc(D7bSL!zop6bxY}x(4{3PvLf6f7pAGA)z z-)VpM3++d{Tpt{su<@-J-xem<=ySJE*YD~*>q&p7Km2aR>_I+o9AR;N@7JsU&N#FS zdd7}pkFgKWah-9l`)l&A<#qpLz3Q)s+?H)`)q~?_oXC-Vb}SCVb3FN__`iMezkl(6 zyz5PWP5)x!4b^k z03!9)eS!Q2{=a?)4?DvrXz#|&z5zY2$oSYVFdol8$y?wz@<1!EqkPjp&neI7f8akBy#~Z_!uSydR$Pzv~C=6fanuhUa+4pXn$2;$PVh#Ljo9-LpUFbIBWW zJwMX^;}_a_pQp+TCmMIk!~EcThtGEAIsD|A-xF#{SMPSvF0n~nsa!@ zqxnfcQqS6djkD~A9~oym;%E2qH~l*=GY=Er@^`F<{C%1Apz?%MU%A(LoBZOu==_n~ z=286wJ97>QJ3%ty56??)lm@pCbKt#Z+>JQOF`5gwlS?R+irS|0SAo#*X_2lRIj`5K;& z{}bW!_`i#IK=nWwKIs+y;lcm$o-;fkc=BiJ)pK>`8P@@hlRU!ze2~Z4UxA(fqdj@R zkIw(8N9H&5$#({;fK8F9ZAK(A|yLZ0tHxKL_An)~hE|B+t z8IRccKkU!-_&?TH-(6+K>wCez*9rf@cLa%huEYC$_dY(Z!#5jG@IQ{X^MCPxZ|^+d zT)#TH`hUCXi}(S21mlG#^W5Kx-e2p>N5xC+sGQ~l?@$zwg|5L*t!(SO?f1zmJ&r*1SnP$NTY}N!C~T0s3dX@fQyyZYhJdH+&~$ z{ApGBjPK5vCdWb%qXT+`#+Rn(;KHYiP zd9rmDdRzDJ>c#$8Kj@Ex>cjahUd??e`sF(7L-iFe#Qf)b=3FN(SL8X$qVcMI*YkhM zK|4F2tzLMZ@!z9zVn^j}A8o&^TYL`QO21-$#J{ZnG5_~$uT%f>v*QOJ^L^;S`AbA@ z%ghh*eS^xWKke%=*FpGG=Yr%5hUc@)`wxsW#2+Yw=!1P9`mv0jcmF@j*`I!R?kw-^ zy53U%@`9{~)cY%(eZGF$Ixw8|;Mfnj9cTIo&+DJ>f7Y|JAMy7`;@`qD0~tKq3y zKeZ0uajozE8M)_q{oveJwaz*Bfv?K$8?i&}smFC(^tL$eN1{4XWyXy^k;cL?W>)*j=cCE@{YedUZ0zI(4U_D zPkkU4&!ykhE?!R`_)UCjdOk6|%Kw@Fp7WA^rd-eQLVs(!%E!9g{+tI(!bMs67G<@y7evQ-OQhUuf@ryeO(~T+B3dpNBqcf^!wuO zugwpG-zI*-?5|b{d#^(zQ}Xs*n8G9j`N%k zW*zN575>lpXv&Uj_OJTU@O|=BugmZk?1O#o?cKi5`a`c@zuN(%e!O4!IsT7$bKHaY z6LBu@g@2(J{fz6~$06A-!<+2q0Pp!g_x;3ie4qSZ*Rfmsr1ni`JQOFyJ#yfej$59R zJOodL9p$Trzm)&`kBbMoLlK+!eWZmR=z0dEb@I&%|jQjhmJ9Xz(CVk=@8<0g9?kqDT9wol-hsU@nJN_Tu?fAnV`980I{}>1B zz`jqY9sls)$#{Q}dYo_JePH&jz85_D)Q!bDF~k>c7Mn{%SpVIO@ThVP|+R z+M#?R_2AE_$GJKE;$I)n@87ATedIzfgYjVM@$GRRzKZMcf8-JBhkZvd?7iNQ_Sfgh z56Dk^_+3T5XGnWt?K=*?=NK<&|F*~f71Iv?U&8h0bAIuF{ErLw5n1nTjFw1J5u(4q{G+OlOt>&PJVNKYJWstb{-->f4cl1WL_k% z`#zuY`kd>}=lx5(S{R=eZ`A%;-Y7mOj3*LDuklLshdo5~qrY+f6u;4q*g-qaev9Yy z8|zW7U66U0^}!%^lLro2SJ;2!vdneYA)YIQ-+L}&Fa6>4llyh8ixEj_IEpuTnu(_7`;zUbF; zprQRCzrT})udcIBMSggeL7tcYYdj(Pb$u9Ww{_jP+xMAA@%jBa@{Jyi8|7&|>V9Y4 zkLVxr7hPw(6PN0rGVQzGW_==$;`+LEcDS#1W*;!?Z~drpa!o$C8y|9YJ$X(!9gqIw zILasCKAzf9o>%+7C&s7FI+t}9eq{c~uGH6mzkWyVyPv_oIj_w9{J*^9 zdDZGUj_l_+cAjDOPs*PiMEzC$t^3=L^;CWBfZrC!;VRd@FUo%UsrAbD>UHPqsIOi2 zJmPwe=UZRzNF4E8NPqQ%edPam{#joWFX~~+jjQYC2lZf_7w@2Y67ApT^^@X6Jnb~& zZu}?i?d#{sXWkwAP~LwZS?4e6JgeJ=CE z>?8Cm_YM9(2;*J%9cO#;i|AwGQn`Lg*?pLC%>J|esn^x(%KzyH>SglRT0Z@3m&^9? zfA+yA-=ZGY_c%V(mVBY0A@#px)KhW=M zzun`P_TBgGnBB>jj!&#U_qF@Z`;#BJK3IHB-0b$)?X<>^`N47L_vu5_AD{K(I;MW` z6Q0*!CO?peR(@F?g7{f^0On8XHSf$g?(|GQ`gi;&=sY2xRDA7mnEgZj0zapo{fqQZ zIfTD39)`bgT*^23fbr%x*zZ|y`lr{|=kO=zS@}WbQcv=^{l(+4@An*w{mN6Y-;EDk_qnt~eSSw5)wk>~~+`b^EcemhXT!+o3K$Num}!+UX^eCc)gK={7!`$zfLSH6Y! z`OQ1d`M}{5<)L`abBHJZXT0t6^g560@84f?aNdi4KRtNI%A!0U=L3}&z7L-BhxhUJ zzb5c|e%}vy;4>*ZF3Rc!{zE&XPwJ~z@{r>Ikpun?9>nkd!RPT64d4GAp0D?S{qEn- z-oO9H|M7bM&+~)ujFv&(6aLM@|2fY1zWeile|goHw}2!1zt< zWB)5MzrqjczubqXaor*R$8+YNFkTQ|&*z+{S=aghC&dN%l(<-t^MvGa>^w-n{!jEP zOb+(3$O8{E>m>7s{cxW+S$V(8#?Q!$UFEq3<^9qFc^JKj&+mV>zb4P1cjoCq^(!Ce zxlHmu_g~@gc-BV_+w(biIm%rpKUAl&-$Eq(I58x9Xwus;C=lCyL4T> z?>uq*EaPImM|`u6m~(>hfAPq_zVfc?yU_K_zTQWlUDprSb&=2GN30X|TX{FuL&TZq z{X*kKeQKxCV|rFU=?VL)ztygHcCMc5A@&76CqJk>Ja@`R+3$Q1hwuyPnRO&~t}LPt zuAjL3Y5r<|>19RQwY=(+`thm02T!}y1C2X)5Azh)S^tNwL%8qyZqW7a@P3X{yS7ic zA2j$sfw0UCKlLZguj2$nEpy zo$NmN%=`WOm;dJ%|JN7)_aEaRy{_X~{mSu=pRM&)KjnIHH+k?J-yT1WpLQI_xqo;r zlRy3a0lQB=FwdOx!&*kK{=P)su)fbD_uaV67xuUM8`mo*_lkS`kAFJe{J?#j=Uh7X z6z>zpXLLUvF@N8AKF`?^A6~BU&j`!#t>{$#yh9E59p&AP?>xIQ=e z0)Nt8`jh_U`=-td%@@Vb?oTrguUjskArIq6KJd&R+2Iv7Pl(R@!xY$}{T_80cbz*d7kr?&t=~@_vP8B$M@yR6Yw7FN3oOZ zDslW@|8D)@_>rG}dg@ZojjyRo>wTyC2fd@O-EL+wcD${Gaj~N5rvm6VHr` z@0!W~!DBGL`9BhVSB>wcdHzWraQ#13_d)p6ehvn{fqL>s*p+?q>hJkC{SIv)^E z+*gmZhn(!g<*O=(@qe8I^t!ws>jlRx?@d17{>uNM56|^^{!hN>`>P&2$@iBY*hjC( z^OS7|yOM`R_&)p$KgF+|f7b7G$m7wz?YMuZKKdHI(EYvqAAFzV8dM)YJa{Pj*N*a$ z@PCaw`<$x+*j&;UVCMnliRZkb>#vm$M|dQ7zd_IQeRusI@-Hs=xQ^WL zOz>&63s1I|ef}E2dpr2Y@2~GFe)Skvi2Z$Ud3Znib^Pp;J%0zv^Yy-NC@)FAhL4ax zdb^&BuMp+)xbOKvm*f3yc5ILLg#^Mmq6=_wuueXsgUuIhp2ofG5NJlDrL zRqEld#Dl+Mh|ZJpiL_6depejc?d0K}%k;y#Pr2^)7p)ggZ2y^@$l>qMXaC7LDBse# zFVE4qUPOQKf7~Cv+aLbK`84@B;t;=rX9_R(y!6I%p}doEZF@a0ABdj0ZXBZz`KmD9 zD(w1+Jg@!Rw~5bwu=2(D)$pU(0e(+==qEhyx}<&f{yj(H*!#b^@-E}{{TtBr-|&5B znSQ8;|A^Xo*3ro4Iw~YSj5{$tFGODTtX|WTd2`~3{;Y?c?RUykkN&(4|L1(#`bd56 z@+qhDpmN6hh5P!DxVD|nFRuKwa?JhO4M#ueWnEvQSNvwjyZ!vS4}zz{4?))vUzUGUf15%dtUc&z30OEwXEEq<5gV0w~l|tkDo_xj>mn}>9^e1zlVQmT%zwk z!4o*1^wPe5U4Od1V?OiuZtU~zyMKx37k>*U@0X9(@9|Vmed%xCyxVWk@v+XN-pGgi zd~XKi`~TDAWE^OxRbI#0_(JtZJ@n&vPW@C?kBy7=kemLLf9C<$>yAS^ zCjTiXW%I_FpZ0u%zVJtRztFrfdB^;$f04f&Z{=Mt>W}_UIbW6c@$UQ+`f)!j5})fl zgWf0)?s{8!J@pIEM!p-Key*c`;x=TQj3=ZY-b)L~kJOh3c{M)ULm$;YvFCS;_ZxKo z?7pA(rjcXk{VJpXXZ}zB>Uz)bxa%LiI<8mP`Yp5`c8hmVzs4bPVL3iN{#Mk!&d12b z`V8bb<&5_Wz3+GM(TD2}`_WI;zxfThCNFv4I5qz;-qoM2kKVkGeB2NB`PTKJ&ll%= zd&R5R{OWwr??cb?Epm=tS9>7WIzHqp{2%KR`ybv9{j@&*{Qb8ttv`CVJ+H$Lrf>Kg)-j>=dQK!RxeoFi@flXX{@icd z9`!2^x_|Wi6L|vO;Y94kb&>T)`(*Q$evE%t4)vGS&&dPSGrnKRJMuZc`||Kv=xdEr z^%MU$=K|%&;?2H)@JsN1@qg;!`%9njL0;$F{mK7*b*&%C!}>pY8owI;ud;Fsk1fxK zpL5=W=l!1~#wX9n`A7Q2zv$O8{2x5y&OgcnvQKqfgPvFW_jjH*K6QBCcwq9?UtN4x z=Kwv|C6DKMzIhKgesBN&U%VfFG&~~n0_Xo;VSJH^f zoXex%LC>Sg`@#3w|L}|Q7IS`2JJWAGp!}cb|9F4d^Nsd9&(#ighKECsoICuu{Puo- z#g(rjkIMVW=lOpmoV!E5-U}X-hlvLaec!nMV~8(9PxOnNAEUfr=LF;Zl@4Qf3L2iU+atLZ!N>iB+uQtY+qj)pR2s&iFqD<@AAcO zD+? z$|1a>d_8f_x|r{VYFFi!SFE4>AsoNgKZ*-byNsP(FZ6z}$n&n}MB;$;1^hYJTi=Jw z1Fj!kr=sWPNBe7?EXK#OzrVB7YPT~!C^OC#wHNxsUfMlGZ?p#@*NSufmyhd=!*)ML z*4xwrjn@}=Kb;!D&W&PDUnE2e!zaY2k z^;by#oAr(PaMnMqdu&I4`1U=Xhlf=D{r7d`UF*A_dTwXGZhz*P*_SDg`z!R9f3DZj z)5tyJ*!cpk4}Y+)Q{z+RPkg^fdG)J!zumuz;}H4uFXsj47v<4z=}-O-zCyWI{trF4 zAN%=%#GUbKoDR=c*?FURg8SGZL{FBrPj-5RclD8%`ggeI563mXXPKAw-y2vbnwQEy z&;Gjl5&Beq5Iya@X7YxOt1@|y=fiV;LVnuqJ-Bt8|8f0J`My&G{eosl>&wS;+TArT#HD%;k>!Y`cU-MS-6HjOUV?T59e`~zizT-9iJSS*7wEt0g zr`!DshpYOvC-WSn-^|V8I?ip7*=kH;0u=+FmV$U~)#6|0Ylb4#Z z=a=MppY1*NSKgiPFMo&1V;pPG_1v_127jjB>DTM^?iV+q@x(gM`L*>6Jmg3EQg7Im zd>yj>ryS~!=ArVs@zuPx>l=TY^%Z{ieE&KB-Nhq*VjOB0%e1%hfyz1joc=lGsXuYP z%g4NC|KTcMe!rvqUU5o3JoAe4yyN#ia<66NDgM$o^C$7xdgtxk4ug(w>N$@#?~1Se zYj`T!VLl4!7d`LetSk>moKt^27g(9+%AeXNePe&^$hxNaEYv^p`{(to^7Xs-J+f}W z590q=zpT%#_pLYQD=RC1dRI>?@5g@2GX1~5%v%?#U0vzvZqMx1#o=f8{yLr+n(w`uLf=mE)m5d4zCydY^+2 zgI`#2KmUi|y!Q*g^V_x@_u=q;@qVG>ra$yD z$ar~v<^Nb8s6XWKeP5pEJAbwl?g#zdrn+?^$x6b)nC*A5|Zp=l?p7=eVsePXO=u%=;l9&j@q+LM<{SAr{LFog{FZ!;dn8OvNc-_vgYlT*&JVIrQ!d}z<^5{%64%X7`}v^uD?Jy#c;fJl`}YVrFKB=A zq5U7O?{U+w?@gz7`lEjRp6kiUo8{3{-g&>7@vQvcsxQ7@N_k(mSw_!Xf9Czr_vrum zzJAH|yK{i}BfRQ&SNp`<9m30Uo&4f`;#E7})yM8@ee7iUb^FN2cmDLJIX~*ScOEc) zFg=2> zv){k(Cpk`JUE=fW@7%6S%@^Ok=Z(R2U45>zKQ5!k_L`gy`NPcS-Jf=h+Ty`kFXc^MHA4{HikYto{|x{0ez)Z&&~IT#Wq}ua5IBKCGwz?D1qA z&3*c7{*dp9kMKHvwBKL(H}h8eXrI61`-ofQc!k)(bAQGc@)2jm^UD9(pZ2(`&pw4b zcho-|IYcH{X|kiEG*+-fhn^*NuZ6Yag7r z#h&;D`)TgH%SL&;HnBOUe{~Mlz`T67njjNTPo%MM0cz)OKT9or6=K+7e z=K9X#{j@T?5YL6|Z})auSAvdb)o_RpqInT$zpTUFdINt~S!__Y9KKM5IKkUNqG`838Hu@p+bJwdU zKgsjhYo0snRhIvwU;X_=+9fXy4)4c#CiTa933)BEZn9l@Qv9Ma_Br{xc)z~qx8tXa z?}8Wm_VNC2=lEzx9#P(pIJ8~%>+**3f$#(JexUNov$3DY9_&ZO=ktHm=e!T{!wYy$ zZ}>mkn{$Mo@kniPLmM4Tapgg=^{9or(K;w$|kXNGo`n;d~-``*DQV+bud+;lkouB1FPW~!> z%j@tZo@4Yog4j>K^3(fu|KFH-f9Kus)3>W%`MJ344#a?&at5f^7D$LNA$Vt7d!0l_o{d2#dV+5bNVOu=?8nQJfQx)^Lf~X z>tXy~yxyOV@>Hxx?QcKFhTV}5yE~2(cl#Cx*i*gsKJbq5g4AN$O5f3B-9<(P8U2U!Q%&LDoW?iZB9byNES z`Z?p*dLLhpS9JaL%Ky6VyhlH*k5@T*K6y@5KF7&(-De$5nf0^zighjd9mKxvJ9-aJ z-j4dLclf=7^^p5%pPPLxa<4p}{-U21_wp&(e_u}{*Umq*4^m#`w!O8VuG63W%zk0@ zPuqX?+qsTBuG_;qegi$YA5$;&Z@z!~GW5E3ySHC!cnhvSK66;%eppEU)7+9@3+z zpU5AVAL#eHhh4(Sr}|~TpNKxUwnyHh+`iFstZQ64F8Oxka$LoY{51RMwO;Xw9-Lq9 zk@lQ#;v3d>-N(xx$otWc^}}5*{VAJAXB>@7KUF{R2B)65u6>@-_x^dl?*L4k>yPMPzg|)MtB-gm@8{3q}T1NklkMnK(Q!0Fx==D8ss@Hq|FJ5Ow z;!%D~J;48=57GAx$={r7`SO|v;u|P){X7o{?&C7AhFvPRzGi)- zf1o$MdyjpvS9XH$^M3}uy=E8ow~UW*h4Vc_-pkdmSZ}E3c)64R<9|Z@0r7j!1IGWs8^O=PuX(@s7?m4+k|$^%|M&le zD;t-@f&3oVd5(It7c%e8xj*_j&;P++IFEzzeYI~p+(+K2_gu!`ybtz0Rr9C$HNWcj z4)UP9{N4Mc|GtaqBcs~C}J$RxO(1|CXX+2`_jw+BiRP#0b6@B6vur-E9sG;- z^fUNAPMQ8a9~jb}{u*{JFdk5S#jB!6=Cv^1 z??n8=^_%-v*Q2gSTxYfZob}FJpY=)SXT#Rft*dwYjo#CL`U}tBU1$gWz&oDjtyjG< zUt9j=9}#;pu8)xCxF0efu4S(4H}Zfd-?z8#d_C(h^YOmE`o+WF;Qv07t9FxXmt*{y zb&3AbKK|?Xvg@)>*F5j~96d&v4{JK*{`l;^3(d_fd(|BhdI<1-rf?1$F-&*O7lhke|~-SdCsBlWwE+jznL?t7Joaih1!zaoC={n;;1 zo=^|=Qy#Hj-cRLv`+m`U$hx<4$GiWHe{?-Rp*(&@zs}`Qr(a!m z2;&n@#GZ^Fx$}?bJSH#b_{jI^#r@VR{%?(6+mDaod3e7SnIE-7{yYASzc(-Uog4OF z#(}uUpK+uAJFYXoWWULytGw8+yi-0lPLNZ(7eB_=UH|5jiC_I0e?=d|`xO_SUwAc- z`#liGQJkD;`};gE-_pJy)KAqP^Q(R^i2mgLhL@Ug_}p$E^OED5_@6R`{}3ac}?>VJc9YTyhc0t<%!C@#sTr7d}|)q^M?Lc zoVE^~IGgdCFDRpT`~&`8-imqF@lDyhqrK;MQ}==LUH<=@`A+>}FU!hhoZ+{QBR>cA z2YD9sc~@TN1MSRnEAQ9*QGbqactH1;DJms_jz7t~@9ICy(&zdGa{JqsS*=x7H8OXkKPq_@(DH zsgJ$k`9kzzJK?nJ_0A!JZx228za^ee^toMc)Z_Xy8kdv*(3{^2L@(-H{u93LzTCOZ z-mjKVf(N92=O^L+&gYe1xn`W~Q_>gm?CYERam@HW#|Ng@!Mpj(xWw-F^PBhcPyEF9 z?A0I7p-1raoBZt+_8e#&?R=m4f%fnCtMZ9*^Sr#D|Erxm+Clr8KWIlpOL^PTT=U!i=hL&Vl$uFK+m+Gmg_^%K|A<0r-2{d?1+$2H$F zPWe3gK|ieH)idR1{dM25tr^CK<)PtDj(}3|f?S^w)7s|6wUH3uin|{#yj(h$}&cU5;#V;9e zi2qaOJzKGJg5k=~(tkWk_|y3f#}_X(*m(kZgPs2)k22nS{!P6Zzv+SXu6h((4`)B) zop|xSNPJNa%P;jm7~clI&Nsx}Zl_%?*XQ~L{bnzoTg&Tp+Dk6vv}`~1x8kaA+PU+$ z{kriq>-oF*qQB&Bzo7j15AB&Bc0?|&o5$3f^-upZUs3igusjRV^4zIy*D{2%fW2O`h!@hv~VI6UVkl6QQMaPp?*u7|Wo zULAbRi>oj4=&&ZyK6iYx6_XIsi*!Y zuf$8Na!}9xW7s~@xF#RcPCVtx11A59$+x0@oBuu|^CtW3@2-A$?ll@`+%K*ex9zuH znf2_hr}WafzV*D>>L27K{cnAq{?_t3zWsV}x97L~EHus-ck|c8sdjpv@5)2+3GC02 z+w-QP`g7iZCvcrS$o;YJ_$6}S&+hB%=ecY=8qdmi=im54{(Xn&EB&bl+jZUJ?;DKA ze7Mio=x_3%b~@|r_8WVar$fg9Ut|7FALt4$l|=cOpDx{2%#^`{Yah7ngB= z^M${^$~VdPu%2*TJ&4@!fchzRgvPOQ z+?~7n^6HoR@qZ&%JkHA7(C_d_$+_lJ^Ktof_&@b&ncvqb_d7f77$2)1(g*LGbN{Pr zJZ}#@iF~iqemd7BA|Lg{@>}RQ$tV1NK|SnYyYPATqa6GHy2J-|J~E8=>pkgb{x6=; z?*n3Q`(ymgKg}1&x&D4)Jgxb8&)1C8_813p<7Ye0`%T!HygEqzb^faS3e_9_1WyLW zJ0XX8Lmsd4i9ARAqkrSZ=c-r!30MA)xI~{2fN4z zj(?y}*Hg`do+G8c^Pv0QbDds!McQ{AqTMOGu3gK<6VK^~#tHgB{^BxBZy|bN+#&s` z2l+qxQ%{}qQ*YG|^^0de;68GM)jP{wr$7C1-*<4Gc6M}r#6Nc)aLUY!=6BB{uwP~U zB|6_v{x`0?kKFnHIxhD+$;tjyzu5Pw?OR*F4DS1L*30=`^7 z@4Qv}$@tG*59nQgnsXwKZ}`9DI_0%I`|)+(jhvLR!-~W?&#h>G#lQB%|Gj?hQ{#KW z##3DE^Cxk`_-M~@&VBvpZk>%kH}CEIq5A>zj(XYmMU311+N<-W>v+~Y#X8gZ%69YX z`CUVOj6bgWr(gBD;`4gl-?R61z5G-0bvGWzi~i_m%`@nO@`==2^*;LF^H%%cGfulc z`<(184@dq`Pvf`7>*w-J<9vm~^QrIYr~cIYJ^#lzv;#=K#2%ctz@FIKewAOIM*Y)o zyv-{_&nw@9J9?+uRr=qZ;mT{Dqr(faRJJot;jsS>KlJBj>Gci8JCr9fAu5#U;C3!dHeGGUJ>Ib zUoj5+L;F|Oe$AuUQ~8IV`hQt_w`I$6Bg-zxU?ek1b~RZnUW!RpmGshj)~o(NGLsd_ zqVbZ(X0(O+|9?Si>~RJiz+UG>mP}96fQ5_0-2ph}##&qbVL$XG55RpO-*?l_EB~h) zp6Bt4);Zgqbot7szqcRHJkTHXYx*bccp8Ut?e~^4i_9y*BdG+i38@XqmH12zJeC|W?U5yw2%g^#Vk@>XF5BgJn_KEld`g7kf zj&+|y51h{!H|?xgx!r%2TRp;?YS+*4fbm!&<5Qlw518MO&plPr_yhbO`282VgVYZ_ zhjX4JzQzuoH$(Xd^vXFEjQ9I+owt#r@9BH~F`kY`(%y5Q#`GFL=wHq|?D5^ptBh~B zmpyh-o@f3~zUI?=-UEiG{OTG#{mI9Tp3;}7eu#4&_wa9?^W^{hA6@t*=4&|j{^0-O z{k$(qntO@E|M@?<@qhB#{?91!8SF>V$PYL62-3W(IWPOw8ThV)#-Os}=)R#A9JnGf= ztJz27a|gXoS@~z|J@4vSK3)zxJ0AHz^>pgXbxu82&imTv$#rq(jhRpCLH;kf&<}PS zgzwvV5bV$Xh24>7u>2Kwz7Bg)Kh&@6Z}qGEOMLb_^5OFs$BO8SbjZF-`b6cY-<|)P zaqoPk{8|2IJ$ZJ1_wruur-wZK4yIq`@2pciFaG9tdD6(aV$bJ3ll$Bncj$k`wfzqN z8t(dk*7wf;(GT_{KEfWH8?=}FA9^I6{?@d9qa5Uuehc-#_Hl4O56rrtpV1!jt!Nyj zJZt~vyPvZ@^8F3#t@r;}$H}K0`S!nJ>kRj|)_%1|@tLR{*L#4-wV!8+w~S*!>kU%A zIJ9%g#H+NAJ?w{g2zggTKkwHxI&i?2vQk>hF{zJy<+mxy~cv&i|<|;;OzsxZ2~C*R`mOqyqNQv_8=V( z$b6k>F|@%}pi<bNIiRPiuMCwc-6rbB^=AH0>Yg{Qd8N$ZuTmgO_shJNf;N%_DL4`O=O*eeSsWMf9YKkox^{#Res zi%%ThPyI|weHi@-`9WV zyW@3zP@nQ5$lw0iya3PrptR^b@%JUi>AWnzew^>@55}G0_=)nmUNer>AMrQqiJh}L zXZE|LHad^M(13vR) z@=@_p#$o7>c#QtI4`|wZ5XC>nJKk?Y9`3uT=bit{ADu7o?f69~|3^K3SDE>}>YH;_ zc8kCCd@P?uyp#N=-cG(xp2_=l{$Fl9U%39ChUI$icfJ2-KkGbae9rTE-=BHPxi(Z! z@_^jK!CqfJp0^*^?)W`ves3@i8lG_O0mA>u^I;$Fdk%VUFy46dl^*2*I{$sVnoA?GMg({q&1?zrViBJ9s|oeS7{79^)5RdF=f22QL9n#CyZ=bn+H_Kag?5 zzr}-wo+r>h^XhNc_`iSE_dAK`d3Zm0K>IV_?=aGjJfHtZ0$*=`A>S>O2OLzMdA}L? z;a`|%+U3JT-r*1Pi|#QF#=F6;x({XgXOK3=@v z`|G`H*V&yfq#f6h&OxqAw97iOzE5p^`M(*@d4Dq=FC0Ekxlex0=fl5EdHYj7*3W%k zVIOgwQ~u6@`*_yzJ-3G*=lc25jH)jr0H|NruTtULHG{^tCV z|ATKczk7cx5170oXY%S-<7dn>^deeMJ+;s8_u-ij?mzDP@f0hs_vvbnd=R^?NdKg> z8~cRzJ>ypMiEEK3WE{ySp8TJ@K6clR@}HdlwNJn6?1=oY+g&}bawN}=#&gQGk7wfY z{CFM5uJ?U>Yq^m_J-9y_k8&O}9%4Pb=liN(e>?9@zt|&mK202p-95*Kv^VE$?M&Qe z{HUGx=bSgp@7xpLC!Xgy<3`(KJy_$(>8JjT>qidcoAWMlTk#i2Tw&ayK8#DA`9JIV zyS#C={gGdsJvircVEJSM;ACn68$Sow&M^6?hVOZrvrdw!R8^qc%>%2jW*$LMdBTmM;kALMNu z<Tm7;`|p9sX`C>;pK(F_&N_dTzwyFf^q!-5KEF?^C)O3` zxje||f7*BaYh2vE5H@b~q&&2volB41R=ek?udi>b9q^CW(qlizJHIQr&&Kx+Uy%PQ zr}fWsK7P@;-*f!h&*|rT+V-6n{Z7|@xX;IRzBR9nr&x!u4~QK21MQxOe>e{O%y}YW z$L870`}PO*zQ)J+#hQNJ4`y6rkKzBU-+I?LSNrO(_?`ah{ZH;0ao<_L!!I0<@|&NZ zh5DQKr|`4hSLJueX$M~8E&fmY>i_g>9P53ynIF3z7;n4|_owiimH)$UdJj1KaIFv2 zL!K4eXG84fdP6*h|LpP3`zs9}C@(>K-@DFhtgoJvSckkX5xRak4=DfPCEl3zan}D; z-_2+5DazM;ddSZ?EB-2s|1<44k^kiXxI_zoxWbbR3R{Xgx+`oz3Tet0nE z^&s|M`9IR@`@Z-i_x)T~;PF^jCT&0Pg7A(ad>?5L`wq&x@qIwvzy0+Ke<7dI{V4Q- zyn~+8nQzGLcwATF(FWzO7&rIV3lz3up2^s|1)5dS&(ChTT=?%VJtt`B$opS-5?+JZg>tptJ9F}7p zR3DyO8W;Pd`8&qjpZCHhz4p7$fBSEI&8rjjr}#PMHU1Pjzw~eUy7)U0JM6qOeu(|W z_&?D3_~QpMUrhhQ1L3c1-}iyh(|vmHANkOGNWHNG`dIauABEZty)$1|#Gcwie?vca z>F0X>enI@U%aL5q`d5B=SLTc3PJfO!I}oqjwOjs<`JsNH{EcgH-KSYEP0x9|H1&DD z;;LWeI>$#^eJA(G;r`3~_Wob|Ux?hESM1mI)b#*+IlgIcosFzTVFR>c#WGdfp^|{k^^T z+I^Hbq$+4Ly|3%TnYJDEW&M@^YaI%)PdtiPKjHcO|5CX- zq+jG`UH4q>xROUZx9_f~pRf67R2s`#blIp?#!%F`HEn)dmpm-dGrl=qVd!cXG+PTcuF+Ob{N1J`~0-hBXngNMN1 z;A`+B;~e=c@;SHbU)|d@{+W9=-2?2t8}X9!<NAjY? zv&HgT(XVkMe4p``{66mw!^8aY(La1C z^B=wpz43mXdSm^Nk3uiB=R808KIXahhv$ROg5Tpk)#3kWCmwKk&uQ21+THVi=lQF9 zBqH~&*dK=1FyDK7&ezUsA0OpB_r?dVNICA4!ZY|@s^j;b9&*V0{q1^RoqB(}-tYGP z;rPI-gUj!jCnA1IxlliXUm(tdheKaGaz55y;PK%9zIiGC&DAXPdD7aAH2yCB;tgb6 zzqzN+ga`r$i(>L0rx zm&kVl*K)|MK9P5|cl?LE@H!sHbmT}wcBK4jfBVbt?lJx?e(y}5?XfR7PWicb zI>v|Jgq(9phn2(5y5iH;S?az3B`n4U_ zcb<#XBhD+n0y$qBr+pr2r+YQ$xg4HwZ%2I`2lXuGh&vBM!-m8cF z(e^~)-Enxpogc)%X%9WWrPt)D+=;bQxiGm)KVx>;@3mnU$8q}cE`RNV>T$oX zLObQ(w$Gr!pL z@k7ez$E*LU*Vcdh(0eD?gY`zlOHsJRU#Z`4IB;!x^7`vGRHD zCu_dr!>?)2ef;^k`q{^`#sk>r9Pg|<%p>@m*U|c`{?TWCwIcrIzPG*yO#AGcq3sR- zhy45g%DCHSMec7Y=iK*`NAf*D_gi^D{n33r{;z%MHC*S7a?brX`yC$F_{X@4b*6P^ z^7U`Vwex?bu`~9t-Q8}h-;6)Zylr3Df9Jx!`j_Kq-rQm31|6^S(Dv8%EVr&plqcQ1 z)t;1_dUyM6{W$K?Cp^O)|F`Ou{lRs0_&@3q&z%ULfgb#>n|u!YCHY|A`3p}T@T{-g z_<8!o|BZ9AF=ohrZyrLZbVLQcH z?NjEjJYYQ8&Z85@$(zB;5ohi1_3k|2@P6g*@BhjJ${)q|88`Z#FXt}O-J9gxhMvGr zmmGdKYWO~RKl8OC`X^1?4l>WR+q~D?d%o~u=vTfHUXbybUhfk+e)LFx__wINI5&5$ z=REFvqTFNS`v>6g8uA$UOZQIZeC__SpXZRr{e*Jze%_Dso*eSe|L)57{rBs;eth3? z_&~l^F9GyjL*$?t{oe)x&+ouBtl zF!A=aZodDHk)$|pa(lYT1S&3o^r{cdB=hd0uG=nH)yhp0W8C-HyH zm&#R-^=;&Ky_`@g88TT?7xiLev(7pu>R1u&zX0|ovcUvUNq~7`bIy`TP9PUdBtrnP-~vt30&pIbV5=&y=tFoL`K; z*dO=bTaDAqhu`Bl$bQN>oAx?y&wFylmEPO&JvrN%eB|ss*7dxCAMAXA=SuU9L-+Gm z=j`Oz(f;7%_uggvAMH`Da}@Tl-g+L?PHS9k zd~LfEKT~dv&qojU`PIk&=+Akq-q*O1c1`c`r~Znb@K=y|sr;e8Yct<%*Y97vyVf_; z>p2H`;N?R0iSyp@&i^q#m{*~Gt3JtJ{h9tqzlEN&N8e|8^-h24>y)?WXFHSb+&_Gm z>&bH(`5OT7KeePdtw^A*qe>9{PfpN-#j-gBM8j_P$q?c#YAUdXiacTeiHN9$I< z&kg_MdUdAv^@wq*htP9$yx#q}nsGj#x6$9TeO!;4uk_dayTj(e=*{wD5B+)4`+U5g zhsfnR6ptt=VplQ}g^7W@3^Ow>8%)i#zLE}x*$g92f-@V4J+BdtCul&pl?PL9Y zUc6P`@iorXPkbMk=l#Cl{;~FNfB6-N-k9g2eBQU=|JL%XoAN!hLp)mg)5Y%?XNB>3 zq2KxY^uhzm4-(JCAK6~{pI-Kl726L6b-OJ>SEJu|G_7zU(Vg= z_rG6$`{8l^6}cBE?-yEb_&@K9+JD~%IWKkw-=AK^E`l@A#?oS&q*-^;y6{04+S@E)Z3@P4M_0e}6{ete+*;&%_x zr}pOGoJWh$9132ym5TW zIs6g*KKGX#p>nW(DQEJEtOJZEUi)k>KMQ-#`PlYO{;hsP{TBbx&$wTUAB8`ANr%i+ z{mk+0`pYi)GwV3zv0wED-522fS#P^fIQ+l!gYh>{;Nz%2?K@8xH~IWejqU&QWBm9n za)zsXT9)^{ZD@S2zx&1 z>cg zyRAH6^HlkL4sVrRJ9oIgs@Hhe?rVeEeb%qiw%d9|eby`STo-p<1$nLaZPD}d=u7>v zjv$wMWqm4t+D#sC?7G^~@pL{`-@AWg&pWjJ^?ZvS_VwvZKcD|CU;gK?^L2<^$g!gO zP4BPU!~GK8PCc0RJ|A+IcK`jsV;`np(koJq^oqz+{oUSUPvvGEqkru}JNJJ7JP)bg zdJx7#^gBX&pHORGp7i_5zirp-Onb;5er`OK6QBKYe?IN5`HYM7jAO=G zzNnrlm!Bo~>-cPsSx@YD-zVHhY0q>1j>z$RPf&R+Kl`xzEj*uc56{OropK@ZX}ll& zpzDF{v2VBT(a*ZijXuXt>waq7Q~cxasqnt8ucCbR$^*{2MEk5u$nUy@-nCQyq+g;J ze|Kg5*Z&5K8|H&)K|H1oVXi)x!dw!g6iI+j#rtVjne!P%8uHWnP{aySS-b;+<3*B%3a&?1$fbbB1 z{yVBK`M;mN@PI3-$9eAfutxGzia$y&SLnC-?72bI)$auV2z%KX?v!8~Yd08}`6Ywaf4g@o~dT zWOvsK%Evo*pD8|W#TkG8cOvmW{#3iGpXGP?VLYb#OP^umOYe+p_#^yd_$c`wc_#E~ zx#6FX8#}y(tiS39UWReqVgBv7y|?E4!v4(%?XvTF*wg&*eBS(C^X2WS7q1u3cj9Z$ z%g3&}T;tF9E&peu-rnZ_@H5&uar%ju(++R*f9^w$kN5u>r-;4b1^Etv`P!R)O~;dm z@qh8<;=30<7=N)JkvQJ8{NMU~=85}mc3shVg5Kn<89&d%<|FM|Z}l(qxAK2`KgL7G zW4$*`++)6R))`lo9;{q(*&g4W@!pxPzi{F<;y~<1yh-}v2U;&$V~;^FfiPx;{*Pht=AiAUFSq-mc!zQ!dF zLOe)Z;yGdv{SE(T{M>zo&J&Dp;=s8NG3=3Gp_Z#kiJ9K7xf`hU%6dR{QW||Fu!#RRG)+T+0<7rrk~H1Z{?#` zo}WCR`S>UDg_NWGE|23H|0bOuid3Uv{+$4@`lNqN@w z+I3;_?a%bOo+^*|`?_7bA$Fu(X|Vp)A8F4M@D%WLgYr_QX~#HoQ2vj2#<*7gN4|*l z<4nu{!RMf-o_~7O$B$`eMdc!2{?K{*>9PLA1Hwybhe6NNmXmkmeEsSD&)@yGcmLa? z{69X@#81BW%lF;Zea7{{{-60j<#By1j&xmUT^StyZ!M150mGU$KzfS^GuXSfS2Q59PM*2D?Kq@>LVBBCq4PZAI?V*e_-7d@X_$VU zzx3;R!Mt&uY+hSm{qlaiY5C0WTz+IaJIniFH~q^r`f@&pK1XiyPyX2ZnXa$+zw37E zxO&p>otMPxq(jaTJ{O(0)zc4o&i)$`|4@HLo*O@X4xjly+uh}x{?>ROIgHPUUyGY2 zZgroZ-&wUM`yBD{885Iu6Gwi!#zT9>3p>K&(eC{3g!}j0-!t8Lrnt9wn)g4f|MAfe zX~q#xvW`c2)njq<+MeS-`*U3KCM$o%xH$JazV+N;96aZTNuzhlV_%T8{q6eO&vnY} zxQ1V$9{x&x$o{GxLgQ!Jvp(b1E|y!*anJe2-^!2PNUxZm=AWg*GoD9(^gAdY*SVYd zseJ~OyK#EXr+vroIiCIth`3kMI;e|MCUNSFa-Rm-RvX!2S3h;cMytMAmoXO5{&(qu+bII6m#0o%J);3-WiI z^7$*{RG#O1j^sc0d+x83)();K&C_*WIbYZFtn;IF&*$enoqh7|IsK3y&bZQtXnwr2 z=iATeIlmgzF81gCX}{{#_`r31md%KTT?~Y$|yv7~t_eI`c_U8Qp z&M*A_=zQb8AH3YjC&ohzV()YRW}J@uIc}04nEYq{Z{-8=$KsfNw^;pa^&jjt`+EJW zAIiDTC@WUTeSj$MAgEAGzV{ z7)O|&s^{4k+9%}wXb1k!ddx@aqrVgVUk~^k^b7hskLA2?#(bi^{4SoD_rsm9JHj7( zE+?P!>7aJepJ|8H$oql+aE+6B#Q6ySq8@ScdH-+!{+xPIzV7#pzv@5kWBPIHOQ_xQ zXL&T{A^Kh8`Q{^fjwd9(MK6xm@94=JFu%BuHoPC{?lZ#oF)rWhMXvOLfA8NLvmWDs zUt?aqd&Ix?%ee6q{@<4Oa^?Rxk7z#;IZ2E0eIfoOU&wa`<&9QkpYJ{-?YQrU@*?s> zp4+>(6n6ebKkSE{vpau_!((*b?;IO{5^obvL_RzhJSy+sabFZ0eyyiPj?7_L6@yvPNw7l4lU-+?Ky!+E-SNMrPUG{?? z`qNbpeu#YhVh}@<#?JrrD95>n^5F1=ljdA6&*uBaJMV+s-Y1GL;r)-mGI(~zEJ33D4qc8F6huyyS?l%{{zoJ*|iv3r6;wP4$d!gEA z>`S`&9`80hTYO@6G+p^HJI4Q={9xt6)}IhR+vOVnS>;DA(#*pZ*|#nC8fp*DPnOGG z-Vd(b@O#(1q#W-7gYkZ0>t^y}cjN~>mz?iQ#{-J!c`b*&TnGF8#(R05lOIKc;cx*in8EUw#h;w<)e74-lx0q&rt0&`G($?GgMdT$P z{}(aX@&A1Hf4%$DV_v?yb^!gZ`TNXE+21`+gPqXFJ!X&4aZ#S} zop^UXTbn-wBF=Tzr-=f5su%`F6B=DDIM#r|x^KWES#D5!lZFo%Y#faXJFonx`qiKE z-)FyKT%%X_8RWHpzSE&Ux$k*zp7FXb@;jdPG%on^B|g{@-op6Bdw%q1`5(OO+h0A9 zcF7O%i~14c5qG40<(vC}?xSy|9hZ9d{bKsH-o8(^KO&FM!@YgRWqUhfm+Ia5k^Zkd z+CzJBUSS^~u4g?Xo?@Q}SqDjbE(PWPx}QJmw!icEe_r?t3Cb)Oy1!=#S6koEKBh`Mbso=-+i;L~h$jFMB+K-}oG4e9!L_ z%soNnavwKt!7tjkwafetwf2h~ryh)>_KFQn^P7Cu*Lkk|!*ltb z<)^D%^k+GLH%I@ZLHx__y22~qcebP75eKP<;rrkLSVvBt(D*?AB<_+Qu)V&sEZ?}# zuXsP~2;Z(AR*XmUJ!yF)#tARSyy9NjpnMW(-)BZH__h^iz9BE`Abu_nD4#g#@Le!Y!Pe#id*eCdzx=E>*$^1Tu8n6CgMNRA?tScL+V3gPw5wg#`Hr4l7ef4L z=Uea7qtE<((DkKtZPuCA8~u&>g}?e9ap<~(pR(?Fp4j<6`f(n~@4+*^mBuc%BgQL= zjzd0Pz7fBoeAqohkhmH@A|B#*ywVd-;io$fc&5=O@z`7V*7;^{&v@VXY2v2g|JqMO z zi(_6gUi@>#{d_?E{ru4Q)_m)C9_V}rroXSQ(efQxewF^!lK;9N;{Vk5oG|51c}vUx zIe*oE{GdEj_pP4!MD^8qn0~1rGEesOuHW!4s+ueC1%8}1F zMEF0_@qo&Cz7L!qHQ&dNXZ^bOukml?+3)wQ`<441{GawD?m#Z%6#2i>A#z!6-uE^B z^7laW>GQc4SU=)=zmWB9PmiAN_1Savirm;Ubp37I?Z4_fJ}}o3X22PBhQED9Y6LxGwusb{7SpyN4BRQF)!?I(u`-HSNh$| z%huZ!^}pulit>NE-_Ckz{`&h5dKyP!~3bf^WL++|H}Wd|Mot}TYR8) zY5n7VCvh3$*fAauxzLy2!}}kP|Eu`LmG1p)@Bbk`ylQ;kAbO{M$a)^{2X_AV`+w|% zAO6k<$ZrtGyFZfV{nWkQS1yWIyp;SS-``U1_zmwn5zot$!NYy;nljWb%X~H{-}}h}W%TDydU4|GoSkrt|z491K}q~Gu{=658?-jNARl^d+(|^i1^5O=WV2XaS?c) zPuKW~b4t(m_KW*=G#(}HJoi)llKs?p(s-S?q%``F4+||{J@o210Q`8#^&H>se2M1{ z%Q4P5r?2N^o|iVhOrLL|`dj%I#?kq0Jy+3h=ZNCI&NKbaJL%Df?J-X3KkHMy8Mk*& zt$043hPci3$9B9Qhkq*ndH*xL-lK9P4~QQrhx*O0?)}g5>=W|P_?2?(y!7Os^6lyP zzmWOFI0xgSM!!5C|Jn70eCkQ;J=@O9XT8$*dT5-X^N98tABdlWwokeG-+4gvzUp`6 zEdL&nuX;OA(K)Dl$m#X8%kBsD+qh5c`D^HT$?+l=`z?sQK;=zeVSdK*dq2rvMo+6g znwRQVefT{6)UWsbIG1=1Jo!D>588`A@_p0S){k=?r627uIOBGl@4_QN`6y|p>o4AKtp0qLgm#HTEdSd6z3T@)fb!vL zm(?%O*J_X5Pt_;SnKzt&L*g{g!y<8v&qdm8fBE>LpB?FU*7LL9-G41N{Eg@N;Zt@# zXZ1VAZTeh)-6wgD-1vuaLi^`@_XD{pck)(~Z+)N3gVCOP4cC3z^(Os@>>G?T?DxF; z`+y&=a_}2pTzc+zOvll_Klh%Mb4}Y1`~2(!^L-NJ*m*znyWS5>AA|Ti{fM=1TDg3# z9;e=FpX`KR_&dUDX#L&J>_7QQ@vHHO{@y+W<}dgW>rCktSDu;tHO;tOH$&DT`?k;F;zR>S|%4&}r(ZbXmz>x%MRw8yC>YgyqSCx=ywj)*QbY^`~7F+OrOaA_PsyPos3I< zF#Ckv%hN9D-|?we?kPGx`A^Pgq?NPxe?9N0bYUoWh=tt$Txt>IVdmur-!`o9ok_of4KUCulSD#{_};l`ybbH_%+J& zUBEwFV!;o9od4s=cx4;LW2mAoNiLO`3EiY<5aR|?iFT785@(}S2@_&@q4&>91 zyd8Fuw-k{x-cN+DbsXU@UeY1sYrKws9cSahujm*42;}@H{`f-YlXfTH@$x*s3D^6F z)`z!ZzxtO8<^9O_eQd{R+V{47KU;lRU%kWEnAShx6-mPruUNVC*tm#$tlzl)@nLWB z(Z?OG<5rGRda^z9S#RD-<0m{1v4`zDUU@(Cj2=hd+_xpoxpqbRQ*PsH z>}Xv4%(uxK?)+!(p)>EP*Y5#?@z>o8mcK)P`n^0Ib|fzEej@r?kasu-berNey&qIZ=QuG@0Z+z>S>k3^Mmslx%TwR|1n7ftf9Dk2A9w9D4zVPFfKI7IizMnX@^G4^`do*rTUvsWe zPW3$JU-iiO*l|tT@giUGH*y$Pb*@1l#XrQGo-c^6&p1ln54{$bSl;&Ii?rvnJ>*y7 z$MA3M7{>dAZ}UI2f7fsJuYd5=*P2$(+SUB^9I)r#`CWe7xI*|O|}fT9ddeqM1SBtCdc7?Wqn-BGY--r z_Vs!4&Ak77KJ$z7pXWCFmEU7sQ9u1o(EYj<9k=!3?;J<#>TC1jw3GJI58|KPC!X)K zY1h7^$8+l`@AEphuUD)8-rLP~p1-%p{>Ql72fLSd{x15%M?B5AjYqzGNq>J!qhFr0 zPFn5<55!MMhuE1k{aPM=P`Ql<_VxJd^d59kA55HKEagTiH!~O7ke~%y9KZh5ye($~3?(ls)$G==}m1E)r*MIkg zlmAoxJziPm>v`z$~md^yiS>hJF#a}Npqxn5ar zAAfpwe6^pv`omp4%CGCCX~(zb)4qO@zKv75|F`Y~`oYS>$@kzdypQ|L_c319FZ_!6 zaQfGoW?U!#=lnt6&;3_kJ3Zew^xhZ$f55yo9&A5~?>iCxPrmD!|FggL{dgk%qWg2i z9gZs=usHD<)sKGRyucpKAMDCKz!lL?{rmkw;wAYu`o#`|_{Z>l+POF}oc&jM@kj5+ zJ%1mOewaVTN0xEQ_uV7o=6uO`YO@XL^qYMRWd-_Y2kc@PXvRdo)h%W14ZooBrfN<$(Q~7g(nl?i5!>r>ENeG$0Nxro$|iF#utD2%x@S6@V!KNH||5iJCZLS;W&r? zB)|KH>ODE&yH@#1%m4A!*?+mlBmW?u`LipnJ_m^}XxDNfd{I20_Z-Ksp4ljqEoYyN3-*-MYZe965>^{7l zakTs&{TWA}_f)-)8~=yiX}9~i!<)%plfG-W_Iv&s;(x~NE6?7%)BkvmA2M(FUF;dv ze{!e?`AO&9%s+TKc}jWB_(=5ptUu=o`HaW;Ex*V7aenjOu=8tu&Ul^o-XCP0B)%uU zdq&qY^5H8y2gD0nUfz%Oyzd9@?+?clPFz!bBhs(&PVq|d%lf{B>%8TxSNt^R)V*E$ zGY;q+zMdD1FFRlEaqPq;?%U7tig63PANs%N|LC7`#m&aGjHCFo-}S{cJ}pjlyq$}8 zo~rSS?)&}@yy{W;CLVO$w0j>nk9?hXX#b2e&=>LUAn^xr_=@r)#7mB6KM$gp)jq6a zq~pg}mq>@K|EA?(svjorYsffk{~7Z?{G0lN#@pR%HGjW9gPqAoj*#|9uZaBi<2d5| z!r|#UXYS{t{3j&N|9JHi-`D-WP`f!E$}z4PzkZP45AWr8OZ(h&->KK+IC1=Y*E97Q zzy7K`>SNWn&+qh|o<+~U{qF+jEzfa|Yu@WBJ^nuPZ1=}qKgu!sBHenT-!ksjkC|Wg zW4dza!8nojkl%LidB2gb^Z#8r<{9gT=)7O~J2j>?2eDamc@tyA@$NPnE@qg~$-(2s7 z{qW`YLhk+1ZukG-p|qRdCqy3oM{K>*zmaS8f9$gJf5c7fkMV%iYrh1s2k1J6o#AWP z=dk--`#Yb~IwR^QpXX)VN6+?IKb2!e?g=4B@xp67-|%9z13%_EFnpA0^X2<&SHHiH z4^DYncf<2}Y4qy4?*5JZjt~9Pug^KhD(~=r$b+3%`JJbZ%XZYu&i|oT`Uxq&?{ClP z_Cfui=k%8!7?-d<<`<#74)@#GCs%oGr*ZoK+UnVI=!tcc@w+bV@utu9$9OpYUjV;k zKf+H%)<^wr&u`xB{)+#v{ShxP-+CX1ep}C;`*Xa1y?74xf06q24)(kxUj4B zd@mV3?pc0$KIHVd<2TKGT=nYxzIaK$&*%Hn@srQ;;a9G|qV3PUM#ks=hR7#6UjA>y z^%@=me&zj@=KhmB+Mw&Yd!}ag^mZrf8fhP_yPGd^}soQL1L=qO zrhAPmqG$P5%h7*w(T?(p^yB?L?=iw(DF06%`P{Sg9whf6Rkv2L)glP?db{*~MN1*`+4Y2SHxkMWIRdchy8f6oI_j&`vV=L6=E=)K6E(~j|c zJfZImBRBc*d!8fW_uj^Mz1NU<#`D6rMR|bY9O6{#@7VLVkT|OI$ZJUZ#eE+i_L+Fp z^T*En5jXDnzSlrIpC0v#Q$_lvJb1QmdX4v)*PinSR~{7qkw1A2(TC@;6qo19=EwANH_tz}exMKSgFic-c)-&7+j-6| z{W_1Z`)TLLbN)T^RWrZVdAH6-?J?!lyZ*Abhd%X_eO)l$c_$A>y_4_bIrjkH!p^B7 zc92)o9_u|l=p|H7+_&KW#QyP$qW|qe)`jdj-#=8p`~Q<@FWbY8wCg-% z-J_k>Ki6;i)33d+gB@Jgc7Cw+2b_IH9-;ZY&!d$eK`;Iu$N8N+Wic2$3_C#@?W zdSKq{Xn*(#?XLWvd=GN_zr^xO&pg}YpZE8W({@)LQ=SR={NI<*ahE^()h^w)gug@1 zmG>i_UU^CRKKzY*^~3Z2p9TM#`+ttR_MOL^YrcQ2PQSVM0}-C>%jGQ+k>z1{@oxvAG}70-f2(%4<3v2_aCqK$T=VX z@rC~ze(B^tr74`dvqu_HXpigQ2F`o=f%DJOpt@8@^^(hm)C|59YUq}2m_CGxHK z{u&SOHN%4;Z>ZfF7xrh|@PFt9J`v=9mDR&99|*rh8aq!rw&%S;#+_Z{JJ7@MVe)v~ zPg7svs}q-*o=jeY@`MRj%(U?!4dpk4*PGhi^ol?kk4F`^6L9^M8#8I~dQe zyr1*U@p^th-;BHO7!c1gF6QNmwCg#f?-}k$f0Tal8+pg@7%Nh z9}04FKM=V&4^ZCooWDEbC&nN9{XpV(cXZ#HI10b^Ji5p6 z<F;xF`%onHv% zq#onX{@)Ib|K}XDrsHe%Yx-Bep07C9t~^1{M^5Aa`5)ixG2>0%d))aj+I3yzoQ0hE zQ~abnJmX&58@=q~SmkwIAs6#W9zle!tKRy)FZ1<$AGmU$?I0)hXP&O}mHfsbxq`4MPZ{~3K{|MVOWDKa0MpYDh2cavRT*vFZd z?(@7ygnx!#y`%>%_ti^z5&3Kf-Vpi!%ir5`Ki~O3+BbiHe;9l3yk5MZ?;rczc}IQp zU_0k~%h_Z79*N^hAKxqKKi%qXixm!H0uR&yKcx6z^{CK z=zT}Zk#G6@o_z*CkT1%Q>A&@a^3KCGevp3{e#CZLSFFFr2eWRw@5qb8M{w^{xz_uB zEs?9OE6mAm{LM@DcKL*n$1+)K~dyJ$V;+8F`0zKY5tFowL2#DPKJyALF1T~|O#8o*{0^bNimZc<)AbfRQ{MHFc*OrH;CFa=N9SE} z$NF8*>V?W>Ka@8f8?4+Q{z^X}d?oh!>&2IN-&c$$lvhJ9@MGPVV_usEiT@@ZRGw#^ zjs9sT#6J2LexD!CdeS-~|ApS+UFdJe^5x5zAKaT8%x=oL%FTG5)7*<>oamu(Bj?Hw z@_V)YQjYU1Y4{S#ao*#9S2)K{e$T15@_uKUerW&X|LQL}l+XFa{b|R?eDOPnA?umn zRh9Q+9<2Ny>k04qs_(TO@BgVk_)5|rFW&E~cmK=9FMPPX=U=aVQXV9Pr{JF7%1aEd zVgAW`m>yok`&+~Rb)Tzz?y13Vi1K{#eS_G+_kyv<@PMob{$DS0vF~$UpZ01uMBhBu zPTXUIpZ$-A-MQx{5BU2h#QySu)Q9&H?H|4iIpW9U*M54nhdl6sC*PBPw5Rck??EH~ z%Kyb<#Iv0IpZEXbYv^#j?`T^7Pd-;(QhAgUzVH1tKKMZSU-?SpW?Vmh@OdKj;QvD6 zuU|c$hw*=)^-umYeovfxi1BzQ#{b0!QqS=+E_uQ*JBP@>@_?lG_MX$0NAL1%$wNK* z1-hAL{w%f6tdk#n0q(et(UR`A?d84>C_Eho4v;9u_-@ zjF&X>gQWLi+;&>Az4p&-H1D${&^zuP+mR}dG<8z8;6@e z>3B%;`90hFyGS1EuC!g2<2KC*-?&WqL@GRfG z!TlZ~{jIzo>zC=iLm1z;BlV2yyXP10x4#dJ{Kla>5(gXii@gsV-xqox(D->Rf6tF# zU)$T`cJw&$uyN2D|L}Z2@0oW0QvUTEF#RM4NPOV$+|-*mL;BW z!`)wa&xiUU_EH~nUL#$8?T4KM!zs77bLN-Eo_GC~-?&2Z)%&x*?ta{Ju=#w4mAmt6 z#vN}I4u3Ryv0dWq?!kN=Z?1aq zfAEIQFXK&k5BxWz9)4`U@#@2qQXl?JzG~*L^_oxk5A#s}oAqS$Iqk#u(a$~F5B1<> z06g&m*L;lBu zC;zt#%V%B=pCO+hAHhAbNfZCZH^@(vUil!)b1#hYzq;`Kh22Awhl1y$f5t5zH#oc= z_2PBpsW?B=F1*O_Z}KJc-9Gh5zxG3gf4Ih>o#6dAul(-sDDOua|NGrby+Pam-KAgn zh~Hg$l%G*P<&g*KJ|KFLKZ3{dJ!0dKzJmyQJ|Q0-1%%HqzVLr4cpug{VzBSbsVDTq zxZrshCu!tE-^dF;M;g78hKG`u#7@~yUX%T0_@>{z$OV4)-M?Mq9_0UpeeS(L_#*8t z!e5rQKm7sz2Yn$gX!?{dIrAIkOzyFNe$ewl`nR9@#SiJ1bo!zGDo66r4*A~aqaOcL z0_v~oi8T5%-}%!#I`zpo(Ffy3Z}4d9^Jf?4SB{5#{QI{H;uoYr{12W{{l)`oxB3m0 zZ^l7=|IRb{Kk5;Ohm6;_ zy!UedbNnAXgZ1|~o_ynY;|1O?G;Y|-A+PbV@B1Z3Hy@gJ>pQGSFZSa$K+neLHt3SHF2Qrf4uBQ zKiuOJjhDO!Pk#HPa=5RupW5Ca9G9#`NYO2>Ob^Pzv60t^*8=tImheyQ@(8|3Uiu{sj-NR0(Ytz5@1ElJ(}6}~ff8}58@@%K>nGNsfzLTBq?V8;ke|ielOa3zG^GR!u-7j{&3xDnW z%)L71i*awfT))$a>|gHZuknBJfFSbxmzVOx!&(1Fk9^iI`UA;_{{uNs^4<}A>Y(H1 zIr_1E`l;OcoV5Lb#vMDd&Yj~eei-z<5Yp`9AoBX1!IO8`{dnf#zHYQ0fcjhe`t$mY zJzI}iFHMJ2es~i7Hot_&V4mf7E7Ct{QJz8GV}CEYa`+4FhRCIV!4uFgeO+vS$KTZZj_Aewou8TZ zhOd#|VgHdY5!uh!_u=)xFBWwD+WEiu!R`&h?`iLkFLoSc{IrXG`#pr;$!vE}`}q3~ z@dA1T<#~*+h-)UF_aKM&(|;;g+=HF{{Up>s@)LQ!c)vTe{P5DQPx&AIv94e8bovK= zXqt7~xT^G^eAV!O>T#ZzMql`$?bIIV_~28pv+2Qoyp4N!KJ}ZvtjF)T-OuZJ*t|O1 z^||_n&qEIIi%aem$!DDjYiH`q^YMK|&K>YIEB_a77*@}A8dp50ydVFYNPqBv7!3Xo z-sGQN(my+p=kP(~fA8<*r=EPG?a3=W-*c2#g8%b(U*}uATs)n;9{2s^!}y;Q;?6<+ zW9q4wsc-wHyKl?6MPAf-2`_`)3Au2GHm56dzvri@luZcgn#7 z%4^ha_r}(HOWHvm4j%EVD>{PD;D4ispIZ4I&cpH+!~4zsH0C4srraOr-d_EnSMIl| zSKjl*uYUJ;)PLan@H=_G|9YYIhM$2q`srhQ@C0lB@N4LC-U~)v%PTkUJ1ZxAi|>7g z-hbkG|A!Ip7s6W^H*h~nUN4?c-p~7L-?{Yfd#CVzmQxORpLjOb$#`9HzgH$d#`yVe zB;$Yo?tguZ`#bOC0pDHs#N?@d^BA}MAM5Kk?8Z{=oAv z{%ugcj(LaP;{U|_Dr8(geeivZ_qUfmk!$!rpUWr8`^DQ%fAaImmwpD<`;N%7^M0RC z@Bb^q|LYhx_x~pH-2U&5<2AmO&%^GNe+`k__`3VP@_xSet)6*~zMT)W`~I>w?V_(0 z^&9)!`M?N8;f5w^J5rFuq(Ry>&A#aPO#2;k#_4;&-TxEO*U8gNyjdKI-ioi0i#TL3 zx$ls1-{m9kp2X2I<4T{@3{p+qb>+gZz&79&49!Yy0LmkJN|v z?J9>om`~UzWS-sefj*ayV4Z56uwC+7N0Q?X-x|k^bGJA4bw2F;i*~o))vnp`UN5ab z$i4EQr5n%S_`$66oNqbb>u2o~b02Q!!*+gb=jZej_jh?V`kS=<$j{jh(TDX!^gU_yxVNhutY_qdj%&Y%xc1+7iq|-TbymL5@0Ad@kOtA8JRtgRT|51M z<`?@DdOuOWp7on`?e%py-Y=YWdiD|h+xHr=FZ&6 z^_y>l&QHtr9lu$hoCoph@zQI&g8uN+5WDl8NcAeuX}xvc(eB+maJ_P0WIT84SMxBu zTNkX?x;pc$@wl$ZyTlWP{1YU+2`Jz8#f9(=q}A8X)4>$v3)Ss%Z=W)bhD>le-&&KKVMgx5n~@a~K!o^Q}` z$>VX3u^oAOzw3y9nI7J6ct`5*{9pHx9YE5B^4etowh%pJ8u!F6JwI-1|!&_@|LG`>%-I`m6n&E^gg8ekhhc9lfR{1`M%o2j%z>izn8d|9E|&OxXzdLULW=D((pd= zee!_RCyg8+JQv9Oy`{C^K0hf>{)&tPd*C1N|BN61@*bdm2ES{(dXFbR2v14*Fh20Z zHI6lZcs;{4Dj!IkN}70XMdEPM;90+T_MZ2N_nZ3%#UsyHJcXa_yhrB%5q%TabG{&sEsfm0 zxAZ*z0Z`lL^+J$QM?BO1TbPigJbxIpE(N6zCs4{68oh>a(F zKF{s^pS<5{cl7H#)Gt=OsPEAe>6t%{bGI|&new#Ty_@FamoM|u?~Eajdp_%H<|Xr1dmxwV z_xP;0#x;I6{GWd8cy|7e`N6(?B7R`pAiu_VNxznVK0nLRKJ~-OgT^5ze)W>SBYL|l zPrK&-!vjlCf8Aqz4Y~Jdya0Z<&JF0Ldw{IR#w#N2YCqNm^-Fr@&%WQB`P9eGA?u`m z`#RPi`#~GS(_l>;n$ENjDLRi7f61{x-{~`15qDd z({%|sydOq8@_w$Tq<7x0G&~->U|4?qW+>lhIr=^MKlP%2_r86+9eDD2-P_Y2=3Z@S zc`E9mZ+XN1_XH%L`Gud=AG`D}@Gx-AEN0e6~&3Sn8iC^Ith-0{a6fz&=9YS~= zcnHw;{`sYy?gQE`?aR}_|H;e31M&SqcptteG->~b*tC2P@ig_}7Y02?P@nU!_toHK zwC^BtbMH_89G*`-KJ$N-V|`Rl@J6&JvR=Yx`F!{_^y&SvctH3C`ODrDmB(bf#0BWZ z_#oax{sR5NZ*XrDo)7zh+{=US6S-#!zl-0&yE1>UGyVeaCC?LT=Xl!2h5c*~J9CdO z{P!yj?>BgfbA3nh-jQ`^v zr*XBs-*;Z&0pWX%x5eS{;sLu4`0e;V^kn>v|EpK#L;1AtJQ<$+Zr(JHm~TCIJn@Vo z<&4XEKUo|eu1i%BShiJm>cS5cxv;i}wrT z{lfM+k$7q1e&Z73N6+Oxr=PpD>!|%syTn6$fA2n?T=_ruZ{w%#b@+RyzndeEaWHXS z@wNIXe%;Ttokzj*{A`>F|7E)qZ!$jOPRALK_wiu|eka2oBK9(U&jV6!+L?ZcyQhEq zGfq~XzW+m`pz;h0k{1_1$@b_OJ`_ zD@Z&c#xuXx-ko1LPW_7bPkGjHqvtbCdF-3K#~4R?@w_)Y)qeiN9`qY# z7taCedFH9@GOp|?PCk0~IeIl8{ZLN)azUOqPdR_qPALCJd-8zhBQNbW&c9yoef;oR z=T>`TSJI~+oc@|U8h_8JH~rKfc=DC$)AK(O3iaM!k*M|8^2n1t!r=`$R}jGtvVVQJ z(joQN@{=}S9zngR*XEzNpGSAQWS?0__3Pm)Ob_pHKF3b=H~tZ?pxm#GANjS{tWW6g zEU(?i9{Jme*s=5V%A=4Uj}p4C@BAO_y_Ro0@S{h3!8$l;0LEh%rhdyL!{^!(HN)Y`>;h5odg zY4khuaMmr_UCX_d_I%Ac+q#Us)hbU z$H^1gKJlD9p!3f(?I9oUU;gEaOTM_y)5yiSlX`qtjpy8(;d_mq)0D?F>k#>%<3VqC zeCf#pc2BSSd+WVg{FSt*|4<%1{_Vl5%I~31cy!VJ=YLYjo$Zw_*Q=2utRdf>_b#rL6)wH)_}XqWdU;YHA=e9+GS`F{u6L4HPluX|n3=shof z?}88FUeREDpyyM@$NeaII{HO^()bO0mv-CvzrOnif2iLMvOjx|N~}Hcjz@}LIT3$i zf5(47#u-lm4sWske+Bal{*U?f^@WUs`&;pU@w&_#ct8*yEX2P1`=`i-U63dJ$p2wa z_V0gr_yhO6;GKBycg3Cm<9U1`{>6Ut^@e?~&iiyH|M%e`2YfK{;1BRVE26JEKPg`x zcKE+9UU7l zhyCUE_I&I`IrJyW^TB)45B%?r<~L7~UwMYdG|p_i-UFl^{m}pM*59!71nYL>`Xzj5|-<<52fc$1N|&cV@H?Y0gJ0QhtwT?|z?F ze{+sfFT?v8FZo>gk+*Z1@r%4#{6={42c8G$4}GXt?QUGQ$NSkw`BwXBcl4m1wFl*Q zULpHd9=T{o`Rd>IfJUD3?SK68Oe+_0o%i^VN8Wk(u}P2oji>Wwh+O`EDD&ygADJiS zi>w=*lleVv(EXWmjh8sg{>76Q?KyH&Zsxu7rg=a4@s!w2y*m$^kM*}cm-nN5{b!fK zv8U%$?j2|k&!zqkDt0GLJ;vGm&HniX{^xUeK-%FvwBo&-`nUb&pZa_JHM}*?AA>$zVd&>pVTiOz3zNs>DpP- z`a!&^dggqLzCrXa65p-!)N$+AcRb73dF<-Bmh|{vekiKf)~V<5cR$E=&T%>}Oc7*sGq{0FwPaN$3BiCtr4`^IOyukQaUmPdApZiwmd}dwqT&zF1 zkDu#l>+CtdiX#T+cR=SyaltdzA4q?#FRPt)yU82Gck~@a?cX}({i^l5kkgO)bzPcu zH#zm+@jLTRzdw0r`(@rM_m>OekEEH0-+w{B1IfH>oa4XvS-h;s_>uoL#BZFB@hz?g z^k+SPk71svhv7}veraF*PaNg?K|RL-U%?FvcoEjINzXdw{VeBU`h1RaoKLT<-}^f6 z@0HA_SwGaL_s_`3FMLki$oj(ivG$9e*8WPnURxgi#(f$2*+)ay(fBa+p&#t)EaMve zo%+q*eP1BtoX&jr+|GKW9NgbQ9`cdr8NL7Yhl}T7ouD1dh0Pb!^vCmf!Fa$ypYQhw z87KL7Nc)^$MD^!=$NTc~jK1$od-5k?eAuAlmXE_8@>PF%@T8nG9RJv@bCc(i_&@e_ z&Ovj3FTM^W-Wue6UHLiAO`gx$PdU#pA7}@CzytpIdS93Sp=3Os1IrKPk9h8RPhQ&b z6K}=?GR~FHRG;pXoJZ8Z?*+r-sYlbCFDTEsMt!WvzR~?Y{`VTcAEX}X(ECF06CYmq zxDVI4cIE##r^^qB@_Ot~@ad;HkgFg}BW6*0T zuL3`({o(Jvy5t@F?zIZ~JmmjVhL4eFAua#s`^MbIf`|O=ImZFt$$BaO8Q&JhAHn0qW3kV3-T=RU^*e|je1BL(e(nbhJNNd zliW{?|ASBWy>Ivz^WpjA>j!DS_k71M7+3sXdJer0i61ro6V-?I&@bo@{}_Gg*Y;z6 z`eVL~KYLEhe?fR%`M94vQ2tN75C3QS|Gvu89>{#*Iq$CyG7kAa`d9zn`(wQJv+{w> zN9#HNnuppyKMc{A@o3oh68XO%?Hd|D%M)T>((tbr@^j30+wFUfJ0d6j zhqR--&J)^GKED%yJ}qB<@8io)Ql5PiJ+pt~e;~hyfc$>JJ`e9_eARuxUp&(IE&B$% zHqYe`28rX16GZq3+uM1G_=)(65c%yllxJkz?pMg=x;FdS>}&V@5BeLPZsN<&=gU{% z2gUour^Yw(0Q38@a__v0ac*%s?MytyIN}BOeB_$*t>?wgpCZqV|K$Iu@9)Dq(trG& ze4qFE*f%Gwe5O}E&~dU~6VKJoitfLR>zTJOUOn&Ubx+B2N$0Q-d5g2}`Ly+%t^GXL zcy5Rninl_pyYqJbklxdG>5%;NKYpXW?&aJ0P3k+Ic!YiYj<@#oGsiQ$A8C2D;=#ew z-_hfpA5Q)q|L3}mKgt7^W?skB>Hq2V)N}k_&%@#U4p85)>zWJn)>#gU`>(x*2pEIo=tp5GH{>(Vu9_RRP>ylXh z=y}yA{e5`I^%|lV<&Fo;Z*7P3VSJoOdEzne<)B~JMaOSiz1ME2emlqSNIlPKgPrpR z)w^~cKG*cTf4HYBr(It=@3tO<*|YJWC+0uA#GwABo#Q?A+t!iQKD*!LUvKk&)MuZ@ zPmDAEb4Y#TgZQ`M^N9CocgL?@(mOI9=)A7JapI3&;zi4`F7TZ717v-%9sZ|~ z{!g5Ei1D%xI&R-5CjKA|s+WCzqdaE@JrqYpk4I2 z``7p#^6;GZI#{QN&+vTuoOYdIJm|M^60gx;{7T3?U|$Yhr~3U>f1>}p{B_++e&vn# z6Y+ENzkHE@#Z}JU2iG4RH}>@2W~jc@hw~WyF^@)X$YVLymEm_7H|at9*Y5I^j=-3D*C1 z{Ga{f59}}ck#e*CsJ9sh>G;)^2a^}XUtAZFbN0jhBt) zp+R}DKRmt{$9X6oP<>DiK1jr_jwkfJWBlEDrQL|1Ni!d?EAu#1p6okVd7r1Rd4AU0 z`966+cs26n;pl&OzWBb-{&?>Fx&8YA^bemCVpn;;P(CSM5S~xIFa9q%x(DcdY@Ksm zT+dY}?`QqSBXW-O{bJMjkK-vVzlk4`PrU2>y=VT9@$l(hG;v@`kZ{j1^q z><7M!`D#9VjrVqc`^Q=jqZZ=$^CelJoz(I33bitwoMU?ArUeiszqUGkF-ejv{2y^p{2%^}AMF01U*sQRykGdNANjv`mmR2IIqbrF(%v7$em!6L zLCTwke{nqW=h(-z_gnMxb3Rc|J$b*cdw;}dQ!t0U-jWhY58TIHs7q7P7Tb<|hvzA9c*6V%u_RIhJ z($B=Z_AB3q{P*dd?>l)y`nO(k%J;GE5GRH5g4)~tedXO4ziHYx?hTEDhX?Hc3;X?h zkb1*I7+3$loW0$$EXi?Z*I?uH>281+aUcjJhU9RDGomEZBj}c(5kEB87-=%j`#*?k z)!Ga0k(GO&hORz~$jk^2cMlJbFC(k^9iI?C@;;IHLq6hrD&rCBkLT7s|Ll6k{?~kj zGWn48@duW#yaoB<-F@@?xxYsK>2Lbs{_FV4lTMudC-v@gH_H3%yvugoPha=vl+QfU z^F=&w{qS;E-fs9m>~cNl=X*MNKlOTjo-)r}`#H;3{_Es1c|Klb?3NwD>=*wt`6zlx z?;-Z3KCGU8?(VOC@N7Rj!~@JezJ0yCM|P1PKhOSr+&!W>~H(CcJsVl`_R3A#$L8VKIilD zbLh|KY!5vuU*}-zCpp|Vb}k0Ja6k46&wXM0!z=FnBJ!R4U(4>RYWKvE-?%XRndPhf z&v=8qyzd^j-(_Fzk^ZjwrCvLD-}SuAkKgS1>3JV3t?^Y}@bqK!Ipc93M0|4p^@{4x zetUm0{kzZC&hTdH@fEQf_P^phPybzyr?}eHa`xPQLBG@wkLZ4P+tur*Kkac97tjy& z;WeJmea#!~HgO62nTOl{p0Dl?hbM90#lDyC!pti?*M}dOSA2~0>wELg-3-Bw3 zQXUZfY;HI7eyqrSX<@)`Y( zbwYm_tX=K9`=P)5xAw1mw((g%gv+?Ha$K*cuk?dn z$T#+UBtEe&!Mor;{GMJ&|9l5LXg{_4ip}Hfjz91B5$=QV5B5VM-)YHf!2hvN!(Wku zdVVJ`blzXzkGQX6KW-d2#{-Y)ciW81^L>m@|B;WA_mgjBUhcB_9(raUpuYV+o!?jR zoG0h^$TQ>lJpanRLVNZ-JNGl+Pvkz&0eU~*ed*WEkItpN@@?`5`}e}oKfDh7n&-UW zN&GJHubv36BQFu}GyH};$I1WsJ??xL{ONH%4gT)i$M46nKE|V9H`hVWd2!y|@;*ne zf52NY|KJhXpAG6Sw2R+>@^@jpAKwupH};eN6P+iVcf`JqhwnJ`?>qjF^LW&Q_IuU$ zNBkeBt{HcT-0@oSgz!bg0nVox53c{`;(0%Qm(9F_>$KCkx6NP4_sw}o+x2`Wyb=2R z>$h=ZZ}c|5_ovgktx$anR$!#OpO`Ni)Fa&FmqYCZQOM@T!$C2xs5j>qrA4F5_jz9VuNcn~%1@YQ5~p7GzqB*;!)LgD&wkT<@H`L4 z`slhB4!>4@Sl+mKI`l=EacrKCa`l7ibILwy3O*y*ht7=NrEt?^k={=gx!S z{qFg{_(Sc>`l$Tu)0Jb!Yy7(I55H7)AB(_Z&96FJ4&iR>mztDAC{*UK&nfA>`zQ16+-FeQB=go&cM&_A${vDFXaULOL-DaOM zh+MlL;sIsQd}i|p=*heYbUcHOS3Z#V1rOyu+~=I1vtHlLGvw1A-bWsy{pNcG?O%KW z9iR2a3C4vy8EC&BFK6+Q@p4~?Tt1il zp5w!x_7kYk$>~QCtSz=jEA^v-r4Wc#M@4P@^6%1{T#pV{Frhe zU;4UY`l24c4{cZdqJR09vt7o=eY{V&V*FT0{B(Yc#e>j%qWQfMJ?mFze4w4;OFYxy zwCD5k{={MUf7(0!S3ki&;RmK2^^t#s&L90rzx_zBy$3k?f8^Tp`HT!H z2p_`vH<9)zgW4nXe-nrk-#@IyzR7cC*cE^JsNo^3bg74~I+6%xPLH^1_J@)$pi|Fd1}r2owM3ga4lpW}fK zg%{e0-M-BK$;8s^RP4L`aV78ZQuENPLS`0v@7?K z_no{SJYe|fz@*JQ% zvHX^NAO9Z$zsc_iQcs*7WIk~necqk_li#vE&OZ__TvvAs_9Y z-y`e4uG4)dI_J#flX%Yas*YE`ZXSWmhmd*Y{OG&g;r~4E*SWuN&i`%xk9^K@{NK;t z%D;Fb=K#Hamg%2*Q9V({?#iXT(2M>!eBg|i@$}tu-$ln0jz6jYlP5(FwsYQxJk(!# zzsljxcX#_dkN?vC#_D~KfSowU8OoE|ul9}i-IIUd zI{ANyTqnQMI(di66W?*={Vd084o_LW7k}{nKG^oVuYL7B|Hpp)s}8|K~c>xqXnlWKezWc5F|5&UYx>cfRkQ^6(z!IqLt_4#Vr97p`yp)9*+1T-TrD z3+|t--nO6E&;9(Bm)mx_^W*$)``z_E^pHKT zIQC7?&7U*gT=~}cKi>QDCPeLP0rz9^Rjv8+V?eDaU{2zHO@}B;z9)^cuz9|>_P5$wB z!y;|kyV+rIN}-XF|-wmW_8vp8s=xl;>er;*kCW59odtKj2&kyc*|9JYUG~ zGI{QAFh2?Nqxx@O<#)gQU-Re3zIXOlexEq}CC{smLDpaD2jL5e4|ASU9*}d1#Ibn5 zeizsM1m{`d0sGzd`EI!Hhy9+|^L_W$LOeoG*Jm8Gq$9;sHI6C@)FB{x3sFyWB787sLN~&SrST(VM(xd?0!~c@_AA8TX8z zb34Y1cntVJ^~O9$Z(K)S#wlN>f3i+;zHX5C0RQzK(vIJ?hVp;-LvmcdXYKso`Tg(w z56JMr_z(X>93QHmA;0hf; z_cPBB(Yx{bJcnkz{NKI~e?+-+ZSYIBCy%B6@tb&V&(UE={pS9Ed*N}IN6r`g>z9j{ zqbyHHUI0Hg__IgZ?>ecE2P6;kK6ydfw;YccPk6`w>9_KKul%L{C_i`Q@2+LOlQo|f zJFhx;<^Rt6_RjL~fwmX#7vDGN|F95unm4q^`~mf=L3lsxOFhVYfQ{A1 z57Li$TPROR`>eB^-{m^;g4g{C`+lD{-(b9yL-gSFJ9M4pdimqV^43A~E6eOlEe{&! z%(vRVeT?Q;#?|sHo@boXj(PAkpGFSGsXXou0_gKblYDr_Qg_ACYJLmHiR>SNCVOGxOtayvT38{&wa6-sk<|1BZ{; z?Z2;I`9Inve(vuV-OsTvto{{=Q^non4%Lr5%DlgF{g}8uc`Flc{tkLW$tf2SU)_R<@h|%b#V~6&-=*>c#d_@c72|>VEq-l zZ`x7*JO0o9j1%S$^sl}{?B)AG_RsK2`m?+Va$(ny_*WS}kWUQhZ_h8=8=k7N_bC^A zo%M_(dx*{_@_zQuB0NX@hH-xQwc-EZp_%_z{;zV^ix0>>@nYme4(0T{2=m=C=e?XC zBNy_=0}&sKx5`Nw{c5kyal%_t@Bcm`$LQts)AY!AJwMoUV*1mM@Kf`XSCq$jt>1cP z9Nfn^sqZ_}IiHEXns?zf?!1=I`Hy~$C&Xv;wc|@=^;(?SsK2RK;@9>4UvXd59`)yU zve;dHT=Ri=Q^!x7NI&|e`h$nF%s!X?;8kd$GTR zzxkIp|Dm3CE&t^0`R|`R3iAR!1@yci@rwB&zlh!3M`J(Q#ecUw@o)QM{PLbB#>=@r zU@zq~j-WsFj~@Bo1lnPr?)S&U9eJlg&r$I^hQt;A&&2&v{s;~P(Wbo&?w=lR&@!}D?eh;fDHgCp;$KgNT;xK6%Pnelqg zl6j0i!QnMM2k3ip_6g1dcsu+cp74J@&Ut?KkmrBC{Vv_VfBln(wc$BK&rQL1BIoeq z%4?k8=l|qShX3=N41UeI8Tks&eewHW`n3qpVwvv?0F?E7{8C_`sjMBzdOIL@y~g|d0PF_`6V~+O=;it5}JYN6*3vZ0QfArvG!G8Bo9vC}tUew>sOE221 z{)Pu+UG#fk8iHrq2tU;SfjC~j2Zo=K_avUdw+%Y~Sx4jh7zgFB`u7mMxDH=`KTdu~ zo(ucQpJp%O1a=C!5BT!t2y~ zKkEef1ZCQ{{(pTd|8gOE;=24F{bG0I51Aj>EhHXN2F*8|hm2?6*ZtLp)q^}=JGEx-{3gQua!Ib<3B2LmS zA^Rcy$^AIx-LC!OCnw*D+_o#CAIkjxf$g33*Zh&Z%=^xBJv)yjk1J0rj|<6D+}GVB z@^C#gpQG%0UHLtX|KR_S%_q)v9yzTSmDBZ*b(8nX<&DZQ{F8F;@7j=S_`&PATn{_< zaEIn0tjFXdtjE0Po3i8H{2qFsUB=)0XV-In_qcVP=Q`iE`2_2gYj_0Zj+cn12+@af zyrS`f`tsuU>{R_7o_bRbFMMXkry8E zOXz;_zP(e==+SZJ&-r6~`g#8zzt4@mM}LmXd2;2A@7u%P?cYQ6nE!9w{!hJm_Uzwx z+3Wh5_3b0VyKUc;b>g zA#$jH%gC#}!1nvJ7mrn563=xaesap4-qbsKW%{PG zjK_FK{A2u`53J01sSnG`$VaaJ@+uE^h`cL;A}+!8;(mBa5IW%WM%S7qXoa$-;9GagYt^LXa9 z^M*3^9jspc!LNMtY}fL%>wT8vWlud}|7q8CZtg#ym*2#H;J@@E-^cUp|G?q(JohzxpY3lRknhI1E~;Pmhr{~~|EFDsmo%6T53C*IoBbeHe;(!2iML z%KxD^u2c5D&Oesd!qZ`I_&@%)mVHJj|2I4!^B+DC{P)NI(tdvMY5Y&|HxC{G{O*Z< z&w9uIb^ee4MIb)OW61;RuYRWpFF`q;FN8nwzTy4wZ@#1amxunpd!B0wiL;$Yn)6A! zAO2r}`NZ!4THo)<^?wq>M-Z3%KG*TVGx_~)_3?FK_4+mQ8s35a;OFR%IJVJwYuw;> z)bJPn?*x5=?EC4L-;;#zf;WO6L@)AQ@_g}s^jE*e>CFeqhwk5N!;Z+q|1zr&c|iCS z{*MG+mj5IE=Am!<1(8GE4*t)$PCeuF+~J9gd%pKH-gzH(pp0FV+w-6De#{Sk|1ZQZ zvzy;Fs~_SPdf+^%Jfi&G3kPIP`Oel{L3#7^05BkfIDzKFOU{|Ca`v91s5hw^$qebl3O_&@!c zdiXKg0e#MP7#C&6@ALA2^@DwQF5Yi&_&(M{c{=s%I(g;aPQH!#&T}E-rVR2t?S&A!q5Jm=WH@($haw||@Q7iWoctdq3IcO78+{k?z1PWs!%SN@Orh#VUk zCw{um)7jpPC;y;-`f+?$K32PCNA$xu!YdD0J!rdUfB6~h+5i5YSb5*$|6DitJu~(% z@hh8eaU9Bb9Y^P6ZrnT&_nA+`bBFRy#KRvp zKYsR@2l|uf|FN;(XmonU0!tlo*?b= z9CD!NFh2+N%e@YGAMu!Zv2otZ8Gng?#%=fY$cg`O9wQ!*{DSj8%{%Qaua!KY<5S-B zLA`dM-gSP^cr^T)W&N*tpI?dcf4rw>{=1LHzlH}q<3ar2;P~yx;rv(r&u`-hukTOr zJJ;1gp3fhL@7sFPUd63Y`*0t2qW}CPOphV`pij~7<4!*C%KyRlnKuqH|Iw#BhI~@< zy>-fbll*MwmGnD#hTk{hC-4|kuY8tSr?oqFV*b}2=RNpNw)1MniEID8f0+Eoc398l z$Bb(ecgBD6r|oC>BW2GIZ5}n=EoA>hTmq3hWS@p!+;@Hd)$iWQzkAc?@1An~^ieMl z$9|4}K=d@o`ei%hk={2bj|l(k`9JL}Kh3&CJlr_?NH6w_{^@_>g#I_@_c|YF9CO|i z2RavLoO-p7_fLKHl=nj(#`~|2eLuf{_pc8gh2O_hPV=!H-<9v0*PVQ$`+0f5e|yB^ z?;dgZ|9$>G;$J?Hdg2*;331PJUGZ}GBXQmF$w&Hrqw%2!;)nbn{%JgvCmMZKrhWXL z`-rF3*B|)<>x22e=d$7b_?^J-AMth0XM3OL`c6KR^Ov6I{*TXb@%FZ1LZLoXX9o4G0$b4*I#G7*IvW_@gVxz2+u|NW8RPc zT<1>Y+!+1BAA#~m@^ty&-*9-O&N0S!!W%ITc)lyf3&L;mer!|EJ!$5B)H2<-z4u^S|w<`7KEPQN9|||KugMS6s1vpSSC}_Tu`L zpCgaqdFJnz`*Zx$|7&~f)9?Ekxy=Wr{84+2J6&%%Li%q%uv~%V59r?BPrXB72it5X8H~vBQhrNf1_p6NlX}36p+{Tg6^L*^z zI{!EG7=8C1q2E&)+~dl>X@C1?eimN&y|aAo-yFC6Aor!8`+kcbeK-8xxj*i6|L?vF zUXgeg4>|s&UC;T{d8^LTFy6cSrrvXn!(TRzEhqkTU&hXj`y;)g-|PIQjNSF$&Y$hP z-#B^Bhkf0=r2PTy)Luxx&cAykPvCla1M9!{zoPTXyo5Z4`{H@blPG%~RPW{i^81i^f&YZ$FO_|6$2;YwUHCuxV>}zTJR`4iIBv(;?=3l=t{X?;G2jJ6^k_U{ z|AU{wt9dTaxI_QWC!dF};(6-f{gkixU)i`jyjpqM)o*d68;tuj-x6uC63yA(U(x2-jdUagd>y_smJt=o( z^aKCbIX%9Yg1@=)Z^QFx@87-I|F>`U|Lq^k`UUm)?TJ5qD}#*hCkHYf+leoPPt-oi z6AvhMesg$0=L==}A55>t`@1|bzRvL%N4Ea)&o7trXa3igIAy#1UkQ9)W#!X;oUhD| z`iFMj{**i?60dq6;kh_?MStf>{tw;`{_o$u{``!?|MvAyAKuUJgK?gY-~S5b_vHJC zql{ypca9GXN}?KYIJULC|;#uhw_T{vIR$Pr>gpavtuxr`(p|>EzLd&w#gxNBhIubHq7# zmK`_I6ZM>PWgg)l;qZU>4g6&&pJMx)|C8r1KD*vwN6Yem@IRJMKGgQnJG@}+gbzhN z>W2qJ4$l3B#5>x| z^c4T+{GD^U+Hs#-&Hu1xejAUCUuzG?pP!4!N4+@h(EmKQpC{j-Y`#l=rvHTI&*jly z;?K&PL-bes*s*q)@AN}H;W&2QuinuMe!#pW|5dJ$hwJ3gAaZZ49(lb_H116MUoQ7t zxaGX&JIEssz-zlqq%8Wza%yo(T_Iky7?Df0zd-mt`_%8ct|3SWE zzwwPHuY|l_Z$CSz9P)kfd#pga{(+VFACvneOH`P%0HkZ1D&==F{dL@!fsp1a%U zIpw@!JVg4CAE7J)GazFX0==I9(w>lRTuVFsReD%IT^}Np?oc+%} zMtl4G$x|_Zs2{A~Eobtozve6Xao@)^pYPE45^r~YpM)M}e`7zaN9b`Q_t}ofb;_aF z)hF?g{Zjp^*WN$GBZViQq+QPOZoM%+^)=}FD=*6RT_#@n{MfDXwjc4w^68I^&v_~0 zf0R$uzMh-le4YC$+l%*Xoa0~H-x#;+jJyGH>b2Z{jkx~$J@D2G@>Sk)pdZT4qvW(b z<~{8W-{*Drg`4-l?#Vani0hy03+Gd^`?kl`zO>_gVB`_^x#zCf{1`l+FW8Uzw&*s{!pG3p7|B>dEZ9Ip`M)w z$f=&Dj6SJ%UpqYEzK^`xviUA@)9yz4kH?&SPWcIlJe-^KzR*0F{TB77o<{HUp22aR z^F2G~2l-p&_t5)JJ*hAIwWvQi~OJdik)8hz;k}sj`8u;PU@e2u|xJE-uM3d z)xKl@_OZro&)3l3#Bt<=?~^YYJnONK{9owx_xV5eC-{ToYX1ExnEqKec+T>mc0-Pj z`9Ji-^Z7UJphvNBIDU8p^byK;vcAc0>6hw{=hGMGFvy44hhcAdw{IUHoKH_fNg!vphUseBVa&!8t=d(^TzA`ej)3r zJlveGjOSCX;RVk!c@F&C*1LAlFSzde2cJ86KJ2MIuIEd~Zu*t^4)z^C+kS%F@JjG` z{%*T*#(3uYS-YZT{g@A&OWV92=eC#+UqASzLDm8IKieVh#P@}KFKK-DJ4OCyg!}pb59&Gp2j202 z&PUIo`MY$(^YMF(tt-e0pZCgVsIRHlew0~{M0h^Rpn96J{=x5c#s_l#kMErQelni% zmDj*d@O1FB=$Zb|yZp(l?~R-P17^I#8!it&N__x`faiG8;$AL_YH{LcSl0GZF!gUEH_J|FlH`J_MT?^&=PX2FrzkB{qo)JHDJ`%^6e?GfHUvIp? z&+qT6omaf(H{^lFC$T)a{L-?&*T;RtN$oP{;CB90d%V|nJj3tx-0pA7gC2NJyP2QT zKjq2SFoxLti|H+&W|`A%bhQA-)lQw zk0;yvV&sblQy*73Xh%K32YCPH36Ou6(eLmE-mf0w8-~YJFO}>6Y8Uw-`nk)q%Zs{R zSycb`&)HtT7q=08$paF1lKVv3SN^Hr{xo(y$MsP?a-Q;Ap8Qb1*=6p3zwG#(=kgWU z({kraj0?PXr5-(i%meQ$z8G(am%Bg4WBKGk@S|O?obY(Im)!Hb^Ok!0<@u2KfS)q| zk>5CQ-EaCG63-de`wq$TUGPV{OBQlgpObPw4e0;;?|76 zb~d7i-7a>c+_^OOCG>ml6Db=H#&55F+kNBi`kvqiysdr!7`4;)}<_mF7`xWm_pT)yT0q7cGI5Zm+(c|Q-3S&jvt)<_VIdo`VDry@_#%2=#S=C!?PgQ@POQJzK&k< zyKvj*YA43C?dJHjXU}bYr>C92)6c|fw)rx@(hUJ^Je$oJoWhfSA*{7e)DDz>wo%oU1WUlfui!o1NOae_-a3SKKKH8 zz%c#~dlKJ~gLPAR_}wkf$@(2GaoF>-jFW6VW9GGS0J-RAkp4N3Jh;C%^xPkOK))~6`99Bmz0Y?xe&*-=ewFbP9>RSu z&+~oo@PFu^eU$BY?$6&7(W8hqHr_Zjei%yaZ7U;D}fVmF=-wJZ0{ z|Gs$rJpal4+KqF6+EYJ}AAGfseudrP1JQTq$9&I;KM^-hl(*#l1pKDw0pkhb2a%)y zfgS$OeEuwVUr7HvFAu3ay9~c!`P?tGF0;<;b-D9xBKl&agk%+4FLFY#JC_+F8`mNM%w_p^`H?qhGuJ6@qz?-yOCCV%7l&WFx2ew<%} z&a3mBz~;ZXPMLXzo}6zV@j9;4tXt$0-oLTyA?=>${jTNf{;x9k+5VgpavrlErv1)` zxWDB&u8UsxzUtdIpZm@F16ilhulzvg*oG%mPs;V4e5V|?hh47wlFIZ~KJ-KIz2~Zj zC!rnlKmATS&wlF8&OE>EiT_Z(^P_zq^53;rJ?&~Yk^0KEbL)XdnQ?vghp8in&4}UZ6e9ZST zKH^GT=PX6qR}UcT1NEW%*~;$2=KC<^-12Ep?H&L8dcE=8A-rkrGN0j1 zuKiB^DWBt$-^AXO@ki^OpV*h@{eB=s?!Dem-oUyGFL0u90Y5+2*UGkgf4w}zb-H{n zyyjPx$s^J0>+b>0`*ij0eLROAX%{3v+Hs8eq@Igg;lwZWb{DVpv+mpPI~ce9#Y3HW zA^Ms89(l>TL-lpdU*0eCTzOY{*&f#(-^7pNK=EeQ59dkwjr!=h;&AbXb=md@)qm%z zLFUomymys1;eOinIpX8^BYL-e_&w{l-t}Xj=RV}Lz42qusrb7;lUJU3Bjf4&p}rgK z{MaD!a<0sNAm(U-yx;$L@C@HS<}3UW|3`s8 zVvj+2yzz78%ztU$@2KQYPM(kcoG&NRzT?TyofoZ_#jTUaM=s)5>$>PU6!^^krxRYn z^?~y~I11+h2R#ocZzq4p{zSg6ymj|Oyfbcg?(aNbgdD^3sR#MMIrqo^AM>5;+~+vR zH;Cth@G<-jT0EffmpFFvoIL*;rzf5iU*H%0zXr~osc(PB?~cEb-{PE}d<=fYc`V)| zi0=QHSLg*qe*BRCC1#%Se-_kp4p98dC&mNv9Wrt3)8l_-nZJMb)!#kwN6-J6pxpn? z$_I8XO?er2=L_L8lIM!@6U-BTUoBLR$YuP*f0dteo4`#BuF4<@PpQ5~R<_-P0p8$Ps-p4tfe@$@07_;nIFvK!TfOJd47ZV!nzeQ?)UU) zA7>oSyFuICyr2Cu&-tAa^z3_F>{#A-@_?=Dw2!|t4(E}G9VmzB%j=uJqu-DC9P>8T zFZNfhrziS6^4#sWhi9Apx9#=Z=GV;Yl)L?}d>;9o^SXUOJl|Y*e0#sl`1U!$bG*o# z+#&j?UfvU)47o;L<-4BKNuG0GGIp9gh;dZ^!%+RdKBrvff#z53r^Ao!tAAim{3LXI zC+~uvso%}Rs88*3j+=gWJ!R+f>}#EGL&*O3D|i+le`y=DBg>%?LF&G>xB|0xga1mnJ<@!xf)_Ym`5 zqITzeVf}>ZE%`Sx4$3p0#ua`%zQ!4Hj)DF{{LuE}FHYR^MStA!OTFpG^FATIkN5ce zPp|Wt`Re^)^T>Htyt(>gzptph;{VuZ`u=qz?azJcvF~u@0eQ}TiEG~P{5yF-?(=&q ztC%@=8u|MOyqWeST7{1py(D;Z8>Rmlg zJU~CJW9n(vVaGA$$wROw>!|zPS%{_p${zcqhif21F~ zA0uB^Zr{U`_p5iGk2fT)?(sFRh$qxj-f=1Y+@X3t=gZz#s@K=^e)L2BsT^~D0eQ*4 zH;x{9&wb5n(o=cc`97FDL^;CiIx*{ee&c+IH;ylscfkJolX<@SN^jV0^MCp$>xbXV zR^EP#zA2yUiFRq7pxxO=#GfDs`+~6pe(pH;^Yp*JSG)SD<7y|!22;jzs&#fJa!7> z|3vvX;(2@^{2g)i%KsVfSO=UB=z;mMY$hw`q zuej|$JmBtE`Rot5`Q0}71I}apk2n4g`OkAjD3zzn`YI{3hWt^1pyDO3} zP(Qq(JSaRP`_%ca*mZ_;h~GT=Qm@gnrmR6A#$G8XtK7GJFzzR&jae z%NZYLz5Dv%&G2mUfXq+%H|*(mxbSVxTM@p^`#|{`)%fm4b_`OB_8Gh68VL$mY zdAL73{#p;1%Fd_OY3HBoPV3J`^=}^2xjM0VDKdZH1NBSKgUO#e?^(Ctom{`l zlm3^t_4yu&L#*f6+4b!Ddw|0SnkUHH6L;)K)c)w9yi=6-^SuP)JbA!)KkeXk*Jb#$ zi9?NFJ<~7i-5w`A9c6IZF%DYx9Ocd@cRhNf%zn^$b>_*FPxRi9eSrB^NdN7BL)zPN zVpq%MvnOf~#upzef6I8WkEkC|rXTHA9>)FZYf!y$ALAHQe)AjTbiGjz`@OCAp_k2v zG9M`8_aWnT9(1l|-ZRbmsC-j)T&|PD8+LuKcddWu!TR&O9eE`6A$i)A8AtE;%kSg; zW}oal?|ZuY^F%w(_x|$!*Zf0$oP1UJlD}JQK4U)B`_uBLc!Ae_O6}VJ?BB4{&X>Cm zP9CP5_z(5)HM8$Cud~d3>TOW{*8df;8~toV9?Il%+)uw7t7m@NUZ_7|?>!FMoAKzM z$?y8ux!u`U;nzHOhseAA{w%8xt|K>yym#&F_O%0XM1P;M{(iO7F4I5dE7Ja#?^7R+ z=lXqbJe+urQ~eO1=*KuU=NybP{;oKAKl?+F^@x3x_h0$LIghS9r=G9+x{kMU_a$#- z=Am}@7~5ZBKlB$8xAddp)`|3&e;bcJjyLoppFdcfay}Gy&iT!A^)r5r{o%dPZ+zIN zH@^_Se(VgmP6p}s8z6biH_v%H-x=<6fVM||M7#2lzE7Y($C&16ELs(^k{$j zp&mK7kM&T*k2ddDedze~3wc8Hpno^s>-aYh=)O??gg9-x=6~^>r=DNqcJVF0=zZO+ z|Hw!D0h{;u5B`2d{AK2Yah>(G_iLv@qX-+)Y~BK z^gQTwka)!VO6M*0&NIu!QT(vD8zO)8`s;PR7`N$<`-tZ!#`}e*yq(Vo8+Umw?HXs$ zm*X%`l;rBpyvCI6PkWs4 zoVa$@j~|Zx((CKGf_=R2>SyN1Tt|O{<&7faH$Uum0do~-7@1Q zzIpx*R8J><_o#Q=SCser{*C_&fBMxwy^ZUi9{D(NBmC#bzMcQW_~(Zo@}2BIzuD3L z@6P|}cfWn|cYpriC3&9sB%deWfxhMYSU=!<2N~zQUz@lvexJYNw=<6%ulybH0y)Uv zk$lr`ggvbyHrD>y_p8`W?c)FYVkM{FCE(Mfz_a?(f!<$GL6}GLO&v2Rp>`oydKT z)BN9ji2FD1XWr!aPmhrN&^B<{i&IS%cQ|2XdaA{_tFKJtF|+S9M^c|FE;cO8GE zKCB%Odr;5lLD?W_;T<^1u!DPQa7`nf;keLn3CpOyU^=f}L*mN)$v2aR9Y*|;`n z9PIZcCO+)v(3fTTKm1tzoml_euU>ZEKJyPblFxRsQ}rJqexW{y$2=ci;}&|?&+^Cd zZ~Zr(toX6tH`q^n-$us2pTEu@#-D$mdVm)rPNO$@KF9y*Z5-b$WS@i{$b;O+Q6_() zY`!!6o%4?}`uOH;K5qUG{ZnRK@`S9EwPW4|4@e%SJSX3WKlA-u=>C}X7Jg9w*ynBR zk37Ngg4lWNryo^jT%8LEIltm~)#t=>%khfwjHkbKZXZ<7@hHx7{B`>|e4yoBk9_27 z?tA4unormKX80`IsoxXh!TNpl!Olg9<>!NEJMm(yzl;xm5AnN+GiO}7i(}}S_tDs& zxQ2e2S0U}u&xxL2l#k)M-w&}*Vf^eX)C1>5=DRTRGvW~PgS6}YCr-V57xR1D5&v<1 z=?Bb1<+Gma`H8sSGnp^7-g3RTb)xsdqZps{Q|Be~xU$cy|KjyM(mwZPzi`{ncJVXj zm;T6mJ^b(UQ(v4bQGYyl%~yx_LN3m={fEb0zj&Z=MI;}Ery>8;zx&QKelXPUiT~s>$o-t-8pMCxZ-mSP{Dku`=*9Cq+}FJGJfnH9afkDJ#JkY< zT;1n7sD6xNC*KDTh@74G10C=GAN~*CEI#m`-}F7`_-PkC*#4X^9G+G_&Hoe09%Bdf z>U$RAa_hyOCo?ZtA7{Sr^>X+=?bQ6(=>7ix2ES9r_rvfPoNuFFm|RxC$BLW{}&oh;rp1UAod?LUe9&U)sR;ZPhH3N?>p${dwj%c^g}#1emZ}M$}H1`Q77xeZPOiW%-1^ea;)cw{;%<_b2|@SO4t||LcK2dhl<|#~(lMm$zZw$^SWi z%f@r`LmUd_9~>9`^S>YT3y-ESo{};=9r2F;L4j}o{NPJN+#Gx=b?Hl?-H4Z)|02u{%*%I_MjepmEVA_-_D+}XnCHjt>V^GGwzRK^?%xlz_a!tPI{q~Q(XcxWMe)$0LP(6XXKL$HjiT=Fb`;w1+0qs*Z zkMcS4FY3d1N>F=f7wkzHdu_x&v=jDnTvJBA>=@tI?}3Qe86GgCJ<7Gqx=y>~Kk|Ur zJjeZe`|q7kO|==_yeKu^rmuzdsl5og%%IsR83}gG#vk1;A&+(|evtR7*Fo*>e2>?N2 zz4^S@c&6U=o0p9ry*h6FcINNZk0+iwe&X6*Z+s7c9~9rb@A{l&?o&TtdUoF2*N;9O z=V{M9-*&&+!Fjjq8K-4&+l%(oPyPX72XOlvcEVrtTab8hMda(deR;C(lP5%;;*RYN zzi)ptfAs$|eq^^0o=&^Uw~;AN8GWQb&&locfwWKAe&FpaJ1^z+*#B|9Nxl%fo!<+? z^SM8IMdgss+q|Fa?&s&aNc*ghBKo9kKdzhD&3*Xz&wGBPU)e8yt=xmQpImdF?NM$X zHLvmyc@zA_ydWeWa6BS@Lph`!uTMUp-|Oe*5B^RF_1FA^^-;M*u2T-nOUYjxkNI(Y zpZ~+i{nqzfc((66x4)C`n>f|F=5^#}zMv2NXZSwK)q~tuelUpKzCU(c?d#6>#f%gC z_g)tH^^pVaCzq|Yqf8aeQ{qZ|y%HKNjr|^G_r#RufrTn`7+n+oN>nDDhe{N(R zFki#*$NW+>&T*gL#bDpPPvAMmC-1`ifiGj<$@wAYk?R!SbE?PQ=Zv2=|GW z)bH8xzq7Xg%KteI=eP5iIHEkD@yYp6J?n(}krzZxc^>0{`y%oy_FMQ7rT?Udc)fndFXY^x@yWcK?|bQYzVjXak8xaizn?tL>B(olBKvf{|7Bd< zr(WaxuGsbA|KyFn%>UVccI5mL?}g-PvxD!MkiYneU!UKt>t`SFf7s{a^DxAZc#h^} z{;izD_vII&@)BRw(;#x{$IKV)rT@d9&3wpjLjA}1hhM=L7@xpDJb19rPhJ7OkMmXW zhCWXmF-{ss(HH!Y`T-v|JlYB22{}i0BIo<`YY;wR_&wVvuVDW_sQy^DiHok^#@jQ# zJH9hc#`}Yg!}D$M0=5fZ4gbhK5nhew`R>3)UYzrX8;N7X`{_@{MR+Lvbfe$*dM=T9b@G46 z4IjAiJg3F)`(gLqqm*})hv0ua?>g;w%h(M+1m%nFk#^;S)TcZt@}MtxM-e@7pYwCh z|DmUNzxUDKKjwMot9c9ZQMTUxy-q*KAFoIL72l_Q&?Dbx!@I)&TjoCF1LNRaFY?0^ zq95YI)=Txcs5S`_54ly>yHt; zu~c4 z9_10^4W|B-_x1VndgHp@NBJr*_Tzr@5%x*WU+p^krS1cn7qk=RC!zV3{=vAeaxgCZ z@QRGvxOgJ>Q6Ii{U;e()_Rjdz{0@=Z_S;{$?_?avk6*Kn`JU&BGfwa8{#UF$`qSQF zykCANAH+DeUoigkX+Glqkak;l#H~N)$<{aauuQ&vy8DEQfy z+p_+l+|zDl$A9{Feh2EO!#C&0AmiNpAN|Ga^?RL_z3=4z7;o)_ck?2D$NtW*(|+-P zB6$n^A9)hIAbL)Jcl@8{2bq^-?(EZeuJe4#wZ9W)+`G&^i|0c2VRPP2dG~ogpLgEK z^Tqdx%5NV2&12rU{^(EaOL_j}bI-E-Q^q|!%Ki7p@R-}bXea;Qe!)DZj6cx-b-j!K zYo24TouA<+J5Jyy#)Ei4*j!KV@G4A2?Y3`|+{( zmOqO2iyl26Ks)$f==jv{#Buf5`L^<9-v26xJdt@JywsHCT`X@NFh0iTna7Mzl=mZU zz!$(j4sze{Pw(@8=!JN1KZA@fJ&Sky3iQLiUO$}mL;pDQ0qivTQGeyZ;_L7Io%|o) z@u~;;x^Lfjy*pGN@_FAq?qlEh{o}l!d?4TbqJMcn+NJ#G59B$%|8<}FG5@!DT;w7S ztM^cS#`}>M#KSob`M~nxYySCBS-+fl!n`Bi^gBb$H{)*xIkK(WXRGR8KQtcu-iSCzT;n=^AD;Vb{Re$84(304kpKJn z1BuUn_s|RT?{A;@qX*B2e!l+d|9Ik$ALjrmhy3oI_V`cFdiW*y#lEkF&%=(C>5ur& zyyASW$aTsf`()13v5%97g73pF{4WXP`t&?k7up{6o%dzlXHUinuf+L0+x5Fy`r$st zjh%k;m|v``?z=Z~-!C8awDXq_WPbeBfm|m(a@~0Gs|&i`F+Stc@Ncfm_>=Qy&hd4g z@AR+X{p1OmFYHg5+1<6D0xkBFX;cjNS99Kv7FtK%f!P%l$I*V7OA0P~W3 zi1y;s!sOkU-t0%ca=&peJ)g*R?nj@>#dZB*Q2q&d<^3wVzfeBT>m#Q~eoh(tf{dr% z`2gv6;~q!%@9|GNwM#$hO(YLQ?vwZP{U-fS-pG6@?__^qoR#-`&HLL|ls}8@Yd5kF zro8vxjJy4D`(@X?b03b~sV9H%{Eg@REK}dPvv|bU?`r9Xys!QCiSa05`)l$f^cdeV ze2Q_VdiRsax$CFgK6HPNWV^`0IFzUT$2H%&wma?F-*PLU@Uh4Hc zFTuEXJ$_F+A$F&ne^@pyA$R+8?ArM7!}eF$qq6h&HNU5R`}LI7du7_$e1rAwuZ;K3 zW9pF$WPVtdA1B@`XXw0OeAYKlKEm<=+vhp@0h@Q?+*kYP#eO;uxA{`Xo4y?Hxu3%S z7|-CT&-6$?-Z#j)tv#-|^_sn!C#RgR`k#12fB4gT=(ybPai8PUZy1mBm$-y{oj=uI zxsD%Sk#^2Fb3ISoclz;tgWK1e4qX5C!gNt3A~?jnO}N8@@dyQ-cY%?AKni? z6WQP4-<7wYojjuPf`0dWa313)@I}hizS1)BNV&`h@CWmTouBBJyB>Q_p1}2|^Hbxb*UxpmxHR+7xJ!NO zl5uzRs(kv7@z6M_U$Rev?9Grr|NqVa0-V8%22nC;t+{UXoAP4%?- zzuHqS@Vedhq(2em$eT;Kd3`%rkmPmd_Xd}RD!_ff`w+&_7pb<%#k zZ^n7mx8*&5u#0(W^GH3ZuaP&s^PRNwlHbWgPx!?k_T${2@`mi67^k@TKkt_h{QSt< zuVtSb{!iX79`Fvyd*CPV7yBE;ABcm4r<~RkPnDx{fazaei}eG(Ve^2rLw>B?=Nz1V z9=|v1ne$=lnrTLvBfoI~yVzs4tzMErnHiua2L^jsw8kK}9m9YlXmkaK*t3$DqkoB8&fc2XGm?!7|Yfy$)3wdC8F8%8--gsotcK+#)NZkJW$Mb_kL*>A4k&FE&{NG%sAItE1zj^!);ZGmDBYettZ|%ZoS^k>` zvQEphaX-pgDi}q4B}-Adlb4YX|kydJV?=h1v%{rJcd*yU%qGeZ~K=PSJk*O3-=c z`b2(3IV2CW{rEkReIWk$9^z-rN6(enKRh_`Q$HRaYIr5b&-GXSNxqLf&*!I%eCYK( zw0-!?^h5iNyZpKMPr1AW{aWvMMn3d|9O0|H*d>2e-^f?~KkZKY-oNe1xU>iT@9UgD zqrGsqr~cyoSl4MM`=NK%CF3%DCh-P4Z~l+_DPIvere1vz$H*^<`<(Z)J@OXx$nO-> zKIK93M&u_C!XML1-$&t>m5WlaU{@r&N&y?Hs9eq%~BI9TM_B@CBARlHv zaKHRJ^6WgJ`vzc97T(%<%a(>!OKj>CN&`wR1E^yNInD~IOsVW_jm3G{9YK(aUO!+PdOeiUNF9ob-;1=y94L% zqRn`&{NH*0Pacna+TZVJXd^|_0Id+7bj0OF6{Ft=%sx_c;x|op8SO8 zSx1N`tSeJiUi@m$6UzBxm|oLUw?4x35the>@QUhl=b^}HxqL1?zT%lj zXYVUw|C9Igy$SZS-u2hA`f5KGsz1j+eq!9Bed8qGlj^sF`Lp?%`a0Jwo+qyyUXHSU zUcK!zUhXSD#vhIEgUDZd+}HiIhrUC{sXWaG{r&W7{fU0%FYV9gT;PyIOl*=Hz6 z`VQm$LeKrh1H$_`PWhEjkFxO>Bwo*T_WPU@ydr!N=L6-#PX6!vN4}n1w5PoXH(zOg z<9Fy0dnlj!Azs?v=!>#^H~)VtPdI!;{?B?to??Dz9=GSq#2fdQ*oEukU-qLs`7wSf z--%z&cS`u7?TmelZ`j3sw0@MG#O?3;2let6@f4j4lmDY1&h2sE>2JmB(00%p?Twy% zzOwvj=L7p*TI4zSJb3GVN3gQ{mHqu9egw}b;@5mPi=6UY@;twJJ0}&t1%JhRBhHz^ zvkX3pkN$uCjQb+z{nRhKA9DTQ59Gf8>)FrOU&;Ud=*iQuYQxX5-v8Af(f#D+`M8hs zb7TX5{oHSI9u7aYJ|t>*F7TU&ob>DX200Jt`T+ljKf&L||Hb>MAN)!?t6$_qe_{IR z9H8?Q{*U`W+W+eZ;$QN9mhn6JKgx`k-$4{l9#H;I{UDFLqr$o$(Gni{Ht_ zzg)kG3zS30#XR%9$3u|E_=uPCX;(}yp>m`T^m_7El;v**dH-gA*bn{gGUKC+p1E#$ z`aw?m6P1tomb`pto85?8XIVd{-uoLz=)B|nFu#Y0U(nALujABij7$Cnzu>!k$JhJD z@(=kN;u!a{esVwOv*&sA!v8iYKmLRql)Ya&J5Pw`_!)5zKQEtbpW1n|cp{N}$>-#e z$j2;?e8UG}$M^Ul>W!nWOZ)%nky{>${Koby<0sA!cys+^BYdFu%Lfu?kZ&W`$pb# zzs!ASSv|@3A;*>1kY_k~Km75B*3&-i*3T8y*GK#xdOP<|?Dx?hhkysz){{vJBc{QsOU^*cCr+;ZN@O}mXdJ%IQV_3rEA13llsK8O6Ab(#0| zl*5zf>pjH$e^9@h=l$?!`bCKUBWLe5kc0TCJj%g1)kk_DKIoSq8S}<_{tvnRo{RH= zjFbDEf1CfaJ?i1#l+Sa0_=n|*zm$>B`pz#-{8ZoU;~A%T@_NeQ`(^k)@pW2ABsNb_~^Iu&x}hs z)Dz|OY2MWMuV@~dKEm{be$1Q1@;UOxtzUkBM?Dv($4hg(uP9^Z zLF8y&G;i`lkapsgn(yd`af)BRq5R*KUs9gYujTarittJNABgCF@0*AJ^4vXs%>UKj zd#Ik0L%ZVl*;~JwvhAoB^G5t_m*udCojQUigpU|KKOkODG>P z{9oq)t!H0CzvK(>C7uTyKJb)js{f8(1=&S$piJbp)p9t^8yaxH+6#fey@>kD#ctGMc=g!=3g7SOf zuO9p(>*8NNzjKE_kNH+&!b={H~f-CO-(&gRQeybY5`&%=}=-MdG3U#rWaL2C)n0AUCp(>IcM;&F3*5 ztsJUX{DJdu_^W&j*Uvn}GVzB0YchV}7x0Go5&JiO$ARZJ5{J+i?`xcA!~ao+XW3XD zbj9){_!rypIr2F4&$^DkBIo<4Um-8=iCw1#d5*kyBl@$wSA4ZQ&%g41$eUkjkMvJH z{i{Fx5G(x>D4xIP|7uUW*xu-EmunY&?)p19^uPDc2gs|j56v$473<&l zS^B^8vv|>aj5iJ0U(%0AyY!1c;}@09e=IXTJ}LHqW5H zO@Ec$FObiW7tVFtnfJcVqbcjR+VT9ZHT#CxMR~;6@r|60FTV<}on{1D@${yN@knfA8cnHOjIn-}E2k#GcOQ+0Tt0Sx@3eve(F`o#6HC4}=%I zkak{+7^SiD;T*uGYFKu)j*7LmksoDRkpQ*p@cd^%A zZ`)4~p8S?^WbDH8+6Vb2E@)?YB-YjB0?|*rDu}%tSG*tgf$y6#{0Q+(UU05!C*t3I zoMRtv`}e4R^oMOn>+k)|yx@F~$NkjDBdF)TtCI)pyzzd&>Au|gLVfc?be-DyXm-ht z-#nr}aSc5ZH`KHGWIo#taRGm0oa~zhx$gdq^%5RRe%$|AnRaTI`C43u*C0;yy_M%g z_I{N9xjv}BxjqoDypEpbC*a-SDMZd;?cWFFyH5Bx&IQ8DxGwiUrTj0l=V5qX$p0&V z^zZ&8eigKy{g-@S81EO#|NYY&4+u}O&jJ4WO`cyrzPIKa-mjnS{{3TrPy6DJzWVRa zvWTC+*P&1NEuNzcpCfB*!0!{gN8|MTPtK0ho5ulU_#KF~hj>xS?Me8=lL`O7Er zeXr|4=LbDc$GJcC-gmct54_Iwg&f5PUK{^mUP{3_!g zy`Z1I#|`0G)!U%+g!zF!H=grFzn3RtKB4db?d^W~-*_J9ojl)f-u&&ikN?~G=ArN5 zCzYRa=Wm%;GrzRkD^KXWoafL>c~W_k`Nf{!=3(Sz+69ycqdj@FYrb}tkrSRT)DHLu zysp3J3V&w&q5jJMv3?rgh+nV#-!(6?OnmUY@}I{4saNHLzhm6PQ!=mj_owoFn?F47 z_xZngw4?rM7kf?F`q6WKCGPw9US;~TAMHZ^T$%RIJeqaE{19|~Kn~W4X%9Il_k8WS ze)zol*B-4a=XJ+%@{r_z&gb5Dmq!m~->aP4-_CKk-qqj6c)s^g-cO!QeV`ZjYxd9i zKic=Z1NL#u`_|F?@rtakjI;BAB6=q8@OiFxpZizp&5zsPGEVXd>_ff)PisD1zRkYV z_BKz4Jg$So1G*3IT%Sn$?B8iW?EH<-bDl-H{NA?jemFlveLUXevC4OrdykD=<~i{z zlkfPP`Ih;y?Q?(6t0(m+pKuvW_zv1ZJyc|7XkJtUl?0=NwEGv(8v_Hm^y-vLQ zUYUO72~Hl9aj1{c&$O?<-<6wRA>+OJ*)De-G+($!#<{Ow%ROJcs9!dp#o+^NkM+hl zs9f$(n6K(Pp6(9SZ~ET;fL_&)?Xdr){4xLMJohR-rySc~ns=M`<2q&M)$mq~Z_We8`-QxR=e^wUf7;vgeAGLC zhyPQ*#*;Z0SNxJcoA2B6fABgVX1v44=r8hW#tZj}_yzmLkT^=&b_bcCo(uH4^7x*E z_LN7xp%vt>8d8|Kb z_q%loJuBb%U4CV|_vh2#pRV)Wb+q&KygA=i6O76PM??Jr4GZtNqx&VQ==g#0&X@SDp*IGY;-o?jPcZ>XCTU_j8{g+TlA(c@*tS{(&7jcWEBO zJeYW*{kX6E-}&Y~dCn~p^?s~psgFpN3!9Nj)K0Wyj?%VvK`JU(Q;1}ip;v?c?K+Z4q-R}GzoBCzF zB~FIK9nL#%B;Na;Z_afwK6pLGEB{1bf`0*#U;OpsKFWjK|BJ8w@$Ed;KR$kc@6(g- z`{p6Xe|tXnqp$wUf$(FrE6O|CKfDk2qQ8wld-8wq7Vv=d7ypMG-#z&>PT_K{j?=S# zXA7@qd+~$vfBY{A@jZ+e{IiE#_yv5G=Mgz)CaIGY-mU;AikQ z#>>eUMj!R(c&wLSplhla{TB0 zv|s(?k?3vmMB{hj?z`L*7Cz|1fAQ|9IJ+B;9r z&-6q0UHC2eZ+^K^|JFZu{r2PLDc8^WpdPGmKFs=y9hk3-H;f0o$Lwsp_!IWI?VXZ&K`IFH>IxsTZXMqZ*`wjGc|Kiu=a`v%9Z*xB(< zf82N7kM(^ayhZx*KE}JpkN;8LeB4=f{WZS4#s}X&SdSd|wa=eeKZAQ7Ip4AuaacK< z?^oROANjCT=suBg%m3-O+WCBMfqj+dd~dPqdv0*c{T?s4d3^5AzJ5>Fep=oSzvtW^ z`8L*#N*xX@?OgEx=#7NigsP^T)*(w_sTP0U1yrN`s3-}#GC4! z|HHreT)dy?c^}uUSx5B;^G5#9v$FnanLMMs1G`OL;yB{5uGss|d4J9L*nbbw-o9>m z=8^Ga%E-6p^^}pzb~~q6Ts!$D^fvl(Jd~NwGalblJO0h z$qUW@Lgcg^_LH>BywVQpjd9t(@9&wfx3+o)?#NWq{w5Q{CypFr)&6{e6eJ^@F`>lU4Inl?~kMrl$ z+tqKlANvr;Lgh8C#H(%I4f%*0oc|*3J6`ib%JG2hYeVM`^5CcR>wdWMl@DY;hd#QSYzzeIoc{2zP=^DKm~B0h0$&3F^f1)sEeH~0<8#7!|C zWB5Py%6m!9$#6bUKJb11k9|IQH}6qc&yg!cU-C0t;5`fdB3~#E(!QVlIpf~QbN~3L z7r%RW=ifiBe}3ruzdVrk|Mo!6clo_A$aC;{p?>j?&w2S5k9N&_2jOYp8$;r~=MMRw z5BR{JJo!du>3@Fe`_q#j{OTbO=k2(k^LMn%@ACOP$ali*n}7UhpYeZwv}@V(c-YZ( zVfM@0&e|J0a1IdO5V-rsM;pZFa|^|JXt<2d&5eNOo*&zEm~#Q%97i*Ye?pN)6JwNT+5AEQm8+W^7hg1J&d**}Woz|N# z(GF#K&%u*FtX+}$0xvb_IMFZd=}&w9IS%Jt`~IDmWXJ4^pD?e_de<-VX8p+inZM@6 zgX)tqc2S;*XUb`uVce9-BRBef41b9yj@KMsknxx|-=X^f^x?SM2b{?DGjF`hw``yM zf&SdrvX3<{iT4ZR{|0&P+_#gT&pAKabss<96??t&EW;1n?U&himdA?mDj%WtwLSL{ zj<0dzH&@=JeYAR*eEOCD8@-zEkO#vDSikua;`Dhw6~Ev<_^4ODMY+r8yY9HJJjL*N zj1#>(-uZr2yUzKN_u4_8_Eq8d5AzAViCot|@xOB(z2~>ilY71ZyG-1qpL@Q+`?Q<$ zta;Nu^ZoeX_|*HUf9%lz2xTYvh{n(S<$31o)G1Z=%Xq&*<`Mk$ApOW6 zzW4izdwx5<_Q8xN`(~%?NgTe{=RS`@931{n{m8S$uVn}03wcJoXmJ$&Z`#@4f#3H( zacR$2{IU7mJhzNIj5|N-TpmbX2G1vQA9u2E!6U5y@pJxB?>v>~YaTK#*YOkML+}%y z3um6YKDA#QJjb0KTEDLRm+L+Do4CXLX}-_8X}(hap}fea{2%dudp+O#0p{@?|7ZQ= z$Cbg6Uw>gfq3z-y*Xa=JaJY39=%d#UaAi;{x3vtj{n5?KjbLSGq3!~ zTYedq$8EG{xqRPPJaQcA$N9=S>-8N+oLA_z^?v+Cz5;z3FGf$sSNWRF zubJ0iH{VBztUr`zT~WU6_uJp|C-2t}^+%tZ^{levl7Ec%yW^`Ir+V4zz^oU09dZ8e ze1&{O9+2^<$MO>51Uw9JBJ_UsSbyr%_-?)nkK*~3%KABam;Vcg_hLUK|3bg)dp7R= zk*7TB`aEUiNlw~9&hWJ3*wy<--?TG&cf81hKWtv_TBaZQB=QFK`IbZZv#E~Xpa-;U|!5qr9Kb|KsC+cr~u`eJ}jikN#Nx zn@1V_Y~IW7e*KP^di4R{hh9MXAN~&>>X(ml$hhFwLS`vE-|&C(e$?}Od)(*m@OeH^ zzKM7TKg+(k^O;{i^-(?Yc+M>z5I&0aL*7bzPg%YUJs|JKuinaH`XHZi9QjSS{mVSX z{d)h8z;)|E{M_~Xx~>x6U3XiTKSJXn^FZD)gXq2Gh6ALa-Dw}Jlsj#Gb|a@VWZ z&U+rISMpx;3;JC+=OWGb{2yp}z{d>_d6?Irah3g0@y&5KZ-&QH50ue6zZWTv9+m69 z-1n&>{;A(~o{zkPb(8myA$pVdBA)5rpx2o<@O$_*JfPQq^2hSE9rWUQZM?_sz5m1h zuHU^!-Tr|-{hfj^9*2EUaWCBS+<9;OmDg|F8?ifO^^RT|_dP1Nabn)r?(w3p-5&mK znfC+slRm%PpMIykw%p8L?Z^7#b$LbNCgm%R-ObO-)6pmX&iQfUjl5!cCF9YrMCQ49 z@9X#G#CPX&Xg;>{MDjY?Bd-#7K9`^9XYcv5^~Dwah4I;*a*~JNwO{}5;mC!2j$^m; zy8nuQ#(y2J_nQX~uT7bG+P;yz3V$-cB9HWc-`K~RKe10IkKgBTcz(+2$?|-s*8Y9& zv)_1tjaR;peW-bE=zgDm&1>#)?;G4-InKr#nonQ#px%7$$$u9f5!XD1FD~$x9hjIL;WtB=Qn=*$MM`F^O@@*&w2mem)?z=dDXs3zrqiB z-t`J(+=Ke*mH+G9QRsZ79oxI-|B{z^==e{Rerzfqs;n~~>Z{!bndeIf_> zN9S-F@0$%xbP7Cfim+{q}`MM zL%%a$o#*CH@oUY)FdndYa>fhVJL5-rwf8q~!`4msD&vFg<98z$(w8^JTYdk`JMahd z8c_clWW4ZV=3T@i_S?3*-_LU2nFn6W95Vh)~|_IGcUET^OAY<%2S;DU3xnC2=jdNDDs?Z8F|tF#`4lHVRl2GjdxJ_&BvH0 z$j5!=RoZ#-istdeC+%`q-s=eQg>jt-&xO7wo)y<#+jBp_{pYzp%h-+j@n7^ye!w`0 zuUBLrxp}`&4>>4@#@CTY`7IN_;ZN{~AI6{IUyR>;jCkU?OXb49uI*E<9&FzmuNPJ? zpF=&cCrgaY!8gkN%ifAm>>&AGXiKIX?HJ@>cMCmIsYb z>?`$0<96*5_v9Og|KodF_KDWV57=jm>>KUZ_4MRb$sf5c|A#%{14aBx9>@Pvc=A2* zks{}E-1n*n%J4t%7a{!LU*7!m4{yl%zrS4a{o*=zC;szQAHV&>8^U{04&jYX{r&ds zIsD}>m;T|?1{v2M-|EBX@f_drf?P+x-@NgUl{xPu&nWg?w&(q@gXjM?54g{3$_KLE zc1{iZ8gJpfu8!aMFA@HP@`?MrBYNW;B>F`zc_{p2^MCpa>$&&o$M0peEB&({;ClZ% zap!@G@A41&5pkUPh27y#MEJKo?!JHC z=sE;HtG>ec>-^ZbM0|HV&6h#-O1zMFQJ?6c@2v4N;=ze~T=GHi!`LNW2>s)4@_ww3 z<|*i%dZO_fo{xAse4q7)548TXT)Xyzy=iB#>pq_y&|mppys`W?eq-Jz_I%@Lo{Pv! z{QZx&_{6zi;uNTTxzBsH!TY!xcY3%Za>9EKk`G#zFJ=9Hzx=Ab&9|xtpEo|^2b4qf zwC@w|C}UqRdm9JQb9O%8Poq!grP%i-Jf}aGkIVlNM`oQ=&hnV;zpPLAFL{OQo``=@ zj?Z-+Q$G8Xzta!$Z^kv}Ypv(+?I6$jTzvBEkGN0%w(-m#@gwSo`h)o+^5|#wv-b_! zf9_ikJ-Gj8Tqpl$9*OY4Wcs)K@p(Vw zW<3sh&UHK9;dx)b*!yktXnrKB7yJeNob@RyfA{qt^`{~SmC=%c(*|Ishc{SfwIUZXeh z(_hhf5YP7>I$wBx`#thfKI5@v?9|I2)SLazJSCrRpJZIK?0B~v+t1X)$v<~LeEM_oGyX5+`pE0}XPzp5=X~Vx z;IZ(Njn9C>)>m&-ctP|XKKFxeI|M@!qch>uOePbRt z&)>uIdHjp^L-b?Z=zXv}75XrLH2h`o|;*2nZgedgmXPhO%Q?|3Y)5O1QsSO?IT zdU=Jtk7wUQd>r(-d0u(YBXKePg4^%jyWTkU@5b#qmEYr!$isIieiuwV;|+Q^bXD1#rufP`}w^s*NH=+_N5)+@I&* z_BliQ{r0MlyzzhRhmdC@a!>}f*I?H}$63CbUkvImvpy=X_09i~f6BDWd<@yg!;4i8 z-LJ8KW`92S*IpLJhpKgfYx&g1rR?w{BX8_&^uaoO+ZM!)G< z9*^(l+0XvJZ~vdb{*UYI_YfFc8vgjWRq6?IIWB-hP9hR)WApdXUey%;3-cSGEJfD1@e!uG>H~PST7+-pY7qwpeEBv4J!r}i= z1i#m(yvDP=UoyU!ulk+d4h5?4%aW9lmFCSwj-}sK1aUdJU~CjHRI-;&-?F|cl^EF z=JMzJe6yeG^*%xz-miIy{gn@Y<^INa!1%xW{+_s@U&{X>59?q^d)zl(>u=U)y={N1 zKUhyb7r(^b+Lh;fzkm9}{(a3?{xQ$>p1!F7Z?VCqUo@{;;uP1N7 zct#ICXLw8vEQQp9c@QHB!0xtGEVyAe&{%ow>&T2!}{2H%UOBa zImhX^?f0Yc=s(p9)zdtupR}I>;a3|M_2|#}9p3qd@4l>C@8RADGcS$T@&l~jzJC&D z{x+ZQIP;?Uc-n94hxP8{%TD`fr&GV#@qO$)I;j2z-QUc9M*U4cAJ^9|=eWj>#iRU` zdX8@}zjU0nxBV+V@D=~pJmY;i`vlLwxxYk@v+r_Un|Z8%$rm=?JBN^;H$U$B9{*R~ zo$sIH@cy)Cyn{zWuOFfNA@^JCUun1V$?v1%l?SAK^*H@+y<(?l+;YC5C;Z8N{hwbl zbL5uiV_z}f{o+5b%d~Un*+1g@w9B5q$U%8ydi`6lxEjX$h444_FCRs}=JkW-AK$;_ zCFs%eiL~$a^3RaGWarq+N?ji00clfVAhpXmpCY@|Kx^`-w`UGtFs*)Q*YPu}l6dD3I3-_bArGI^bG1HGWfka;HW7h(tElt>(* zJo{SOZ{NtdHOucK|Cd2M&-<}&W`421HtyT6=kDMa>Q_07kHyQ0@A75X)BU4&Ihp0$XCS!@_)hbdcV1%!vDSyo?!EU#C7<2|f4ESd`12(P-$nlPSG1qu|0u)%!3+KKg~aXOzv(?bjqiG~59jsZT|QmoVx52= z1K|T1hsgOr`7QWH;^43T%J0Q{`8$sAiN;Ixhd=!-{2%fw4?Gm>xqL)=RUgD{{7Ph< zZ(USRt@p-vzcYuY+vP1E{tHj3ok2QAet915Gr#CZ^!n&YzLa|X@3a5QtejkzFH1hl zBWL4soLrX&M33q>?0li;RFzXd?z>;&l-G@WywAYz;koE1-lIGk|5qOF(=TPu|0%!o zNFEbE(GRkJ?+Ld(E;U_oL;I9xY~Ig!GjZa{|CQ%C|Bavc1Nj0-{#d>jAI7;+;v@6Y zICaJ+9{;$OrI#(f``^~xjR)#Ck(BcAu`{2z#a5bwg|?t5nA>f~kUf$>Z|;?wkF zUN-lu*K>?#_&($6-+zg-pz{9Z&HkMm{y*1!^|9kI`k*Z8m)%$Yp8HcyY}yj1=5{C&T+c^30e*YD^4+I-XR&gkF$x=4TS zOE)^+&iy>^<4^H^pn1mN{r;5E)9e1{_fEXud+qkimU+HBM!z}t9kUM^KEZmH8Nc~@ z`;g6}Ag8>`o$tGsYlnQ#xcOQR#xS)IQ5fP#UV(m+Ya`En zy==etc27S)`9JnU-WTB~cA0+n^YH?Fm&$ed`glP1p~|U#Sq~_O>VNE2dE14&*>j!x z^W6{BYdr1G^{dx*&hNB~a!vcJPkX;pULJPevi^zvD$h9c&nLFd7YCnyy~oe<$v68{ z<5*>RKjOsfUm0KfuCRUUAo@P}zw{zL{d(Wm@09(+z&Z2WHa-RSGT&;L0eE&>|eQl#;NwD?L+x~m40{GcK-6Ez4!S)`N8)2 z6CciaYWy)CYk&9c@xuSlFMoZluKbSOr%T@9dx!tS{+k!l59I&gJ>(7jUUl9x4X^Xf z_52?%zV7?0pZ|FwdimE2u?N=~zxY3{?{X>skL!FM_c{MZnR8`>`U(6WyxdQh+}~fk zn`P>eC;Zbwp7%W9@PPk#>0O?R?~mbgumk6~u$Rc&Mb0&e#6_;NUi!VOav2vp=jOS; z_^Gh}?SRjd*8=7F{9c;h`9sg1N96Yqk>eL{JRpc%o^yi-{_c{C=Y0=`AL4hNzd|p_ ztzU_iPlP`+-iw^u!=KQfd=S@b-*tV;`VnP*-w*lem+{^C)8Q%c5983tkDTx~+7*4n zyHSq+!*0sS_t0})-U>y@Q@%pxuRNa5neV{k8vmYU>%)8YJvDp_b`JG}{K4zWC;wNz z60(kY|A~y3I5Ow|w5xWL*JA&tAL0l2V}2^{#JWa(aN>aNp6fPoN{>kr#pYuI}=X~SAl$-H84)YB13!dkFAJ6+f)_Aq~J-_E2e_)?F_uaSJj{Thc zpU*L`X@_~vJTcA|e_!F$gBQ2HJYZ!|J-_Dv;sLXJs9mxTdW{!$KR~^S)A|!-{EWOL zjQ6{jpLq@O-tp7Uy?ykx`@{a$dyV*k_0RnP?Tmjhu6R82SnTY5_gU_Ti0h8K`l8pF z-|z8%=BL%0{$`(5K6>(h?6-*n{@$ z>)gD*mN(?S+{szRJ z=;e$bXSw?HF0h%pZ2jJe&PQ<*?;!i z`h9i2s(SjB`(N#nJ=6>J#xEwno;-f)`+R=rJQ}~OyxWa;((lfGX!ptcDfe8Td4m3! zC&dfPGvDl&{h9Sb=fC5@?~#-JF5_T7sNL7x|p|0plT0ay-Nr^Pu~6{ch(KlV3Qmo^i(O?#r>C`()?G z=Ksng#Iygq+>`fdx5iDrMt>Wb7v^!_ebEm*p#Ew;$$3ic>2>W@zP8T+YX6DD`knf~ zem-rGl>X^(#HdGnqB zLw@2V^I*=E#V4`PWgQ6n&bM=aoX;Z8ht#8g_RYk5?K1qOcA2v6KKVcDZGMaR8z0#C z={LFP5B;$par1xj!TmB|6m3#$0js7_wh&=qSuVr~t%IF`Y zzI+_KA?p+K0(&wa;8{5Th<^Ql*y1+v`MK`9u6d3Sc`VB>a-Pn7!12LX#;+0I<=>pw z+7rGv{x@{JW;~tC$4<11-MsF(!&iJ#c?fb5hiAN$<&#g|G`U3d`HJ`JI_vO0&)2vH zTZv2kh>nFdbU*?}rWL-PgZSqz9 z1AX8xjN{Dr?9c1*qUxP`*+)N_d~)P2ZfXBl@ond2=3Dsb-Cu2I{5-!ePq9965j%-iR=eZGqR*bg!fo;;EJWdHY* zb|>$&AIgmH6=RI`SU#qY%3@-@d zKlf=}54A(~8@&*Jj3e)1_B#EA`K$ljzpuQPN8joFMEgZP+tXi>+kN4_ul^^0zn7Vx z`Ac&1yyJc~&UjDeWBrHjN6!7D`#bwF4tP$Le%&{?A0aP)?kn`~*{{-${Mq(r#%FxO zPU$)Q@A+vwO5WGF<&U=u<_NsS|@3iyGm$`1reOFU(VBKcOD)>;9B&-+YaIGi6Xe1L0xZ55Gd|+n&D@c(+%1 z(niN0-*wK%v|<5|c&F+Y&kBfh&1TYjZC#)aQn&;38|*^Q4+w0-l|AHL+T zA-t)2#xI%=qWW>asT}wBy42hAgL#x+J>&Kn-;B2t_a~k@KFj1Wj%(tp<8i$x?iV-j z_RxRX=NnfxI&Q9OH~Ss_=j7Mqo%Z=Y_Q&#k@_yI@IX1RFFwVxI-JX1w_wAo?B#->x z=#zX2|ATjl2PEzzFUWZyp0}S+KO>(*e<1al?;-8=-CsNq`$l=6>LFj}dqLs_`z{c_ z3`gF^<$T@i^F5xN<;L$hKzK;UP5npv5_`7~$ zzR0{(ZqV~GBJ+&z<4%;vLyyD%*k~W>cBLKi5YGdK%1iu{4#*m(M1Gf&vit}3J?~FwX2Q^1UbL zT>s-bclq7hbA8ttFDYM5_Z^>kB=N4Ydcc11BJ$(t&2xa3v``9I5!(|FA|