From 9264609aeb68867ebe8c081f3817a1491692ad74 Mon Sep 17 00:00:00 2001 From: forrest <709335543@qq.com> Date: Mon, 2 May 2022 17:09:51 +0800 Subject: [PATCH] first commit --- .gitignore | 8 + AUTHORS.md | 4 + LICENSE | 203 + README.md | 92 + apollo_common/CMakeLists.txt | 73 + apollo_common/README.md | 77 + apollo_common/data/mkz_config.pb.txt | 18 + .../include/apollo_common/adapters/adapter.h | 396 + .../apollo_common/adapters/adapter_gflags.h | 55 + .../apollo_common/adapters/adapter_manager.h | 218 + .../apollo_common/adapters/message_adapters.h | 82 + .../include/apollo_common/apollo_app.h | 127 + .../apollo_common/configs/config_gflags.h | 40 + .../configs/vehicle_config_helper.h | 101 + apollo_common/include/apollo_common/log.h | 48 + apollo_common/include/apollo_common/macro.h | 59 + .../include/apollo_common/math/aabox2d.h | 246 + .../apollo_common/math/aaboxkdtree2d.h | 487 + .../include/apollo_common/math/angle.h | 295 + .../include/apollo_common/math/box2d.h | 271 + .../apollo_common/math/euler_angles_zxy.h | 205 + .../include/apollo_common/math/integral.h | 78 + .../apollo_common/math/kalman_filter.h | 258 + .../apollo_common/math/line_segment2d.h | 240 + .../apollo_common/math/linear_interpolation.h | 96 + .../math/linear_quadratic_regulator.h | 71 + .../include/apollo_common/math/math_utils.h | 178 + .../apollo_common/math/matrix_operations.h | 99 + .../include/apollo_common/math/polygon2d.h | 332 + .../include/apollo_common/math/quaternion.h | 132 + .../include/apollo_common/math/search.h | 69 + .../include/apollo_common/math/sin_table.h | 57 + .../include/apollo_common/math/vec2d.h | 149 + .../include/apollo_common/monitor/monitor.h | 94 + .../apollo_common/monitor/monitor_buffer.h | 166 + .../include/apollo_common/status/status.h | 153 + .../include/apollo_common/time/time.h | 243 + .../include/apollo_common/util/factory.h | 120 + .../include/apollo_common/util/file.h | 180 + .../apollo_common/util/string_tokenizer.h | 103 + .../include/apollo_common/util/util.h | 65 + .../vehicle_state/vehicle_state.h | 209 + apollo_common/package.xml | 33 + apollo_common/src/adapters/adapter_gflags.cc | 61 + apollo_common/src/adapters/adapter_manager.cc | 131 + apollo_common/src/apollo_app.cc | 82 + apollo_common/src/configs/config_gflags.cc | 36 + .../src/configs/vehicle_config_helper.cc | 64 + apollo_common/src/math/aabox2d.cc | 173 + apollo_common/src/math/angle.cc | 81 + apollo_common/src/math/box2d.cc | 331 + apollo_common/src/math/integral.cc | 69 + apollo_common/src/math/line_segment2d.cc | 241 + .../src/math/linear_interpolation.cc | 84 + .../src/math/linear_quadratic_regulator.cc | 90 + apollo_common/src/math/math_utils.cc | 99 + apollo_common/src/math/polygon2d.cc | 610 + apollo_common/src/math/search.cc | 68 + apollo_common/src/math/sin_table.cc | 3322 ++++ apollo_common/src/math/vec2d.cc | 138 + apollo_common/src/monitor/monitor.cc | 70 + apollo_common/src/monitor/monitor_buffer.cc | 109 + apollo_common/src/util/file.cc | 107 + apollo_common/src/util/string_tokenizer.cc | 74 + apollo_common/src/util/util.cc | 46 + .../src/vehicle_state/vehicle_state.cc | 171 + apollo_control/CMakeLists.txt | 62 + apollo_control/README.md | 13 + apollo_control/conf/adapter.conf | 31 + apollo_control/conf/control.conf | 12 + apollo_control/conf/lincoln.pb.txt | 6560 ++++++++ apollo_control/conf/lincoln_062145.pb.txt | 8110 ++++++++++ apollo_control/conf/lincoln_062146.pb.txt | 7780 +++++++++ apollo_control/conf/lincoln_062147.pb.txt | 7590 +++++++++ apollo_control/conf/lincoln_062546.pb.txt | 6810 ++++++++ apollo_control/conf/lincoln_062547.pb.txt | 6755 ++++++++ apollo_control/conf/lincoln_062845.pb.txt | 6680 ++++++++ .../apollo_control/common/base_types.h | 77 + .../apollo_control/common/control_gflags.h | 66 + .../apollo_control/common/definitions.h | 52 + .../apollo_control/common/hysteresis_filter.h | 60 + .../apollo_control/common/interpolation_2d.h | 92 + .../apollo_control/common/pid_controller.h | 118 + .../common/trajectory_analyzer.h | 158 + .../include/apollo_control/control.h | 148 + .../apollo_control/controller/controller.h | 119 + .../controller/controller_agent.h | 115 + .../controller/lat_controller.h | 234 + .../controller/lon_controller.h | 164 + .../apollo_control/filters/digital_filter.h | 171 + .../filters/digital_filter_coefficients.h | 64 + .../apollo_control/filters/mean_filter.h | 105 + apollo_control/launch/control.launch | 8 + apollo_control/package.xml | 29 + apollo_control/src/common/control_gflags.cc | 64 + .../src/common/hysteresis_filter.cc | 59 + apollo_control/src/common/interpolation_2d.cc | 126 + apollo_control/src/common/pid_controller.cc | 109 + .../src/common/trajectory_analyzer.cc | 244 + apollo_control/src/control.cc | 331 + .../src/controller/controller_agent.cc | 124 + .../src/controller/lat_controller.cc | 507 + .../src/controller/lon_controller.cc | 369 + apollo_control/src/filters/digital_filter.cc | 140 + .../filters/digital_filter_coefficients.cc | 68 + apollo_control/src/filters/mean_filter.cc | 127 + apollo_control/src/main.cc | 37 + apollo_decision/CMakeLists.txt | 50 + apollo_decision/README.md | 21 + apollo_decision/conf/adapter.conf | 6 + apollo_decision/conf/decision.conf | 1 + .../apollo_decision/common/decision_gflags.h | 42 + .../include/apollo_decision/decision.h | 69 + apollo_decision/launch/decision.launch | 7 + apollo_decision/package.xml | 29 + apollo_decision/src/common/decision_gflags.cc | 37 + apollo_decision/src/decision.cc | 80 + apollo_decision/src/main.cc | 42 + apollo_localization/CMakeLists.txt | 54 + apollo_localization/README.md | 29 + apollo_localization/conf/camera_adapter.conf | 26 + apollo_localization/conf/localization.conf | 1 + .../conf/localization_config.pb.txt | 1 + apollo_localization/conf/rtk_adapter.conf | 21 + .../camera/camera_localization.h | 113 + .../common/localization_gflags.h | 74 + .../include/apollo_localization/decision.h | 69 + .../apollo_localization/localization.h | 103 + .../apollo_localization/localization_base.h | 75 + .../rtk/rtk_localization.h | 116 + .../launch/localization.launch | 9 + apollo_localization/package.xml | 29 + .../src/camera/camera_localization.cc | 264 + .../src/common/localization_gflags.cc | 93 + apollo_localization/src/localization.cc | 93 + apollo_localization/src/main.cc | 36 + .../src/rtk/rtk_localization.cc | 429 + apollo_msgs/CMakeLists.txt | 81 + apollo_msgs/README.md | 3 + .../apollo_msgs/proto/canbus/chassis.pb.cc | 1763 ++ .../apollo_msgs/proto/canbus/chassis.pb.h | 1238 ++ .../proto/canbus/chassis_detail.pb.cc | 12819 +++++++++++++++ .../proto/canbus/chassis_detail.pb.h | 8221 ++++++++++ .../proto/common/adapter_config.pb.cc | 822 + .../proto/common/adapter_config.pb.h | 572 + .../proto/common/config_extrinsics.pb.cc | 797 + .../proto/common/config_extrinsics.pb.h | 593 + .../apollo_msgs/proto/common/error_code.pb.cc | 441 + .../apollo_msgs/proto/common/error_code.pb.h | 313 + .../apollo_msgs/proto/common/geometry.pb.cc | 1738 ++ .../apollo_msgs/proto/common/geometry.pb.h | 920 ++ .../proto/common/gnss_status.pb.cc | 1300 ++ .../apollo_msgs/proto/common/gnss_status.pb.h | 864 + .../apollo_msgs/proto/common/header.pb.cc | 661 + .../apollo_msgs/proto/common/header.pb.h | 437 + .../apollo_msgs/proto/common/monitor.pb.cc | 857 + .../apollo_msgs/proto/common/monitor.pb.h | 645 + .../proto/common/vehicle_config.pb.cc | 1254 ++ .../proto/common/vehicle_config.pb.h | 797 + .../proto/control/calibration_table.pb.cc | 693 + .../proto/control/calibration_table.pb.h | 397 + .../proto/control/control_cmd.pb.cc | 4030 +++++ .../proto/control/control_cmd.pb.h | 2607 +++ .../proto/control/control_conf.pb.cc | 957 ++ .../proto/control/control_conf.pb.h | 640 + .../proto/control/lat_controller_conf.pb.cc | 932 ++ .../proto/control/lat_controller_conf.pb.h | 540 + .../proto/control/lon_controller_conf.pb.cc | 1636 ++ .../proto/control/lon_controller_conf.pb.h | 1151 ++ .../apollo_msgs/proto/control/pad_msg.pb.cc | 478 + .../apollo_msgs/proto/control/pad_msg.pb.h | 321 + .../apollo_msgs/proto/decision/decision.pb.cc | 13319 ++++++++++++++++ .../apollo_msgs/proto/decision/decision.pb.h | 9431 +++++++++++ .../proto/localization/camera.pb.cc | 501 + .../proto/localization/camera.pb.h | 353 + .../proto/localization/camera_parameter.pb.cc | 1220 ++ .../proto/localization/camera_parameter.pb.h | 737 + .../apollo_msgs/proto/localization/gps.pb.cc | 436 + .../apollo_msgs/proto/localization/gps.pb.h | 305 + .../apollo_msgs/proto/localization/imu.pb.cc | 435 + .../apollo_msgs/proto/localization/imu.pb.h | 305 + .../proto/localization/localization.pb.cc | 1040 ++ .../proto/localization/localization.pb.h | 805 + .../localization/localization_config.pb.cc | 374 + .../localization/localization_config.pb.h | 262 + .../apollo_msgs/proto/localization/pose.pb.cc | 758 + .../apollo_msgs/proto/localization/pose.pb.h | 630 + .../perception/perception_obstacle.pb.cc | 1576 ++ .../proto/perception/perception_obstacle.pb.h | 1071 ++ .../perception/traffic_light_detection.pb.cc | 844 + .../perception/traffic_light_detection.pb.h | 589 + .../apollo_msgs/proto/planning/planning.pb.cc | 2490 +++ .../apollo_msgs/proto/planning/planning.pb.h | 1587 ++ .../proto/planning/planning_internal.pb.cc | 2680 ++++ .../proto/planning/planning_internal.pb.h | 2232 +++ .../prediction/prediction_obstacle.pb.cc | 1614 ++ .../proto/prediction/prediction_obstacle.pb.h | 962 ++ apollo_msgs/package.xml | 20 + .../apollo_msgs/proto/canbus/chassis.proto | 106 + .../proto/canbus/chassis_detail.proto | 503 + .../proto/common/adapter_config.proto | 41 + .../proto/common/config_extrinsics.proto | 21 + .../apollo_msgs/proto/common/error_code.proto | 30 + .../apollo_msgs/proto/common/geometry.proto | 48 + .../proto/common/gnss_status.proto | 41 + .../apollo_msgs/proto/common/header.proto | 32 + .../apollo_msgs/proto/common/monitor.proto | 37 + .../proto/common/vehicle_config.proto | 44 + .../proto/control/calibration_table.proto | 13 + .../proto/control/control_cmd.proto | 115 + .../proto/control/control_conf.proto | 34 + .../proto/control/lat_controller_conf.proto | 23 + .../proto/control/lon_controller_conf.proto | 40 + .../apollo_msgs/proto/control/pad_msg.proto | 22 + .../apollo_msgs/proto/decision/decision.proto | 317 + .../proto/localization/camera.proto | 16 + .../proto/localization/camera_parameter.proto | 30 + .../apollo_msgs/proto/localization/gps.proto | 13 + .../apollo_msgs/proto/localization/imu.proto | 13 + .../proto/localization/localization.proto | 69 + .../localization/localization_config.proto | 11 + .../apollo_msgs/proto/localization/pose.proto | 71 + .../perception/perception_obstacle.proto | 55 + .../perception/traffic_light_detection.proto | 30 + .../apollo_msgs/proto/planning/planning.proto | 63 + .../proto/planning/planning_internal.proto | 86 + .../prediction/prediction_obstacle.proto | 33 + apollo_planning/CMakeLists.txt | 54 + apollo_planning/README.md | 19 + apollo_planning/conf/adapter.conf | 16 + apollo_planning/conf/planning.conf | 5 + apollo_planning/data/garage.csv | 2083 +++ .../apollo_planning/common/base_types.h | 85 + .../apollo_planning/common/planning_gflags.h | 45 + .../include/apollo_planning/planner/planner.h | 79 + .../planner/rtk_replay_planner.h | 93 + .../include/apollo_planning/planner_factory.h | 74 + .../include/apollo_planning/planning.h | 94 + .../include/apollo_planning/planning_node.h | 91 + apollo_planning/launch/planning.launch | 8 + apollo_planning/package.xml | 29 + apollo_planning/src/common/planning_gflags.cc | 53 + apollo_planning/src/main.cc | 49 + .../src/planner/rtk_replay_planner.cc | 178 + apollo_planning/src/planner_factory.cc | 51 + apollo_planning/src/planning.cc | 186 + apollo_planning/src/planning_node.cc | 144 + apollo_simulator/CMakeLists.txt | 51 + apollo_simulator/README.md | 3 + apollo_simulator/conf/adapter.conf | 21 + .../apollo_simulator/apollo_simulator.h | 197 + .../sim_model_constant_acceleration.h | 105 + .../vehicle_sim_model/sim_model_ideal.h | 243 + .../vehicle_sim_model/sim_model_interface.h | 126 + .../vehicle_sim_model/sim_model_time_delay.h | 347 + .../vehicle_sim_model/sim_model_util.h | 24 + apollo_simulator/launch/simulation.launch | 7 + apollo_simulator/launch/simulator.launch | 25 + apollo_simulator/package.xml | 22 + apollo_simulator/param/simulator_params.yaml | 32 + apollo_simulator/rviz/simulation.rviz | 161 + apollo_simulator/src/apollo_simulator.cpp | 475 + apollo_simulator/src/main.cpp | 39 + .../sim_model_constant_acceleration.cpp | 79 + .../src/vehicle_sim_model/sim_model_ideal.cpp | 137 + .../vehicle_sim_model/sim_model_interface.cpp | 48 + .../sim_model_time_delay.cpp | 339 + .../src/vehicle_sim_model/sim_model_util.cpp | 31 + 268 files changed, 174993 insertions(+) create mode 100644 .gitignore create mode 100644 AUTHORS.md create mode 100644 LICENSE create mode 100644 README.md create mode 100644 apollo_common/CMakeLists.txt create mode 100644 apollo_common/README.md create mode 100644 apollo_common/data/mkz_config.pb.txt create mode 100644 apollo_common/include/apollo_common/adapters/adapter.h create mode 100644 apollo_common/include/apollo_common/adapters/adapter_gflags.h create mode 100644 apollo_common/include/apollo_common/adapters/adapter_manager.h create mode 100644 apollo_common/include/apollo_common/adapters/message_adapters.h create mode 100644 apollo_common/include/apollo_common/apollo_app.h create mode 100644 apollo_common/include/apollo_common/configs/config_gflags.h create mode 100644 apollo_common/include/apollo_common/configs/vehicle_config_helper.h create mode 100644 apollo_common/include/apollo_common/log.h create mode 100644 apollo_common/include/apollo_common/macro.h create mode 100644 apollo_common/include/apollo_common/math/aabox2d.h create mode 100644 apollo_common/include/apollo_common/math/aaboxkdtree2d.h create mode 100644 apollo_common/include/apollo_common/math/angle.h create mode 100644 apollo_common/include/apollo_common/math/box2d.h create mode 100644 apollo_common/include/apollo_common/math/euler_angles_zxy.h create mode 100644 apollo_common/include/apollo_common/math/integral.h create mode 100644 apollo_common/include/apollo_common/math/kalman_filter.h create mode 100644 apollo_common/include/apollo_common/math/line_segment2d.h create mode 100644 apollo_common/include/apollo_common/math/linear_interpolation.h create mode 100644 apollo_common/include/apollo_common/math/linear_quadratic_regulator.h create mode 100644 apollo_common/include/apollo_common/math/math_utils.h create mode 100644 apollo_common/include/apollo_common/math/matrix_operations.h create mode 100644 apollo_common/include/apollo_common/math/polygon2d.h create mode 100644 apollo_common/include/apollo_common/math/quaternion.h create mode 100644 apollo_common/include/apollo_common/math/search.h create mode 100644 apollo_common/include/apollo_common/math/sin_table.h create mode 100644 apollo_common/include/apollo_common/math/vec2d.h create mode 100644 apollo_common/include/apollo_common/monitor/monitor.h create mode 100644 apollo_common/include/apollo_common/monitor/monitor_buffer.h create mode 100644 apollo_common/include/apollo_common/status/status.h create mode 100644 apollo_common/include/apollo_common/time/time.h create mode 100644 apollo_common/include/apollo_common/util/factory.h create mode 100644 apollo_common/include/apollo_common/util/file.h create mode 100644 apollo_common/include/apollo_common/util/string_tokenizer.h create mode 100644 apollo_common/include/apollo_common/util/util.h create mode 100644 apollo_common/include/apollo_common/vehicle_state/vehicle_state.h create mode 100644 apollo_common/package.xml create mode 100644 apollo_common/src/adapters/adapter_gflags.cc create mode 100644 apollo_common/src/adapters/adapter_manager.cc create mode 100644 apollo_common/src/apollo_app.cc create mode 100644 apollo_common/src/configs/config_gflags.cc create mode 100644 apollo_common/src/configs/vehicle_config_helper.cc create mode 100644 apollo_common/src/math/aabox2d.cc create mode 100644 apollo_common/src/math/angle.cc create mode 100644 apollo_common/src/math/box2d.cc create mode 100644 apollo_common/src/math/integral.cc create mode 100644 apollo_common/src/math/line_segment2d.cc create mode 100644 apollo_common/src/math/linear_interpolation.cc create mode 100644 apollo_common/src/math/linear_quadratic_regulator.cc create mode 100644 apollo_common/src/math/math_utils.cc create mode 100644 apollo_common/src/math/polygon2d.cc create mode 100644 apollo_common/src/math/search.cc create mode 100644 apollo_common/src/math/sin_table.cc create mode 100644 apollo_common/src/math/vec2d.cc create mode 100644 apollo_common/src/monitor/monitor.cc create mode 100644 apollo_common/src/monitor/monitor_buffer.cc create mode 100644 apollo_common/src/util/file.cc create mode 100644 apollo_common/src/util/string_tokenizer.cc create mode 100644 apollo_common/src/util/util.cc create mode 100644 apollo_common/src/vehicle_state/vehicle_state.cc create mode 100644 apollo_control/CMakeLists.txt create mode 100644 apollo_control/README.md create mode 100644 apollo_control/conf/adapter.conf create mode 100644 apollo_control/conf/control.conf create mode 100644 apollo_control/conf/lincoln.pb.txt create mode 100644 apollo_control/conf/lincoln_062145.pb.txt create mode 100644 apollo_control/conf/lincoln_062146.pb.txt create mode 100644 apollo_control/conf/lincoln_062147.pb.txt create mode 100644 apollo_control/conf/lincoln_062546.pb.txt create mode 100644 apollo_control/conf/lincoln_062547.pb.txt create mode 100644 apollo_control/conf/lincoln_062845.pb.txt create mode 100644 apollo_control/include/apollo_control/common/base_types.h create mode 100644 apollo_control/include/apollo_control/common/control_gflags.h create mode 100644 apollo_control/include/apollo_control/common/definitions.h create mode 100644 apollo_control/include/apollo_control/common/hysteresis_filter.h create mode 100644 apollo_control/include/apollo_control/common/interpolation_2d.h create mode 100644 apollo_control/include/apollo_control/common/pid_controller.h create mode 100644 apollo_control/include/apollo_control/common/trajectory_analyzer.h create mode 100644 apollo_control/include/apollo_control/control.h create mode 100644 apollo_control/include/apollo_control/controller/controller.h create mode 100644 apollo_control/include/apollo_control/controller/controller_agent.h create mode 100644 apollo_control/include/apollo_control/controller/lat_controller.h create mode 100644 apollo_control/include/apollo_control/controller/lon_controller.h create mode 100644 apollo_control/include/apollo_control/filters/digital_filter.h create mode 100644 apollo_control/include/apollo_control/filters/digital_filter_coefficients.h create mode 100644 apollo_control/include/apollo_control/filters/mean_filter.h create mode 100644 apollo_control/launch/control.launch create mode 100644 apollo_control/package.xml create mode 100644 apollo_control/src/common/control_gflags.cc create mode 100644 apollo_control/src/common/hysteresis_filter.cc create mode 100644 apollo_control/src/common/interpolation_2d.cc create mode 100644 apollo_control/src/common/pid_controller.cc create mode 100644 apollo_control/src/common/trajectory_analyzer.cc create mode 100644 apollo_control/src/control.cc create mode 100644 apollo_control/src/controller/controller_agent.cc create mode 100644 apollo_control/src/controller/lat_controller.cc create mode 100644 apollo_control/src/controller/lon_controller.cc create mode 100644 apollo_control/src/filters/digital_filter.cc create mode 100644 apollo_control/src/filters/digital_filter_coefficients.cc create mode 100644 apollo_control/src/filters/mean_filter.cc create mode 100644 apollo_control/src/main.cc create mode 100644 apollo_decision/CMakeLists.txt create mode 100644 apollo_decision/README.md create mode 100644 apollo_decision/conf/adapter.conf create mode 100644 apollo_decision/conf/decision.conf create mode 100644 apollo_decision/include/apollo_decision/common/decision_gflags.h create mode 100644 apollo_decision/include/apollo_decision/decision.h create mode 100644 apollo_decision/launch/decision.launch create mode 100644 apollo_decision/package.xml create mode 100644 apollo_decision/src/common/decision_gflags.cc create mode 100644 apollo_decision/src/decision.cc create mode 100644 apollo_decision/src/main.cc create mode 100644 apollo_localization/CMakeLists.txt create mode 100644 apollo_localization/README.md create mode 100644 apollo_localization/conf/camera_adapter.conf create mode 100644 apollo_localization/conf/localization.conf create mode 100644 apollo_localization/conf/localization_config.pb.txt create mode 100644 apollo_localization/conf/rtk_adapter.conf create mode 100644 apollo_localization/include/apollo_localization/camera/camera_localization.h create mode 100644 apollo_localization/include/apollo_localization/common/localization_gflags.h create mode 100644 apollo_localization/include/apollo_localization/decision.h create mode 100644 apollo_localization/include/apollo_localization/localization.h create mode 100644 apollo_localization/include/apollo_localization/localization_base.h create mode 100644 apollo_localization/include/apollo_localization/rtk/rtk_localization.h create mode 100644 apollo_localization/launch/localization.launch create mode 100644 apollo_localization/package.xml create mode 100644 apollo_localization/src/camera/camera_localization.cc create mode 100644 apollo_localization/src/common/localization_gflags.cc create mode 100644 apollo_localization/src/localization.cc create mode 100644 apollo_localization/src/main.cc create mode 100644 apollo_localization/src/rtk/rtk_localization.cc create mode 100644 apollo_msgs/CMakeLists.txt create mode 100644 apollo_msgs/README.md create mode 100644 apollo_msgs/include/apollo_msgs/proto/canbus/chassis.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/canbus/chassis.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/canbus/chassis_detail.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/canbus/chassis_detail.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/adapter_config.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/adapter_config.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/config_extrinsics.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/config_extrinsics.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/error_code.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/error_code.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/geometry.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/geometry.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/gnss_status.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/gnss_status.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/header.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/header.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/monitor.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/monitor.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/vehicle_config.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/common/vehicle_config.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/control/calibration_table.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/control/calibration_table.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/control/control_cmd.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/control/control_cmd.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/control/control_conf.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/control/control_conf.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/control/lat_controller_conf.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/control/lat_controller_conf.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/control/lon_controller_conf.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/control/lon_controller_conf.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/control/pad_msg.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/control/pad_msg.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/decision/decision.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/decision/decision.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/camera.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/camera.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/camera_parameter.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/camera_parameter.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/gps.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/gps.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/imu.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/imu.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/localization.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/localization.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/localization_config.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/localization_config.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/pose.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/localization/pose.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/perception/perception_obstacle.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/perception/perception_obstacle.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/perception/traffic_light_detection.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/perception/traffic_light_detection.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/planning/planning.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/planning/planning.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/planning/planning_internal.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/planning/planning_internal.pb.h create mode 100644 apollo_msgs/include/apollo_msgs/proto/prediction/prediction_obstacle.pb.cc create mode 100644 apollo_msgs/include/apollo_msgs/proto/prediction/prediction_obstacle.pb.h create mode 100644 apollo_msgs/package.xml create mode 100644 apollo_msgs/proto/apollo_msgs/proto/canbus/chassis.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/canbus/chassis_detail.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/common/adapter_config.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/common/config_extrinsics.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/common/error_code.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/common/geometry.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/common/gnss_status.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/common/header.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/common/monitor.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/common/vehicle_config.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/control/calibration_table.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/control/control_cmd.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/control/control_conf.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/control/lat_controller_conf.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/control/lon_controller_conf.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/control/pad_msg.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/decision/decision.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/localization/camera.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/localization/camera_parameter.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/localization/gps.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/localization/imu.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/localization/localization.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/localization/localization_config.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/localization/pose.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/perception/perception_obstacle.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/perception/traffic_light_detection.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/planning/planning.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/planning/planning_internal.proto create mode 100644 apollo_msgs/proto/apollo_msgs/proto/prediction/prediction_obstacle.proto create mode 100644 apollo_planning/CMakeLists.txt create mode 100644 apollo_planning/README.md create mode 100644 apollo_planning/conf/adapter.conf create mode 100644 apollo_planning/conf/planning.conf create mode 100644 apollo_planning/data/garage.csv create mode 100644 apollo_planning/include/apollo_planning/common/base_types.h create mode 100644 apollo_planning/include/apollo_planning/common/planning_gflags.h create mode 100644 apollo_planning/include/apollo_planning/planner/planner.h create mode 100644 apollo_planning/include/apollo_planning/planner/rtk_replay_planner.h create mode 100644 apollo_planning/include/apollo_planning/planner_factory.h create mode 100644 apollo_planning/include/apollo_planning/planning.h create mode 100644 apollo_planning/include/apollo_planning/planning_node.h create mode 100644 apollo_planning/launch/planning.launch create mode 100644 apollo_planning/package.xml create mode 100644 apollo_planning/src/common/planning_gflags.cc create mode 100644 apollo_planning/src/main.cc create mode 100644 apollo_planning/src/planner/rtk_replay_planner.cc create mode 100644 apollo_planning/src/planner_factory.cc create mode 100644 apollo_planning/src/planning.cc create mode 100644 apollo_planning/src/planning_node.cc create mode 100644 apollo_simulator/CMakeLists.txt create mode 100644 apollo_simulator/README.md create mode 100644 apollo_simulator/conf/adapter.conf create mode 100644 apollo_simulator/include/apollo_simulator/apollo_simulator.h create mode 100644 apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_constant_acceleration.h create mode 100644 apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_ideal.h create mode 100644 apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_interface.h create mode 100644 apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_time_delay.h create mode 100644 apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_util.h create mode 100644 apollo_simulator/launch/simulation.launch create mode 100644 apollo_simulator/launch/simulator.launch create mode 100644 apollo_simulator/package.xml create mode 100644 apollo_simulator/param/simulator_params.yaml create mode 100644 apollo_simulator/rviz/simulation.rviz create mode 100644 apollo_simulator/src/apollo_simulator.cpp create mode 100644 apollo_simulator/src/main.cpp create mode 100644 apollo_simulator/src/vehicle_sim_model/sim_model_constant_acceleration.cpp create mode 100644 apollo_simulator/src/vehicle_sim_model/sim_model_ideal.cpp create mode 100644 apollo_simulator/src/vehicle_sim_model/sim_model_interface.cpp create mode 100644 apollo_simulator/src/vehicle_sim_model/sim_model_time_delay.cpp create mode 100644 apollo_simulator/src/vehicle_sim_model/sim_model_util.cpp diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..329f8e3 --- /dev/null +++ b/.gitignore @@ -0,0 +1,8 @@ +*.zip +*.tar.gz + +/cmake-build-debug +/cmake-build-release + +/.vscode +/.idea diff --git a/AUTHORS.md b/AUTHORS.md new file mode 100644 index 0000000..0a85dae --- /dev/null +++ b/AUTHORS.md @@ -0,0 +1,4 @@ +| Github account | name | +|---|---| +| Forrest-Z | Zuhong Zhou | + diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..9be1af9 --- /dev/null +++ b/LICENSE @@ -0,0 +1,203 @@ +Copyright (c) 2017 Apollo Authors. All Rights Reserved + + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright (c) 2017 Apollo Authors. All Rights Reserve. + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. diff --git a/README.md b/README.md new file mode 100644 index 0000000..31a5294 --- /dev/null +++ b/README.md @@ -0,0 +1,92 @@ +# apollo.ros-1.0.0 + +## 简介 + + 此工程为基于 apollo 1.0.0 的ros1移植版本,移植主要目的如下: + +- 学习apollo框架设计 +- 学习apollo中的控制算法 + +目前只针对apollo中主要模块进行了移植,移植模块有: + +```bash +apollo_ros + ├── apollo_common + ├── apollo_control + ├── apollo_decision + ├── apollo_localization + ├── apollo_msgs + ├── apollo_planning + └── apollo_simulator +``` + +目前移植版本与原有版本改动点如下: + +- 使用原生ros(基于noetic)替代apollo中更改的ros +- 使用ros pkg封装apollo中每个module +- 使用cmake进行编译 +- 将protobuff版本提升到3.6.0 +- 使用ros中的`std_msgs/String`替代apollo的`pd_msgs/xxx`消息 +- 增加pnc仿真工具`apollo_simulator` + +>此移植版本,能很好的将自己的算法增加到框架中,应用于机器人或者无人驾驶中。同时,由于apollo中的模块抽象,每个模块之间和中间件没有耦合,中间件能很容易从ros1移植到ros2、LCM等,具体开发可根据自己的需求进行魔改。 + +## 安装 + +### 依赖 + +- ros1(noetic,安装见ros官网) + +- eigen3 + + ```bash + sudo apt install libeigen3-dev + ``` + +- glog + + ```bash + sudo apt install libgoogle-glog-dev + ``` + +- gflags + + ```bash + sudo apt install libgflags-dev + ``` + +- gtest + + ```bash + sudo apt install libgtest-dev + ``` + +- protobuff 3.6.0 + + ```shell + wget https://github.com/google/protobuf/releases/download/v3.6.0/protobuf-cpp-3.6.0.tar.gz + tar xzf protobuf-cpp-3.6.0.tar.gz + + pushd protobuf-3.6.0 + ./configure --prefix=/usr + make -j8 + make install + popd + ``` + +### 编译 + +- 创建的ros工作空间 +- 使用`catkin_make`或者`catkin build`指令进行代码编译 + +## 测试 + +这里主要使用`apollo_simulator`仿真工具进行规划控制(pnc)进行测试,测试指令如下: + +```shell +roslaunch apollo_simulator simulation.launch +``` + +## 维护者 + +[@周祖鸿](709335543@qq.com) diff --git a/apollo_common/CMakeLists.txt b/apollo_common/CMakeLists.txt new file mode 100644 index 0000000..2cab14c --- /dev/null +++ b/apollo_common/CMakeLists.txt @@ -0,0 +1,73 @@ +cmake_minimum_required(VERSION 3.0.2) +project(apollo_common) + +add_compile_options(-std=c++17) +# set(CMAKE_BUILD_TYPE "Debug") +set(CMAKE_BUILD_TYPE "Release") + +find_package(Eigen3 REQUIRED) + +find_package(catkin REQUIRED COMPONENTS + roscpp + tf2_msgs + tf2_ros + apollo_msgs +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${PROTO_LIB_NAME} ${PROJECT_NAME} + CATKIN_DEPENDS roscpp tf2_msgs tf2_ros apollo_msgs +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIR} + /usr/include +) + +file(GLOB MATH_SRC_FILES "src/math/*.cc") + +add_library(${PROJECT_NAME} + src/apollo_app.cc + # adapters + src/adapters/adapter_gflags.cc + src/adapters/adapter_manager.cc + # configs + src/configs/config_gflags.cc + src/configs/vehicle_config_helper.cc + # math + ${MATH_SRC_FILES} + # monitor + src/monitor/monitor_buffer.cc + src/monitor/monitor.cc + # util + src/util/file.cc + src/util/string_tokenizer.cc + src/util/util.cc + # vehicle_state + src/vehicle_state/vehicle_state.cc +) +add_dependencies(${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} + protobuf + glog + gflags +) + +# install +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE +) + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) \ No newline at end of file diff --git a/apollo_common/README.md b/apollo_common/README.md new file mode 100644 index 0000000..2bb7946 --- /dev/null +++ b/apollo_common/README.md @@ -0,0 +1,77 @@ +# Common + +``` +Contains code that is not module-specific. +``` + +## apollo_app +``` +The "apollo_app" build target defines the abstract class ApolloApp, +which is implemented by all modules, as well as the macro APOLLO_MAIN, +used to launch each module. +``` + +## log +``` +The "log" build target wraps the Google Log system into project-specific macros, +allowing for more refined control over the levels of logging. +``` + +## macro +``` +The "macro" build target defines a few commonly used class-specific macros. +``` + +## adapters +``` +Adapters are used by the different modules to communicate with one another. +The AdapterManager class hosts all the specific adapters and manages them. +Adapters need to be registered with the macro REGISTER_ADAPTER. +The Adapter class serves as a layer of abstraction between +Apollo modules and I/O mechanisms (e.g. ROS). +``` + + +## configs/data +``` +These specify the vehicle configuration. +``` + +## math +``` +Implements a number of useful mathematical libraries. +``` + +## monitor +``` +Defines a logging system. +``` + +## proto +``` +Defines a number of project-wide protocol buffers. +``` + +## status +``` +Used for determining whether certain functions were performed successfully, +providing helpful error messages otherwise. +``` + +## time +``` +Helper functions related to time. +``` + +## util +``` +Contains an implementation of a factory design pattern with registration, +a few string parsing functions, and some utilities for parsing +protocol buffers from files. +``` + +## vehicle_state +``` +This class specifies the current state of the vehicle (e.g. position, velocity, +heading, etc.). +``` diff --git a/apollo_common/data/mkz_config.pb.txt b/apollo_common/data/mkz_config.pb.txt new file mode 100644 index 0000000..10df861 --- /dev/null +++ b/apollo_common/data/mkz_config.pb.txt @@ -0,0 +1,18 @@ +vehicle_param { + front_edge_to_center: 3.89 + back_edge_to_center: 1.043 + left_edge_to_center: 1.055 + right_edge_to_center: 1.055 + + length: 4.933 + width: 2.11 + height: 1.48 + min_turn_radius: 5.05386147161 + max_acceleration: 2.0 + max_deceleration: -6.0 + max_steer_angle: 8.20304748437 + max_steer_angle_rate: 6.98131700798 + steer_ratio: 16 + wheel_base: 2.8448 + wheel_rolling_radius: 0.335 +} diff --git a/apollo_common/include/apollo_common/adapters/adapter.h b/apollo_common/include/apollo_common/adapters/adapter.h new file mode 100644 index 0000000..853ad9c --- /dev/null +++ b/apollo_common/include/apollo_common/adapters/adapter.h @@ -0,0 +1,396 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + */ + +#ifndef MODULES_ADAPTERS_ADAPTER_H_ +#define MODULES_ADAPTERS_ADAPTER_H_ + +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include + +#include "apollo_msgs/proto/common/header.pb.h" + +#include "apollo_common/adapters/adapter_gflags.h" +#include "apollo_common/time/time.h" +#include "apollo_common/util/file.h" +#include "apollo_common/util/util.h" + +/** + * @namespace apollo::common::adapter + * @brief apollo::common::adapter + */ +namespace apollo { +namespace common { +namespace adapter { + +/** + * @class Adapter + * @brief this class serves as the interface and a layer of + * abstraction for Apollo modules to interact with various I/O (e.g. + * ROS). The adapter will also store history data, so that other + * Apollo modules can get access to both the current and the past data + * without having to handle communication protocols directly. + * + * \par + * Each \class Adapter instance only works with one single topic and + * its corresponding data type. + * + * \par + * Under the hood, a queue is used to store the current and historical + * messages. In most cases, the underlying data type is a proto, though + * this is not necessary. + * + * \note + * Adapter::Observe() is thread-safe, but calling it from + * multiple threads may introduce unexpected behavior. Adapter is + * thread-safe w.r.t. data access and update. + */ +template +class Adapter { + public: + /// The user can use Adapter::DataType to get the type of the + /// underlying data. + typedef D DataType; + + typedef typename std::list>::const_iterator Iterator; + typedef typename std::function Callback; + + /** + * @brief Construct the \class Adapter object. + * @param adapter_name the name of the adapter. It is used to log + * error messages when something bad happens, to help people get an + * idea which adapter goes wrong. + * @param topic_name the topic that the adapter listens to. + * @param message_num the number of historical messages that the + * adapter stores. Older messages will be removed upon calls to + * Adapter::OnReceive(). + */ + Adapter(const std::string &adapter_name, const std::string &topic_name, + size_t message_num, const std::string &dump_dir = "/tmp") + : topic_name_(topic_name), + message_num_(message_num), + enable_dump_(FLAGS_enable_adapter_dump && HasSequenceNumber()), + dump_path_(enable_dump_ ? dump_dir + "/" + adapter_name : "") { + if (enable_dump_) { + if (!apollo::common::util::EnsureDirectory(dump_path_)) { + AERROR << "Cannot enable dumping for '" << adapter_name + << "' adapter because the path " << dump_path_ + << " cannot be created or is not a directory."; + enable_dump_ = false; + } else if (!apollo::common::util::RemoveAllFiles(dump_path_)) { + AERROR << "Cannot enable dumping for '" << adapter_name + << "' adapter because the path " << dump_path_ + << " contains files that cannot be removed."; + enable_dump_ = false; + } + } + } + + /** + * @brief returns the topic name that this adapter listens to. + */ + const std::string &topic_name() const { return topic_name_; } + + /** + * @brief reads the proto message from the file, and push it into + * the adapter's data queue. + * @param message_file the path to the file that contains a (usually + * proto) message of DataType. + */ + void FeedProtoFile(const std::string &message_file) { + D data; + CHECK(apollo::common::util::GetProtoFromFile(message_file, &data)) + << "Unable to parse input pb file " << message_file; + FeedProto(data); + } + + /** + * @brief push (a copy of) the input data into the data queue of + * the adapter. + * @param data the input data. + */ + void FeedProto(const D &data) { + auto data_ptr = std::make_shared(data); + EnqueueData(data_ptr); + } + + /** + * @brief the callback that will be invoked whenever a new + * message is received. + * @param message the newly received message. + */ + void OnReceive(const std_msgs::String::ConstPtr &message) { + D data; + if (!data.ParseFromString(message->data)) { + AERROR << "Failed to parse proto-message."; + return; + } + auto data_ptr = std::make_shared(data); + EnqueueData(data_ptr); + FireCallback(data); + } + + /** + * @brief copy the data_queue_ into the observing queue to create a + * view of data up to the call time for the user. + */ + void Observe() { + std::lock_guard lock(mutex_); + observed_queue_ = data_queue_; + } + + /** + * @brief returns TRUE if the observing queue is empty. + */ + bool Empty() const { + std::lock_guard lock(mutex_); + return observed_queue_.empty(); + } + + /** + * @brief returns the most recent message in the observing queue. + * + * /note + * Please call Empty() to make sure that there is data in the + * queue before calling GetOldestObserved(). + */ + const D &GetLatestObserved() const { + std::lock_guard lock(mutex_); + DCHECK(!observed_queue_.empty()) + << "The view of data queue is empty. No data is received yet or you " + "forgot to call Observe()" + << ":" << topic_name_; + return *observed_queue_.front(); + } + + /** + * @brief returns the oldest message in the observing queue. + * + * /note + * Please call Empty() to make sure that there is data in the + * queue before calling GetOldestObserved(). + */ + const D &GetOldestObserved() const { + std::lock_guard lock(mutex_); + DCHECK(!observed_queue_.empty()) + << "The view of data queue is empty. No data is received yet or you " + "forgot to call Observe()."; + return *observed_queue_.back(); + } + + /** + * @brief returns an iterator representing the head of the observing + * queue. The caller can use it to iterate over the observed data + * from the head. The API also supports range based for loop. + */ + Iterator begin() const { return observed_queue_.begin(); } + + /** + * @brief returns an iterator representing the tail of the observing + * queue. The caller can use it to iterate over the observed data + * from the head. The API also supports range based for loop. + */ + Iterator end() const { return observed_queue_.end(); } + + /** + * @brief registers the provided callback function to the adapter, + * so that the callback function will be called once right after the + * message hits the adapter. + * @param callback the callback with signature void(const D &). + */ + void SetCallback(Callback callback) { receive_callback_ = callback; } + + /** + * @brief fills the fields module_name, timestamp_sec and + * sequence_num in the header. + */ + void FillHeader(const std::string &module_name, + apollo::common::Header *header) { + double timestamp = + apollo::common::time::ToSecond(apollo::common::time::Clock::Now()); + header->set_module_name(module_name); + header->set_timestamp_sec(timestamp); + header->set_sequence_num(++seq_num_); + } + + private: + // HasSequenceNumber returns false for non-proto-message data types. + template + static bool HasSequenceNumber( + typename std::enable_if< + !std::is_base_of::value, + InputMessageType>::type *message = nullptr) { + return false; + } + + // HasSequenceNumber returns true if the data type is proto and has + // header.sequence_num. + template + static bool HasSequenceNumber( + typename std::enable_if< + std::is_base_of::value, + InputMessageType>::type *message = nullptr) { + using gpf = google::protobuf::FieldDescriptor; + InputMessageType sample; + auto descriptor = sample.GetDescriptor(); + auto header_descriptor = descriptor->FindFieldByName("header"); + if (header_descriptor == nullptr) { + return false; + } + if (header_descriptor->cpp_type() != gpf::CPPTYPE_MESSAGE) { + return false; + } + auto sequence_num_descriptor = + header_descriptor->message_type()->FindFieldByName("sequence_num"); + if (sequence_num_descriptor == nullptr) { + return false; + } + if (sequence_num_descriptor->cpp_type() != gpf::CPPTYPE_UINT32) { + return false; + } + return true; + } + + // DumpMessage does nothing for non proto message data type. + template + bool DumpMessage( + const typename std::enable_if< + !std::is_base_of::value, + InputMessageType>::type &message) { + return true; + } + + // DumpMessage dumps the message to a file to + // /tmp//.pb.txt, where the message is in ASCII + // mode and is the .header().sequence_num() of the message. + template + bool DumpMessage( + const typename std::enable_if< + std::is_base_of::value, + InputMessageType>::type &message) { + using google::protobuf::Message; + auto descriptor = message.GetDescriptor(); + auto header_descriptor = descriptor->FindFieldByName("header"); + if (header_descriptor == nullptr) { + ADEBUG << "Fail to find header field in pb."; + return false; + } + const Message &header = message.GetReflection()->GetMessage( + *static_cast(&message), header_descriptor); + auto seq_num_descriptor = + header.GetDescriptor()->FindFieldByName("sequence_num"); + if (seq_num_descriptor == nullptr) { + ADEBUG << "Fail to find sequence_num field in pb."; + return false; + } + uint32_t sequence_num = + header.GetReflection()->GetUInt32(header, seq_num_descriptor); + return apollo::common::util::SetProtoToASCIIFile( + message, dump_path_ + "/" + std::to_string(sequence_num) + ".pb.txt"); + } + + /** + * @brief proactively invokes the callback with the specified data. + * @param data the specified data. + */ + void FireCallback(const D &data) { + if (receive_callback_ != nullptr) { + receive_callback_(data); + } + } + + /** + * @brief push the shared-pointer-guarded data to the data queue of + * the adapter. + */ + void EnqueueData(std::shared_ptr data_ptr) { + if (enable_dump_) { + DumpMessage(*data_ptr); + } + + // Lock the queue. + std::lock_guard lock(mutex_); + if (data_queue_.size() + 1 > message_num_) { + data_queue_.pop_back(); + } + data_queue_.push_front(data_ptr); + } + + /// The topic name that the adapter listens to. + std::string topic_name_; + + /// The maximum size of data_queue_ and observed_queue_ + size_t message_num_ = 0; + + /// The received data. Its size is no more than message_num_ + std::list> data_queue_; + + /// It is the snapshot of the data queue. The snapshot is taken when + /// Observe() is called. + std::list> observed_queue_; + + /// User defined function when receiving a message + Callback receive_callback_ = nullptr; + + /// The mutex guarding data_queue_ and observed_queue_ + mutable std::mutex mutex_; + + /// Whether dumping is enabled. + bool enable_dump_ = false; + + /// The directory of dumped files. + std::string dump_path_; + + /// The monotonically increasing sequence number of the message to + /// be published. + uint32_t seq_num_ = 0; +}; + +} // namespace adapter +} // namespace common +} // namespace apollo + +#endif // MODULES_ADAPTERS_ADAPTER_H_ diff --git a/apollo_common/include/apollo_common/adapters/adapter_gflags.h b/apollo_common/include/apollo_common/adapters/adapter_gflags.h new file mode 100644 index 0000000..9a03012 --- /dev/null +++ b/apollo_common/include/apollo_common/adapters/adapter_gflags.h @@ -0,0 +1,55 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_COMMON_ADAPTERS_ADAPTER_GFLAGS_H_ +#define MODULES_COMMON_ADAPTERS_ADAPTER_GFLAGS_H_ + +#include + +DECLARE_string(adapter_config_path); +DECLARE_bool(enable_adapter_dump); +DECLARE_string(monitor_topic); +DECLARE_string(gps_topic); +DECLARE_string(imu_topic); +DECLARE_string(chassis_topic); +DECLARE_string(chassis_detail_topic); +DECLARE_string(localization_topic); +DECLARE_string(planning_trajectory_topic); +DECLARE_string(monitor_topic); +DECLARE_string(pad_topic); +DECLARE_string(control_command_topic); +DECLARE_string(prediction_topic); +DECLARE_string(perception_obstacle_topic); +DECLARE_string(traffic_light_detection_topic); +DECLARE_string(decision_topic); + +#endif // MODULES_COMMON_ADAPTERS_ADAPTER_GFLAGS_H_ diff --git a/apollo_common/include/apollo_common/adapters/adapter_manager.h b/apollo_common/include/apollo_common/adapters/adapter_manager.h new file mode 100644 index 0000000..b0c8d81 --- /dev/null +++ b/apollo_common/include/apollo_common/adapters/adapter_manager.h @@ -0,0 +1,218 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + */ + +#ifndef MODULES_ADAPTERS_ADAPTER_MANAGER_H_ +#define MODULES_ADAPTERS_ADAPTER_MANAGER_H_ + +#include +#include +#include + +#include + +#include "apollo_msgs/proto/common/adapter_config.pb.h" + +#include "apollo_common/adapters/adapter.h" +#include "apollo_common/adapters/message_adapters.h" +#include "apollo_common/log.h" +#include "apollo_common/macro.h" + +/** + * @namespace apollo::common::adapter + * @brief apollo::common::adapter + */ +namespace apollo { +namespace common { +namespace adapter { + +/// Macro to prepare all the necessary adapter functions when adding a +/// new input/output. For example when you want to listen to +/// car_status message for your module, you can do +/// REGISTER_ADAPTER(CarStatus) write an adapter class called +/// CarStatusAdapter, and call EnableCarStatus(`car_status_topic`, +/// true, `callback`(if there's one)) in AdapterManager. +#define REGISTER_ADAPTER(name) \ + public: \ + static void Enable##name(const std::string &topic_name, \ + AdapterConfig::Mode mode, \ + int message_history_limit) { \ + CHECK(message_history_limit > 0) \ + << "Message history limit must be greater than 0"; \ + instance()->InternalEnable##name(topic_name, mode, message_history_limit); \ + } \ + static name##Adapter *Get##name() { \ + return instance()->InternalGet##name(); \ + } \ + static void Feed##name##ProtoFile(const std::string &proto_file) { \ + CHECK(instance()->name##_) \ + << "Initialize adapter before feeding protobuf"; \ + Get##name()->FeedProtoFile(proto_file); \ + } \ + static void Publish##name(const name##Adapter::DataType &data) { \ + instance()->InternalPublish##name(data); \ + } \ + static void Fill##name##Header(const std::string &module_name, \ + apollo::common::Header *header) { \ + instance()->name##_->FillHeader(module_name, header); \ + } \ + static void Set##name##Callback(name##Adapter::Callback callback) { \ + CHECK(instance()->name##_) \ + << "Initialize adapter before setting callback"; \ + instance()->name##_->SetCallback(callback); \ + } \ + template \ + static void Set##name##Callback( \ + void (T::*fp)(const name##Adapter::DataType &data), T *obj) { \ + Set##name##Callback(std::bind(fp, obj, std::placeholders::_1)); \ + } \ + \ + private: \ + std::unique_ptr name##_; \ + ros::Publisher name##publisher_; \ + ros::Subscriber name##subscriber_; \ + \ + void InternalEnable##name(const std::string &topic_name, \ + AdapterConfig::Mode mode, \ + int message_history_limit) { \ + name##_.reset( \ + new name##Adapter(#name, topic_name, message_history_limit)); \ + if (mode != AdapterConfig::PUBLISH_ONLY && node_handle_) { \ + name##subscriber_ = node_handle_->subscribe( \ + topic_name, message_history_limit, \ + &name##Adapter::OnReceive, name##_.get()); \ + } \ + if (mode != AdapterConfig::RECEIVE_ONLY && node_handle_) { \ + name##publisher_ = node_handle_->advertise( \ + topic_name, message_history_limit); \ + } \ + \ + observers_.push_back([this]() { name##_->Observe(); }); \ + } \ + name##Adapter *InternalGet##name() { return name##_.get(); } \ + void InternalPublish##name(const name##Adapter::DataType &data) { \ + std_msgs::String message; \ + message.data = data.SerializeAsString(); \ + name##publisher_.publish(message); \ + } + +/** + * @class AdapterManager + * + * @brief this class hosts all the specific adapters and manages them. + * It provides APIs for the users to initialize, access and interact + * with the adapters that they are interested in. + * + * \par + * Each (potentially) useful adapter needs to be registered here with + * the macro REGISTER_ADAPTER. + * + * \par + * The AdapterManager is a singleton. + */ +class AdapterManager { + public: + /** + * @brief Initialize the /class AdapterManager singleton. + */ + static void Init(); + + /** + * @brief Initialize the /class AdapterManager singleton with the + * provided configuration. The configuration is specified by the + * file path. + * @param adapter_config_filename the path to the proto file that + * contains the adapter manager configuration. + */ + static void Init(const std::string &adapter_config_filename); + + /** + * @brief Initialize the /class AdapterManager singleton with the + * provided configuration. + * @param configs the adapter manager configuration proto. + */ + static void Init(const AdapterManagerConfig &configs); + static void Observe(); + + /** + * @brief create a timer which will call a callback at the specified + * rate. It takes a class member function, and a bare pointer to the + * object to call the method on. + */ + template + static ros::Timer CreateTimer(ros::Duration period, + void (T::*callback)(const ros::TimerEvent &), + T *obj, bool oneshot = false, + bool autostart = true) { + CHECK(instance()->node_handle_) + << "ROS node is only available in ROS mode, " + "check your adapter config file!"; + return instance()->node_handle_->createTimer(period, callback, obj, oneshot, + autostart); + } + + private: + /// The node handler of ROS, owned by the /class AdapterManager + /// singleton. + std::unique_ptr node_handle_; + + /// Observe() callbacks that will be used to to call the Observe() + /// of enabled adapters. + std::vector> observers_; + + /// The following code registered all the adapters of interest. + REGISTER_ADAPTER(Chassis); + REGISTER_ADAPTER(ChassisDetail); + REGISTER_ADAPTER(ControlCommand); + REGISTER_ADAPTER(Decision); + REGISTER_ADAPTER(Gps); + REGISTER_ADAPTER(Imu); + REGISTER_ADAPTER(Camera); + REGISTER_ADAPTER(Localization); + REGISTER_ADAPTER(Monitor); + REGISTER_ADAPTER(Pad); + REGISTER_ADAPTER(PerceptionObstacles); + REGISTER_ADAPTER(PlanningTrajectory); + REGISTER_ADAPTER(Prediction); + REGISTER_ADAPTER(TrafficLightDetection); + + DECLARE_SINGLETON(AdapterManager); +}; + +} // namespace adapter +} // namespace common +} // namespace apollo + +#endif diff --git a/apollo_common/include/apollo_common/adapters/message_adapters.h b/apollo_common/include/apollo_common/adapters/message_adapters.h new file mode 100644 index 0000000..152832d --- /dev/null +++ b/apollo_common/include/apollo_common/adapters/message_adapters.h @@ -0,0 +1,82 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_ADAPTERS_MESSAGE_ADAPTERS_H_ +#define MODULES_ADAPTERS_MESSAGE_ADAPTERS_H_ + +#include "apollo_common/adapters/adapter.h" + +#include "apollo_msgs/proto/common/monitor.pb.h" +#include "apollo_msgs/proto/canbus/chassis.pb.h" +#include "apollo_msgs/proto/canbus/chassis_detail.pb.h" +#include "apollo_msgs/proto/localization/camera.pb.h" +#include "apollo_msgs/proto/localization/gps.pb.h" +#include "apollo_msgs/proto/localization/imu.pb.h" +#include "apollo_msgs/proto/localization/localization.pb.h" +#include "apollo_msgs/proto/perception/perception_obstacle.pb.h" +#include "apollo_msgs/proto/perception/traffic_light_detection.pb.h" +#include "apollo_msgs/proto/prediction/prediction_obstacle.pb.h" +#include "apollo_msgs/proto/decision/decision.pb.h" +#include "apollo_msgs/proto/planning/planning.pb.h" +#include "apollo_msgs/proto/control/control_cmd.pb.h" +#include "apollo_msgs/proto/control/pad_msg.pb.h" + +/** + * @file message_adapters.h + * @namespace apollo::common::adapter + * @brief This is an agglomeration of all the message adapters supported that + * specializes the adapter template. + */ +namespace apollo { +namespace common { +namespace adapter { + +using MonitorAdapter = Adapter; +using ChassisAdapter = Adapter<::apollo::canbus::Chassis>; +using ChassisDetailAdapter = Adapter<::apollo::canbus::ChassisDetail>; +using GpsAdapter = Adapter; +using ImuAdapter = Adapter<::apollo::localization::Imu>; +using CameraAdapter = Adapter<::apollo::localization::Camera>; +using LocalizationAdapter = Adapter; +using PerceptionObstaclesAdapter = Adapter<::apollo::perception::PerceptionObstacles>; +using TrafficLightDetectionAdapter = Adapter<::apollo::perception::TrafficLightDetection>; +using PredictionAdapter = Adapter<::apollo::prediction::PredictionObstacles>; +using PlanningTrajectoryAdapter = Adapter<::apollo::planning::ADCTrajectory>; +using DecisionAdapter = Adapter<::apollo::decision::DecisionResult>; +using ControlCommandAdapter = Adapter<::apollo::control::ControlCommand>; +using PadAdapter = Adapter<::apollo::control::PadMessage>; + +} // namespace adapter +} // namespace common +} // namespace apollo + +#endif // MODULES_ADAPTERS_MESSAGE_ADAPTERS_H_ diff --git a/apollo_common/include/apollo_common/apollo_app.h b/apollo_common/include/apollo_common/apollo_app.h new file mode 100644 index 0000000..a4c3489 --- /dev/null +++ b/apollo_common/include/apollo_common/apollo_app.h @@ -0,0 +1,127 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + */ + +#ifndef MODULES_APOLLO_APP_H_ +#define MODULES_APOLLO_APP_H_ + +#include +#include + +#include +#include + +#include "apollo_common/log.h" +#include "apollo_common/status/status.h" + +/** + * @namespace apollo::common + * @brief apollo::common + */ +namespace apollo { +namespace common { + +/** + * @class ApolloApp + * + * @brief The base module class to define the interface of an Apollo app. + * An Apollo app runs infinitely until being shutdown by SIGINT or ROS. Many + * essential components in Apollo, such as localization and control are examples + * of Apollo apps. The APOLLO_MAIN macro helps developer to setup glog, gflag + * and ROS in one line. + */ +class ApolloApp { + public: + /** + * @brief module name. It is used to uniquely identify the app. + */ + virtual std::string Name() const = 0; + + /** + * @brief this is the entry point of an Apollo App. It initializes the app, + * starts the app, and stop the app when the ros has shutdown. + */ + virtual int Spin(); + + /** + * The default destructor. + */ + virtual ~ApolloApp() = default; + + protected: + /** + * @brief The module initialization function. This is the first function being + * called when the App starts. Usually this function loads the configurations, + * subscribe the data from sensors or other modules. + * @return Status initialization status + */ + virtual apollo::common::Status Init() = 0; + + /** + * @brief The module start function. Apollo app usually triggered to execute + * in two ways: 1. Triggered by upstream messages, or 2. Triggered by timer. + * If an app is triggered by upstream messages, the Start() function usually + * register a call back function that will be called when an upstream message + * is received. If an app is triggered by timer, the Start() function usually + * register a timer callback function. + * @return Status start status + */ + virtual apollo::common::Status Start() = 0; + + /** + * @brief The module stop function. This function will be called when + * after ros::shutdown() has finished. In the default APOLLO_MAIN macro, + * ros::shutdown() is called when SIGINT is received. + */ + virtual void Stop() = 0; +}; + +void apollo_app_sigint_handler(int signal_num); + +} // namespace common +} // namespace apollo + +#define APOLLO_MAIN(APP) \ + int main(int argc, char **argv) { \ + google::InitGoogleLogging(argv[0]); \ + google::ParseCommandLineFlags(&argc, &argv, true); \ + signal(SIGINT, apollo::common::apollo_app_sigint_handler); \ + APP apollo_app_; \ + ros::init(argc, argv, apollo_app_.Name()); \ + apollo_app_.Spin(); \ + return 0; \ + } + +#endif // MODULES_APOLLO_APP_H_ diff --git a/apollo_common/include/apollo_common/configs/config_gflags.h b/apollo_common/include/apollo_common/configs/config_gflags.h new file mode 100644 index 0000000..8c53c97 --- /dev/null +++ b/apollo_common/include/apollo_common/configs/config_gflags.h @@ -0,0 +1,40 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_COMMON_CONFIGS_GFLAGS_H_ +#define MODULES_COMMON_CONFIGS_GFLAGS_H_ + +#include + +DECLARE_string(vehicle_config_path); + +#endif // MODULES_COMMON_CONFIGS_GFLAGS_H_ diff --git a/apollo_common/include/apollo_common/configs/vehicle_config_helper.h b/apollo_common/include/apollo_common/configs/vehicle_config_helper.h new file mode 100644 index 0000000..5470788 --- /dev/null +++ b/apollo_common/include/apollo_common/configs/vehicle_config_helper.h @@ -0,0 +1,101 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + */ + +#ifndef MODULES_CONFIGS_VEHICLE_CONFIG_H_ +#define MODULES_CONFIGS_VEHICLE_CONFIG_H_ + +#include "apollo_msgs/proto/common/vehicle_config.pb.h" + +#include "apollo_common/macro.h" + +/** + * @namespace apollo::common::config + * @brief apollo::common::config + */ +namespace apollo { +namespace common { +namespace config { + +/** + * @class VehicleConfigHelper + * + * @Brief This is a helper class that can load vehicle configurations. The + * vehicle configurations are + * defined apollo_common/configs/proto/vehicle_config.proto + */ +class VehicleConfigHelper { + public: + /** + * @brief Initialize vehicle configurations with default configuration file + * pointed by gflags FLAGS_vehicle_config_path. The code will crash if + * FLAGS_vehicle_config_path does not exit or it points to a file with invalid + * format. + */ + static void Init(); + + /** + * @brief Initialize vehicle configurations with \p config + * @param config A VehicleConfig class instance. The VehicleConfig class is + * defined by apollo_common/configs/proto/vehicle_config.proto. + */ + static void Init(const VehicleConfig& config); + + /** + * @brief Initialize vehicle configurations with \p config_file. + * The code will crash if \p config_file does not exist or \p config_file has + * invalid format. + * @param config_file The configuration file path. The format of the file is + * defined by protobuf file + * apollo_common/configs/proto/vehicle_config.proto. + */ + static void Init(const std::string& config_file); + + /** + * @brief Get the current vehicle configuration. + * @return the current VehicleConfig instance reference. + */ + static const VehicleConfig& GetConfig(); + + private: + static VehicleConfig vehicle_config_; + DECLARE_SINGLETON(VehicleConfigHelper); +}; + +} // namespace config +} // namespace common +} // namespace apollo + +#endif // MODULES_CONFIGS_VEHICLE_CONFIG_H_ diff --git a/apollo_common/include/apollo_common/log.h b/apollo_common/include/apollo_common/log.h new file mode 100644 index 0000000..3038204 --- /dev/null +++ b/apollo_common/include/apollo_common/log.h @@ -0,0 +1,48 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + */ + +#ifndef MODULES_COMMON_LOG_H_ +#define MODULES_COMMON_LOG_H_ + +#include + +#define ADEBUG VLOG(4) << "[DEBUG] " +#define AINFO VLOG(3) << "[INFO] " +#define AWARN LOG(WARNING) +#define AERROR LOG(ERROR) +#define AFATAL LOG(FATAL) + +#endif // MODULES_COMMON_LOG_H_ diff --git a/apollo_common/include/apollo_common/macro.h b/apollo_common/include/apollo_common/macro.h new file mode 100644 index 0000000..2ccecfa --- /dev/null +++ b/apollo_common/include/apollo_common/macro.h @@ -0,0 +1,59 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + */ + +#ifndef MODULES_COMMON_MACRO_H_ +#define MODULES_COMMON_MACRO_H_ + +#define DISALLOW_COPY_AND_ASSIGN(classname) \ + private: \ + classname(const classname&); \ + classname& operator=(const classname&); + +#define DISALLOW_IMPLICIT_CONSTRUCTORS(classname) \ + private: \ + classname(); \ + DISALLOW_COPY_AND_ASSIGN(classname); + +#define DECLARE_SINGLETON(classname) \ + public: \ + static classname* instance() { \ + static classname instance; \ + return &instance; \ + } \ + DISALLOW_IMPLICIT_CONSTRUCTORS(classname) \ + private: + +#endif // MODULES_COMMON_MACRO_H_ diff --git a/apollo_common/include/apollo_common/math/aabox2d.h b/apollo_common/include/apollo_common/math/aabox2d.h new file mode 100644 index 0000000..1c3ad76 --- /dev/null +++ b/apollo_common/include/apollo_common/math/aabox2d.h @@ -0,0 +1,246 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the AABox2d class. + */ + +#ifndef MODULES_COMMON_MATH_AABOX2D_H_ +#define MODULES_COMMON_MATH_AABOX2D_H_ + +#include +#include + +#include "apollo_common/math/vec2d.h" + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +/** + * @class AABox2d + * @brief Implements a class of (undirected) axes-aligned bounding boxes in 2-D. + * This class is referential-agnostic. + */ +class AABox2d { + public: + /** + * @brief Default constructor. + * Creates an axes-aligned box with zero length and width at the origin. + */ + AABox2d() = default; + /** + * @brief Parametrized constructor. + * Creates an axes-aligned box with given center, length, and width. + * @param center The center of the box + * @param length The size of the box along the x-axis + * @param width The size of the box along the y-axis + */ + AABox2d(const Vec2d& center, const double length, const double width); + /** + * @brief Parametrized constructor. + * Creates an axes-aligned box from two opposite corners. + * @param one_corner One corner of the box + * @param opposite_corner The opposite corner to the first one + */ + AABox2d(const Vec2d& one_corner, const Vec2d& opposite_corner); + /** + * @brief Parametrized constructor. + * Creates an axes-aligned box containing all points in a given vector. + * @param points Vector of points to be included inside the box. + */ + explicit AABox2d(const std::vector& points); + + /** + * @brief Getter of center_ + * @return Center of the box + */ + const Vec2d& center() const { return center_; } + + /** + * @brief Getter of x-component of center_ + * @return x-component of the center of the box + */ + double center_x() const { return center_.x(); } + + /** + * @brief Getter of y-component of center_ + * @return y-component of the center of the box + */ + double center_y() const { return center_.y(); } + + /** + * @brief Getter of length_ + * @return The length of the box + */ + double length() const { return length_; } + + /** + * @brief Getter of width_ + * @return The width of the box + */ + double width() const { return width_; } + + /** + * @brief Getter of half_length_ + * @return Half of the length of the box + */ + double half_length() const { return half_length_; } + + /** + * @brief Getter of half_width_ + * @return Half of the width of the box + */ + double half_width() const { return half_width_; } + + /** + * @brief Getter of length_*width_ + * @return The area of the box + */ + double area() const { return length_ * width_; } + + /** + * @brief Returns the minimum x-coordinate of the box + * + * @return x-coordinate + */ + double min_x() const { return center_.x() - half_length_; } + + /** + * @brief Returns the maximum x-coordinate of the box + * + * @return x-coordinate + */ + double max_x() const { return center_.x() + half_length_; } + + /** + * @brief Returns the minimum y-coordinate of the box + * + * @return y-coordinate + */ + double min_y() const { return center_.y() - half_width_; } + + /** + * @brief Returns the maximum y-coordinate of the box + * + * @return y-coordinate + */ + double max_y() const { return center_.y() + half_width_; } + + /** + * @brief Gets all corners in counter clockwise order. + * + * @param corners Output where the corners are written + */ + void GetAllCorners(std::vector* const corners) const; + + /** + * @brief Determines whether a given point is in the box. + * + * @param point The point we wish to test for containment in the box + */ + bool IsPointIn(const Vec2d& point) const; + + /** + * @brief Determines whether a given point is on the boundary of the box. + * + * @param point The point we wish to test for boundary membership + */ + bool IsPointOnBoundary(const Vec2d& point) const; + + /** + * @brief Determines the distance between a point and the box. + * + * @param point The point whose distance to the box we wish to determine. + */ + double DistanceTo(const Vec2d& point) const; + + /** + * @brief Determines the distance between two boxes. + * + * @param box Another box. + */ + double DistanceTo(const AABox2d& box) const; + + /** + * @brief Determines whether two boxes overlap. + * + * @param box Another box + */ + bool HasOverlap(const AABox2d& box) const; + + /** + * @brief Shift the center of AABox by the input vector. + * + * @param shift_vec The vector by which we wish to shift the box + */ + void Shift(const Vec2d& shift_vec); + + /** + * @brief Changes box to include another given box, as well as the current one. + * + * @param other_box Another box + */ + void MergeFrom(const AABox2d& other_box); + + /** + * @brief Changes box to include a given point, as well as the current box. + * + * @param other_point Another point + */ + void MergeFrom(const Vec2d& other_point); + + /** + * @brief Gets a human-readable debug string + * + * @return A string + */ + std::string DebugString() const; + + private: + Vec2d center_; + double length_ = 0.0; + double width_ = 0.0; + double half_length_ = 0.0; + double half_width_ = 0.0; +}; + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_AABOX2D_H_ */ diff --git a/apollo_common/include/apollo_common/math/aaboxkdtree2d.h b/apollo_common/include/apollo_common/math/aaboxkdtree2d.h new file mode 100644 index 0000000..85c07ec --- /dev/null +++ b/apollo_common/include/apollo_common/math/aaboxkdtree2d.h @@ -0,0 +1,487 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the templated AABoxKDTree2dNode class. + */ + +#ifndef MODULES_COMMON_MATH_AABOXKDTREE2D_H_ +#define MODULES_COMMON_MATH_AABOXKDTREE2D_H_ + +#include +#include +#include +#include + +#include "apollo_common/log.h" + +#include "apollo_common/math/aabox2d.h" +#include "apollo_common/math/math_utils.h" + +/** + * @namespace apollo::common::math + * @brief The math namespace deals with a number of useful mathematical objects. + */ +namespace apollo { +namespace common { +namespace math { + +/** + * @class AABoxKDTreeParams + * @brief Contains parameters of axis-aligned bounding box. + */ +struct AABoxKDTreeParams { + /// The maximum depth of the kdtree. + int max_depth = -1; + /// The maximum number of items in one leaf node. + int max_leaf_size = -1; + /// The maximum dimension size of leaf node. + double max_leaf_dimension = -1.0; +}; + +/** + * @class AABoxKDTree2dNode + * @brief The class of KD-tree node of axis-aligned bounding box. + */ +template +class AABoxKDTree2dNode { + public: + using ObjectPtr = const ObjectType*; + /** + * @brief Constructor which takes a vector of objects, + * parameters and depth of the node. + * @param objects Objects to build the KD-tree node. + * @param params Parameters to build the KD-tree. + * @param depth Depth of the KD-tree node. + */ + AABoxKDTree2dNode(const std::vector& objects, + const AABoxKDTreeParams& params, int depth) + : depth_(depth) { + CHECK(!objects.empty()); + + ComputeBoundary(objects); + ComputePartition(); + + if (SplitToSubNodes(objects, params)) { + std::vector left_subnode_objects; + std::vector right_subnode_objects; + PartitionObjects(objects, &left_subnode_objects, &right_subnode_objects); + + // Split to sub-nodes. + if (!left_subnode_objects.empty()) { + left_subnode_.reset(new AABoxKDTree2dNode( + left_subnode_objects, params, depth + 1)); + } + if (!right_subnode_objects.empty()) { + right_subnode_.reset(new AABoxKDTree2dNode( + right_subnode_objects, params, depth + 1)); + } + } else { + InitObjects(objects); + } + } + + /** + * @brief Get the nearest object to a target point by the KD-tree + * rooted at this node. + * @param point The target point. Search it's nearest object. + * @return The nearest object to the target point. + */ + ObjectPtr GetNearestObject(const Vec2d& point) const { + ObjectPtr nearest_object = nullptr; + double min_distance_sqr = std::numeric_limits::infinity(); + GetNearestObjectInternal(point, &min_distance_sqr, &nearest_object); + return nearest_object; + } + + /** + * @brief Get objects within a distance to a point by the KD-tree + * rooted at this node. + * @param point The center point of the range to search objects. + * @param distance The radius of the range to search objects. + * @return All objects within the specified distance to the specified point. + */ + std::vector GetObjects(const Vec2d& point, + const double distance) const { + std::vector result_objects; + GetObjectsInternal(point, distance, Square(distance), &result_objects); + return result_objects; + } + + /** + * @brief Get the axis-aligned bounding box of the objects. + * @return The axis-aligned bounding box of the objects. + */ + AABox2d GetBoundingBox() const { + return AABox2d({min_x_, min_y_}, {max_x_, max_y_}); + } + + private: + void InitObjects(const std::vector& objects) { + num_objects_ = objects.size(); + objects_sorted_by_min_ = objects; + objects_sorted_by_max_ = objects; + std::sort(objects_sorted_by_min_.begin(), objects_sorted_by_min_.end(), + [&](ObjectPtr obj1, ObjectPtr obj2) { + return partition_ == PARTITION_X + ? obj1->aabox().min_x() < obj2->aabox().min_x() + : obj1->aabox().min_y() < obj2->aabox().min_y(); + }); + std::sort(objects_sorted_by_max_.begin(), objects_sorted_by_max_.end(), + [&](ObjectPtr obj1, ObjectPtr obj2) { + return partition_ == PARTITION_X + ? obj1->aabox().max_x() > obj2->aabox().max_x() + : obj1->aabox().max_y() > obj2->aabox().max_y(); + }); + objects_sorted_by_min_bound_.reserve(num_objects_); + for (ObjectPtr object : objects_sorted_by_min_) { + objects_sorted_by_min_bound_.push_back(partition_ == PARTITION_X + ? object->aabox().min_x() + : object->aabox().min_y()); + } + objects_sorted_by_max_bound_.reserve(num_objects_); + for (ObjectPtr object : objects_sorted_by_max_) { + objects_sorted_by_max_bound_.push_back(partition_ == PARTITION_X + ? object->aabox().max_x() + : object->aabox().max_y()); + } + } + + bool SplitToSubNodes(const std::vector& objects, + const AABoxKDTreeParams& params) { + if (params.max_depth >= 0 && depth_ >= params.max_depth) { + return false; + } + if (static_cast(objects.size()) <= std::max(1, params.max_leaf_size)) { + return false; + } + if (params.max_leaf_dimension >= 0.0 && + std::max(max_x_ - min_x_, max_y_ - min_y_) <= + params.max_leaf_dimension) { + return false; + } + return true; + } + + double LowerDistanceSquareToPoint(const Vec2d& point) const { + double dx = 0.0; + if (point.x() < min_x_) { + dx = min_x_ - point.x(); + } else if (point.x() > max_x_) { + dx = point.x() - max_x_; + } + double dy = 0.0; + if (point.y() < min_y_) { + dy = min_y_ - point.y(); + } else if (point.y() > max_y_) { + dy = point.y() - max_y_; + } + return dx * dx + dy * dy; + } + + double UpperDistanceSquareToPoint(const Vec2d& point) const { + const double dx = + (point.x() > mid_x_ ? (point.x() - min_x_) : (point.x() - max_x_)); + const double dy = + (point.y() > mid_y_ ? (point.y() - min_y_) : (point.y() - max_y_)); + return dx * dx + dy * dy; + } + + void GetAllObjects(std::vector* const result_objects) const { + result_objects->insert(result_objects->end(), + objects_sorted_by_min_.begin(), + objects_sorted_by_min_.end()); + if (left_subnode_ != nullptr) { + left_subnode_->GetAllObjects(result_objects); + } + if (right_subnode_ != nullptr) { + right_subnode_->GetAllObjects(result_objects); + } + } + + void GetObjectsInternal(const Vec2d& point, const double distance, + const double distance_sqr, + std::vector* const result_objects) const { + if (LowerDistanceSquareToPoint(point) > distance_sqr) { + return; + } + if (UpperDistanceSquareToPoint(point) <= distance_sqr) { + GetAllObjects(result_objects); + return; + } + const double pvalue = (partition_ == PARTITION_X ? point.x() : point.y()); + if (pvalue < partition_position_) { + const double limit = pvalue + distance; + for (int i = 0; i < num_objects_; ++i) { + if (objects_sorted_by_min_bound_[i] > limit) { + break; + } + ObjectPtr object = objects_sorted_by_min_[i]; + if (object->DistanceSquareTo(point) <= distance_sqr) { + result_objects->push_back(object); + } + } + } else { + const double limit = pvalue - distance; + for (int i = 0; i < num_objects_; ++i) { + if (objects_sorted_by_max_bound_[i] < limit) { + break; + } + ObjectPtr object = objects_sorted_by_max_[i]; + if (object->DistanceSquareTo(point) <= distance_sqr) { + result_objects->push_back(object); + } + } + } + if (left_subnode_ != nullptr) { + left_subnode_->GetObjectsInternal(point, distance, distance_sqr, + result_objects); + } + if (right_subnode_ != nullptr) { + right_subnode_->GetObjectsInternal(point, distance, distance_sqr, + result_objects); + } + } + + void GetNearestObjectInternal(const Vec2d& point, + double* const min_distance_sqr, + ObjectPtr* const nearest_object) const { + if (LowerDistanceSquareToPoint(point) >= *min_distance_sqr - kMathEpsilon) { + return; + } + const double pvalue = (partition_ == PARTITION_X ? point.x() : point.y()); + const bool search_left_first = (pvalue < partition_position_); + if (search_left_first) { + if (left_subnode_ != nullptr) { + left_subnode_->GetNearestObjectInternal(point, min_distance_sqr, + nearest_object); + } + } else { + if (right_subnode_ != nullptr) { + right_subnode_->GetNearestObjectInternal(point, min_distance_sqr, + nearest_object); + } + } + if (*min_distance_sqr <= kMathEpsilon) { + return; + } + + if (search_left_first) { + for (int i = 0; i < num_objects_; ++i) { + const double bound = objects_sorted_by_min_bound_[i]; + if (bound > pvalue && Square(bound - pvalue) > *min_distance_sqr) { + break; + } + ObjectPtr object = objects_sorted_by_min_[i]; + const double distance_sqr = object->DistanceSquareTo(point); + if (distance_sqr < *min_distance_sqr) { + *min_distance_sqr = distance_sqr; + *nearest_object = object; + } + } + } else { + for (int i = 0; i < num_objects_; ++i) { + const double bound = objects_sorted_by_max_bound_[i]; + if (bound < pvalue && Square(bound - pvalue) > *min_distance_sqr) { + break; + } + ObjectPtr object = objects_sorted_by_max_[i]; + const double distance_sqr = object->DistanceSquareTo(point); + if (distance_sqr < *min_distance_sqr) { + *min_distance_sqr = distance_sqr; + *nearest_object = object; + } + } + } + if (*min_distance_sqr <= kMathEpsilon) { + return; + } + if (search_left_first) { + if (right_subnode_ != nullptr) { + right_subnode_->GetNearestObjectInternal(point, min_distance_sqr, + nearest_object); + } + } else { + if (left_subnode_ != nullptr) { + left_subnode_->GetNearestObjectInternal(point, min_distance_sqr, + nearest_object); + } + } + } + + void ComputeBoundary(const std::vector& objects) { + min_x_ = std::numeric_limits::infinity(); + min_y_ = std::numeric_limits::infinity(); + max_x_ = -std::numeric_limits::infinity(); + max_y_ = -std::numeric_limits::infinity(); + for (ObjectPtr object : objects) { + min_x_ = std::min(min_x_, object->aabox().min_x()); + max_x_ = std::max(max_x_, object->aabox().max_x()); + min_y_ = std::min(min_y_, object->aabox().min_y()); + max_y_ = std::max(max_y_, object->aabox().max_y()); + } + mid_x_ = (min_x_ + max_x_) / 2.0; + mid_y_ = (min_y_ + max_y_) / 2.0; + } + + void ComputePartition() { + if (max_x_ - min_x_ >= max_y_ - min_y_) { + partition_ = PARTITION_X; + partition_position_ = (min_x_ + max_x_) / 2.0; + } else { + partition_ = PARTITION_Y; + partition_position_ = (min_y_ + max_y_) / 2.0; + } + } + + void PartitionObjects(const std::vector& objects, + std::vector* const left_subnode_objects, + std::vector* const right_subnode_objects) { + left_subnode_objects->clear(); + right_subnode_objects->clear(); + std::vector other_objects; + if (partition_ == PARTITION_X) { + for (ObjectPtr object : objects) { + if (object->aabox().max_x() <= partition_position_) { + left_subnode_objects->push_back(object); + } else if (object->aabox().min_x() >= partition_position_) { + right_subnode_objects->push_back(object); + } else { + other_objects.push_back(object); + } + } + } else { + for (ObjectPtr object : objects) { + if (object->aabox().max_y() <= partition_position_) { + left_subnode_objects->push_back(object); + } else if (object->aabox().min_y() >= partition_position_) { + right_subnode_objects->push_back(object); + } else { + other_objects.push_back(object); + } + } + } + InitObjects(other_objects); + } + + private: + int num_objects_ = 0; + std::vector objects_sorted_by_min_; + std::vector objects_sorted_by_max_; + std::vector objects_sorted_by_min_bound_; + std::vector objects_sorted_by_max_bound_; + int depth_ = 0; + + // Boundary + double min_x_ = 0.0; + double max_x_ = 0.0; + double min_y_ = 0.0; + double max_y_ = 0.0; + double mid_x_ = 0.0; + double mid_y_ = 0.0; + + enum Partition { + PARTITION_X = 1, + PARTITION_Y = 2, + }; + Partition partition_ = PARTITION_X; + double partition_position_ = 0.0; + + std::unique_ptr> left_subnode_ = nullptr; + std::unique_ptr> right_subnode_ = nullptr; +}; + +/** + * @class AABoxKDTree2d + * @brief The class of KD-tree of Aligned Axis Bounding Box(AABox). + */ +template +class AABoxKDTree2d { + public: + using ObjectPtr = const ObjectType*; + + /** + * @brief Contructor which takes a vector of objects and parameters. + * @param params Parameters to build the KD-tree. + */ + AABoxKDTree2d(const std::vector& objects, + const AABoxKDTreeParams& params) { + if (!objects.empty()) { + std::vector object_ptrs; + for (const auto& object : objects) { + object_ptrs.push_back(&object); + } + root_.reset(new AABoxKDTree2dNode(object_ptrs, params, 0)); + } + } + + /** + * @brief Get the nearest object to a target point. + * @param point The target point. Search it's nearest object. + * @return The nearest object to the target point. + */ + ObjectPtr GetNearestObject(const Vec2d& point) const { + return root_ == nullptr ? nullptr : root_->GetNearestObject(point); + } + + /** + * @brief Get objects within a distance to a point. + * @param point The center point of the range to search objects. + * @param distance The radius of the range to search objects. + * @return All objects within the specified distance to the specified point. + */ + std::vector GetObjects(const Vec2d& point, + const double distance) const { + if (root_ == nullptr) { + return {}; + } + return root_->GetObjects(point, distance); + } + + /** + * @brief Get the axis-aligned bounding box of the objects. + * @return The axis-aligned bounding box of the objects. + */ + AABox2d GetBoundingBox() const { + return root_ == nullptr ? AABox2d() : root_->GetBoundingBox(); + } + + private: + std::unique_ptr> root_ = nullptr; +}; + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_AABOXKDTREE2D_H_ */ diff --git a/apollo_common/include/apollo_common/math/angle.h b/apollo_common/include/apollo_common/math/angle.h new file mode 100644 index 0000000..47ad214 --- /dev/null +++ b/apollo_common/include/apollo_common/math/angle.h @@ -0,0 +1,295 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the templated Angle class. + */ + +#ifndef MODULES_COMMON_MATH_ANGLE_H_ +#define MODULES_COMMON_MATH_ANGLE_H_ + +#include +#include +#include + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +/** + * @class Angle + * @brief The Angle class uses an integer to represent an angle, and supports + * commonly-used operations such as addition and subtraction, + * as well as the use of trigonometric functions. + * + * Having a specialized Angle class prevents code repetition, namely for tasks + * such as computing angle differences or finding equivalent angles in some + * specified interval, typically [-pi, pi). + * Representing angles by integers has the following advantages: + * 1) Finer level of precision control (< means "less precise than"): + * Angle8 < Angle16 < float < Angle32 < double < Angle64. + * 2) Angle8 and Angle16 allow super fast trigonometric functions + * via a 64-KiB lookup table. + * 3) Higher precision with the same representation size. + * The use of the Angle class is encouraged. + * In particular, Angle32 should be used for latitude/longitude (<1cm error). + * Angle16 is precise enough for localization/object detection. + + * @param T signed integer type +*/ +template +class Angle { + public: + static_assert(std::numeric_limits::is_integer && + std::numeric_limits::is_signed, + "T must be a signed integer type"); + + /** + * @brief Constructs an Angle object from an angle in degrees (factory). + * @param value Angle in degrees + * @return Angle object + */ + static Angle from_deg(double value) { + Angle a(std::lround(value * DEG_TO_RAW)); + return a; + } + + /** + * @brief Constructs an Angle object from an angle in radians (factory). + * @param value Angle in radians + * @return Angle object + */ + static Angle from_rad(double value) { + Angle a(std::lround(value * RAD_TO_RAW)); + return a; + } + + /** + * @brief Constructs an Angle object from raw internal value. + * @param value Angle in degrees + * @return Angle object + */ + explicit Angle(T value = 0) : value_(value) {} + /// Internal representation of pi + static constexpr T RAW_PI = std::numeric_limits::min(); + /// Internal representation of pi/2 + static constexpr T RAW_PI_2 = -(std::numeric_limits::min() >> 1); + /// Used for converting angle units + static constexpr double DEG_TO_RAW = RAW_PI / -180.0; + /// Used for converting angle units + static constexpr double RAD_TO_RAW = RAW_PI * -M_1_PI; + /// Used for converting angle units + static constexpr double RAW_TO_DEG = -180.0 / RAW_PI; + /// Used for converting angle units + static constexpr double RAW_TO_RAD = -M_PI / RAW_PI; + + /** + * @brief Getter of value_. + * @return Internal unsigned integer representation of angle + */ + T raw() const { return value_; } + + /** + * @brief Converts the internal representation to degrees. + * @return angle in degrees + */ + double to_deg() const { return value_ * RAW_TO_DEG; } + + /** + * @brief Converts the internal representation to radians. + * @return angle in radians + */ + double to_rad() const { return value_ * RAW_TO_RAD; } + + /** + * @brief Sums another angle to the current one. + * @param other Another Angle object + * @return Result of sum + */ + Angle operator+=(Angle other) { + value_ += other.value_; + return *this; + } + + /** + * @brief Subtracts another angle from the current one. + * @param other Another Angle object + * @return Result of subtraction + */ + Angle operator-=(Angle other) { + value_ -= other.value_; + return *this; + } + + /** + * @brief Multiplies angle by scalar + * @param s A scalar + * @return Result of multiplication + */ + template + Angle operator*=(Scalar s) { + value_ = std::lround(value_ * s); + return *this; + } + + /** + * @brief Divides angle by scalar + * @param s A scalar + * @return Result of division + */ + template + Angle operator/=(Scalar s) { + value_ = std::lround(value_ / s); + return *this; + } + + private: + T value_; +}; + +using Angle8 = Angle; +using Angle16 = Angle; +using Angle32 = Angle; +using Angle64 = Angle; + +/** + * @brief Sums two angles + * @param lhs An Angle object + * @param rhs An Angle object + * @return Result of addition + */ +template +Angle operator+(Angle lhs, Angle rhs) { + lhs += rhs; + return lhs; +} + +/** + * @brief Subtracts two angles + * @param lhs An Angle object + * @param rhs An Angle object + * @return Result of subtraction + */ +template +Angle operator-(Angle lhs, Angle rhs) { + lhs -= rhs; + return lhs; +} + +/** + * @brief Multiplies an Angle by a scalar + * @param lhs An Angle object + * @param rhs A scalar + * @return Result of multiplication + */ +template +Angle operator*(Angle lhs, Scalar rhs) { + lhs *= rhs; + return lhs; +} + +/** + * @brief Multiplies an Angle by a scalar + * @param lhs An Angle object + * @param rhs A scalar + * @return Result of multiplication + */ +template +Angle operator*(Scalar lhs, Angle rhs) { + rhs *= lhs; + return rhs; +} + +/** + * @brief Divides an Angle by a scalar + * @param lhs An Angle object + * @param rhs A scalar + * @return Result of division + */ +template +Angle operator/(Angle lhs, Scalar rhs) { + lhs /= rhs; + return lhs; +} + +/** + * @brief Divides an Angle by a scalar + * @param lhs An Angle object + * @param rhs A scalar + * @return Result of division + */ +template +double operator/(Angle lhs, Angle rhs) { + return static_cast(lhs.raw()) / rhs.raw(); +} + +/** + * @brief Tests two Angle objects for equality + * @param lhs An Angle object + * @param rhs An Angle object + * @return lhs == rhs + */ +template +bool operator==(Angle lhs, Angle rhs) { + return lhs.raw() == rhs.raw(); +} + +/** + * @brief Tests two Angle objects for inequality + * @param lhs An Angle object + * @param rhs An Angle object + * @return lhs != rhs + */ +template +bool operator!=(Angle lhs, Angle rhs) { + return !(lhs == rhs); +} + +// Fast trigonometric functions. Single precision is sufficient for Angle16 and +// Angle8. +float sin(Angle16 a); +float cos(Angle16 a); +float tan(Angle16 a); +float sin(Angle8 a); +float cos(Angle8 a); +float tan(Angle8 a); + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_AABOX2D_H_ */ diff --git a/apollo_common/include/apollo_common/math/box2d.h b/apollo_common/include/apollo_common/math/box2d.h new file mode 100644 index 0000000..4d7b112 --- /dev/null +++ b/apollo_common/include/apollo_common/math/box2d.h @@ -0,0 +1,271 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief The class of Box2d. Here, the x/y axes are respectively Forward/Left, + * as opposed to what happens in euler_angles_zxy.h (Right/Forward). + */ + +#ifndef MODULES_COMMON_MATH_BOX2D_H_ +#define MODULES_COMMON_MATH_BOX2D_H_ + +#include +#include + +#include "apollo_common/math/aabox2d.h" +#include "apollo_common/math/line_segment2d.h" +#include "apollo_common/math/vec2d.h" + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +/** + * @class Box2d + * @brief Rectangular (undirected) bounding box in 2-D. + * + * This class is referential-agnostic, although our convention on the use of + * the word "heading" in this project (permanently set to be 0 at East) + * forces us to assume that the X/Y frame here is East/North. + * For disambiguation, we call the axis of the rectangle parellel to the + * heading direction the "heading-axis". The size of the heading-axis is + * called "length", and the size of the axis perpenticular to it "width". + */ +class Box2d { + public: + /** + * @brief Constructor which takes the center, heading, length and width. + * @param center The center of the rectangular bounding box. + * @param heading The angle between the x-axis and the heading-axis, + * measured counter-clockwise. + * @param length The size of the heading-axis. + * @param width The size of the axis perpendicular to the heading-axis. + */ + Box2d(const Vec2d& center, const double heading, const double length, + const double width); + + /** + * @brief Constructor which takes the heading-axis and the width of the box + * @param axis The heading-axis + * @param width The width of the box, which is taken perpendicularly + * to the heading direction. + */ + Box2d(const LineSegment2d& axis, const double width); + + /** + * @brief Constructor which takes an AABox2d (axes-aligned box). + * @param aabox The input AABox2d. + */ + explicit Box2d(const AABox2d& aabox); + + /** + * @brief Creates an axes-aligned Box2d from two opposite corners + * @param one_corner One of the corners + * @param opposite_corner The opposite corner to the first one + * @return An axes-aligned Box2d + */ + static Box2d CreateAABox(const Vec2d& one_corner, + const Vec2d& opposite_corner); + + /** + * @brief Getter of the center of the box + * @return The center of the box + */ + const Vec2d& center() const { return center_; } + + /** + * @brief Getter of the x-coordinate of the center of the box + * @return The x-coordinate of the center of the box + */ + double center_x() const { return center_.x(); } + + /** + * @brief Getter of the y-coordinate of the center of the box + * @return The y-coordinate of the center of the box + */ + double center_y() const { return center_.y(); } + + /** + * @brief Getter of the length + * @return The length of the heading-axis + */ + double length() const { return length_; } + + /** + * @brief Getter of the width + * @return The width of the box taken perpendicularly to the heading + */ + double width() const { return width_; } + + /** + * @brief Getter of half the length + * @return Half the length of the heading-axis + */ + double half_length() const { return half_length_; } + + /** + * @brief Getter of half the width + * @return Half the width of the box taken perpendicularly to the heading + */ + double half_width() const { return half_width_; } + + /** + * @brief Getter of the heading + * @return The counter-clockwise angle between the x-axis and the heading-axis + */ + double heading() const { return heading_; } + + /** + * @brief Getter of the co-sine of the heading + * @return The co-sine of the heading + */ + double cos_heading() const { return cos_heading_; } + + /** + * @brief Getter of the sine of the heading + * @return The sine of the heading + */ + double sin_heading() const { return sin_heading_; } + + /** + * @brief Getter of the area of the box + * @return The product of its length and width + */ + double area() const { return length_ * width_; } + + /** + * @brief Getter of the size of the diagonal of the box + * @return The diagonal size of the box + */ + double diagonal() const { return std::hypot(length_, width_); } + + /** + * @brief Getter of the corners of the box + * @param corners The vector where the corners are listed + */ + void GetAllCorners(std::vector* const corners) const; + + /** + * @brief Tests points for membership in the box + * @param point A point that we wish to test for membership in the box + * @return True iff the point is contained in the box + */ + bool IsPointIn(const Vec2d& point) const; + + /** + * @brief Tests points for membership in the boundary of the box + * @param point A point that we wish to test for membership in the boundary + * @return Truee iff the point is a boundary point of the box + */ + bool IsPointOnBoundary(const Vec2d& point) const; + + /** + * @brief Determines the distance between the box and a given point + * @param point The point whose distance to the box we wish to compute + * @return A distance + */ + double DistanceTo(const Vec2d& point) const; + + /** + * @brief Determines the distance between the box and a given line segment + * @param line_segment The line segment whose distance to the box we compute + * @return A distance + */ + double DistanceTo(const LineSegment2d& line_segment) const; + + /** + * @brief Determines the distance between two boxes + * @param box The box whose distance to this box we want to compute + * @return A distance + */ + double DistanceTo(const Box2d& box) const; + + /** + * @brief Determines whether this box overlaps a given line segment + * @param line_segment The line-segment + * @return True if they overlap + */ + bool HasOverlap(const LineSegment2d& line_segment) const; + + /** + * @brief Determines whether these two boxes overlap + * @param line_segment The other box + * @return True if they overlap + */ + bool HasOverlap(const Box2d& box) const; + + /** + * @brief Gets the smallest axes-aligned box containing the current one + * @return An axes-aligned box + */ + AABox2d GetAABox() const; + + /** + * @brief ... + * @param ... + * @return ... + */ + void RotateFromCenter(const double rotate_angle); + + /** + * @brief Shifts this box by a given vector + * @param shift_vec The vector determining the shift + */ + void Shift(const Vec2d& shift_vec); + + /** + * @brief Gets a human-readable description of the box + * @return A debug-string + */ + std::string DebugString() const; + + private: + Vec2d center_; + double length_ = 0.0; + double width_ = 0.0; + double half_length_ = 0.0; + double half_width_ = 0.0; + double heading_ = 0.0; + double cos_heading_ = 1.0; + double sin_heading_ = 0.0; +}; + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_BOX2D_H_ */ diff --git a/apollo_common/include/apollo_common/math/euler_angles_zxy.h b/apollo_common/include/apollo_common/math/euler_angles_zxy.h new file mode 100644 index 0000000..af0c737 --- /dev/null +++ b/apollo_common/include/apollo_common/math/euler_angles_zxy.h @@ -0,0 +1,205 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the EulerAnglesZXY class. + */ + +#ifndef MODULES_COMMON_MATH_EULER_ANGLES_ZXY_H_ +#define MODULES_COMMON_MATH_EULER_ANGLES_ZXY_H_ + +// TODO(all): should use Angle class internally. + +#include + +#include + +#include "apollo_common/math/math_utils.h" + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +/** + * @class EulerAnglesZXY + * + * Any orientation of a rigid body on a 3-D space can be achieved by + * composing three rotations about the axes of an orthogonal coordinate system. + * These rotations are said to be extrinsic if the axes are assumed to be + * motionless, and intrinsic otherwise. Here, we use an intrinsic referential, + * which is relative to the car's orientation. + * Our vehicle reference frame follows NovAtel's convention: + * Right/Forward/Up (RFU) respectively for the axes x/y/z. + * In particular, we describe the orientation of the car by three angles: + * 1) the pitch, in (-pi/2, pi/2), corresponds to a rotation around the x-axis; + * 2) the roll, in [-pi, pi), corresponds to a rotation around the y-axis; + * 3) the yaw, in [-pi, pi), corresponds to a rotation around the z-axis. + * The pitch is zero when the car is level and positive when the nose is up. + * The roll is zero when the car is level and positive when the left part is up. + * The yaw is zero when the car is facing North, and positive when facing West. + * In turn, in the world frame, the x/y/z axes point to East/North/Up (ENU). + * These angles represent the rotation from the world to the vehicle frames. + * + * @brief Implements a class of Euler angles (actually, Tait-Bryan angles), + * with intrinsic sequence ZXY. + * + * @param T Number type: double or float + */ +template +class EulerAnglesZXY { + public: + /** + * @brief Constructs an identity rotation. + */ + EulerAnglesZXY() : roll_(0), pitch_(0), yaw_(0) {} + + /** + * @brief Constructs a rotation using only yaw (i.e., around the z-axis). + * + * @param yaw The yaw of the car + * @param pitch The pitch of the car + * @param roll The roll of the car + */ + explicit EulerAnglesZXY(T yaw) : roll_(0), pitch_(0), yaw_(yaw) {} + + /** + * @brief Constructs a rotation using arbitrary roll, pitch, and yaw. + * + * @param roll The roll of the car + * @param pitch The pitch of the car + * @param yaw The yaw of the car + */ + EulerAnglesZXY(T roll, T pitch, T yaw) + : roll_(roll), pitch_(pitch), yaw_(yaw) {} + + /** + * @brief Constructs a rotation using components of a quaternion. + * + * @param qw Quaternion w-coordinate + * @param qx Quaternion x-coordinate + * @param qy Quaternion y-coordinate + * @param qzQuaternion z-coordinate + */ + EulerAnglesZXY(T qw, T qx, T qy, T qz) + : roll_(std::atan2(2.0 * (qw * qy - qx * qz), + 2.0 * (Square(qw) + Square(qz)) - 1.0)), + pitch_(std::asin(2.0 * (qw * qx + qy * qz))), + yaw_(std::atan2(2.0 * (qw * qz - qx * qy), + 2.0 * (Square(qw) + Square(qy)) - 1.0)) {} + + /** + * @brief Constructs a rotation from quaternion. + * @param q Quaternion + */ + explicit EulerAnglesZXY(const Eigen::Quaternion& q) + : EulerAnglesZXY(q.w(), q.x(), q.y(), q.z()) {} + + /** + * @brief Getter for roll_ + * @return The roll of the car + */ + T roll() const { return roll_; } + + /** + * @brief Getter for pitch_ + * @return The pitch of the car + */ + T pitch() const { return pitch_; } + + /** + * @brief Getter for yaw_ + * @return The yaw of the car + */ + T yaw() const { return yaw_; } + + /** + * @brief Normalizes roll_, pitch_, and yaw_ to [-PI, PI). + */ + void Normalize() { + roll_ = NormalizeAngle(roll_); + pitch_ = NormalizeAngle(pitch_); + yaw_ = NormalizeAngle(yaw_); + } + + /** + * @brief Verifies the validity of the specified rotation. + * @return True iff -PI/2 < pitch < PI/2 + */ + bool IsValid() { + Normalize(); + return pitch_ < M_PI_2 && pitch_ > -M_PI_2; + } + + /** + * @brief Converts to a quaternion with a non-negative scalar part + * @return Quaternion encoding this rotation. + */ + Eigen::Quaternion ToQuaternion() const { + T r = roll_ * 0.5; + T p = pitch_ * 0.5; + T y = yaw_ * 0.5; + + T sr = std::sin(r); + T sp = std::sin(p); + T sy = std::sin(y); + + T cr = std::cos(r); + T cp = std::cos(p); + T cy = std::cos(y); + + T qw = cr * cp * cy - sr * sp * sy; + T qx = cr * sp * cy - sr * cp * sy; + T qy = cr * sp * sy + sr * cp * cy; + T qz = cr * cp * sy + sr * sp * cy; + if (qw < 0.0) return {-qw, -qx, -qy, -qz}; + return {qw, qx, qy, qz}; + } + + private: + T roll_; + T pitch_; + T yaw_; +}; + +using EulerAnglesZXYf = EulerAnglesZXY; +using EulerAnglesZXYd = EulerAnglesZXY; + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_EULER_ANGLES_ZXY_H_ */ diff --git a/apollo_common/include/apollo_common/math/integral.h b/apollo_common/include/apollo_common/math/integral.h new file mode 100644 index 0000000..8e88642 --- /dev/null +++ b/apollo_common/include/apollo_common/math/integral.h @@ -0,0 +1,78 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Functions to compute integral. + */ + +#ifndef MODULES_COMMON_MATH_INTEGRATION_H_ +#define MODULES_COMMON_MATH_INTEGRATION_H_ + +#include + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +// Given a target function and integral lower and upper bound, +// compute the integral approximation using 5th order Gauss-Legendre +// integration. +// The target function must be a smooth function. +// Example: +// target function: auto func = [](const double& x) {return x * x;}; +// double integral = gauss_legendre(func, -2, 3); +// This gives you the approximated integral of function x^2 in bound [-2, 3] + +// reference: https://en.wikipedia.org/wiki/Gaussian_quadrature +// http://www.mymathlib.com/quadrature/gauss_legendre.html + +/** + * @brief Compute the integral of a target single-variable function + * from a lower bound to an upper bound, by 5-th Gauss-Legendre method + * @param func The target single-variable function + * @param lower_bound The lower bound of the integral + * @param upper_bound The upper bound of the integral + * @return The integral result + */ +double GaussLegendre(const std::function& func, + const double lower_bound, const double upper_bound); + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_INTEGRATION_H_ */ diff --git a/apollo_common/include/apollo_common/math/kalman_filter.h b/apollo_common/include/apollo_common/math/kalman_filter.h new file mode 100644 index 0000000..c4c93d5 --- /dev/null +++ b/apollo_common/include/apollo_common/math/kalman_filter.h @@ -0,0 +1,258 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the templated KalmanFilter class. + */ + +#ifndef MODULES_COMMON_MATH_KALMAN_FILTER_H_ +#define MODULES_COMMON_MATH_KALMAN_FILTER_H_ + +#include +#include + +#include + +#include "apollo_common/log.h" +#include "apollo_common/math/matrix_operations.h" + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +/** + * @class KalmanFilter + * + * @brief Implements a discrete-time Kalman filter. + * + * @param XN dimension of state + * @param ZN dimension of observations + * @param UN dimension of controls + */ +template +class KalmanFilter { + public: + /** + * @brief Constructor which defers initialization until the initial state + * distribution parameters are set (with SetStateEstimate), + * typically on the first observation + */ + KalmanFilter() { + F_.setIdentity(); + Q_.setZero(); + H_.setIdentity(); + R_.setZero(); + B_.setZero(); + } + + /** + * @brief Sets the initial state belief distribution. + * + * @param x Mean of the state belief distribution + * @param P Covariance of the state belief distribution + */ + void SetStateEstimate(const Eigen::Matrix& x, + const Eigen::Matrix& P) { + x_ = x; + P_ = P; + is_initialized_ = true; + } + + /** + * @brief Constructor which fully initializes the Kalman filter + * @param x Mean of the state belief distribution + * @param P Covariance of the state belief distribution + */ + KalmanFilter(const Eigen::Matrix& x, + const Eigen::Matrix& P) + : KalmanFilter() { + SetStateEstimate(x, P); + } + + /** + * @brief Destructor + */ + virtual ~KalmanFilter() {} + + /** + * @brief Changes the system transition function under zero control. + * + * @param F New transition matrix + */ + void SetTransitionMatrix(const Eigen::Matrix& F) { F_ = F; } + + /** + * @brief Changes the covariance matrix of the transition noise. + * + * @param Q New covariance matrix + */ + void SetTransitionNoise(const Eigen::Matrix& Q) { Q_ = Q; } + + /** + * @brief Changes the observation matrix, which maps states to observations. + * + * @param H New observation matrix + */ + void SetObservationMatrix(const Eigen::Matrix& H) { H_ = H; } + + /** + * @brief Changes the covariance matrix of the observation noise. + * + * @param R New covariance matrix + */ + void SetObservationNoise(const Eigen::Matrix& R) { R_ = R; } + + /** + * @brief Changes the control matrix in the state transition rule. + * + * @param B New control matrix + */ + void SetControlMatrix(const Eigen::Matrix& B) { B_ = B; } + + /** + * @brief Updates the state belief distribution given the control input u. + * + * @param u Control input (by default, zero) + */ + void Predict( + const Eigen::Matrix& u = Eigen::Matrix::Zero()); + + /** + * @brief Updates the state belief distribution given an observation z. + * + * @param z Observation + */ + void Correct(const Eigen::Matrix& z); + + /** + * @brief Gets mean of our current state belief distribution + * + * @return State vector + */ + Eigen::Matrix GetStateEstimate() const { return x_; } + + /** + * @brief Gets covariance of our current state belief distribution + * + * @return Covariance matrix + */ + Eigen::Matrix GetStateCovariance() const { return P_; } + + /** + * @brief Gets debug string containing detailed information about the filter. + * + * @return Debug string + */ + std::string DebugString() const; + + private: + // Mean of current state belief distribution + Eigen::Matrix x_; + + // Covariance of current state belief dist + Eigen::Matrix P_; + + // State transition matrix under zero control + Eigen::Matrix F_; + + // Covariance of the state transition noise + Eigen::Matrix Q_; + + // Observation matrix + Eigen::Matrix H_; + + // Covariance of observation noise + Eigen::Matrix R_; + + // Control matrix in state transition rule + Eigen::Matrix B_; + + // Innovation; marked as member to prevent memory re-allocation. + Eigen::Matrix y_; + + // Innovation covariance; marked as member to prevent memory re-allocation. + Eigen::Matrix S_; + + // Kalman gain; marked as member to prevent memory re-allocation. + Eigen::Matrix K_; + + // true iff SetStateEstimate has been called. + bool is_initialized_ = false; +}; + +template +inline void KalmanFilter::Predict( + const Eigen::Matrix& u) { + CHECK(is_initialized_); + x_ = F_ * x_ + B_ * u; + P_ = F_ * P_ * F_.transpose() + Q_; +} + +template +inline void KalmanFilter::Correct( + const Eigen::Matrix& z) { + CHECK(is_initialized_); + y_ = z - H_ * x_; + + S_ = H_ * P_ * H_.transpose() + R_; + + K_ = P_ * H_.transpose() * PseudoInverse(S_); + + x_ = x_ + K_ * y_; + + P_ = (Eigen::Matrix::Identity() - K_ * H_) * P_; +} + +template +inline std::string KalmanFilter::DebugString() const { + Eigen::IOFormat clean_fmt(4, 0, ", ", " ", "[", "]"); + std::ostringstream strs; + strs << "F = " << F_.format(clean_fmt) << "\n"; + strs << "B = " << B_.format(clean_fmt) << "\n"; + strs << "H = " << H_.format(clean_fmt) << "\n"; + strs << "Q = " << Q_.format(clean_fmt) << "\n"; + strs << "R = " << R_.format(clean_fmt) << "\n"; + strs << "x = " << x_.format(clean_fmt) << "\n"; + strs << "P = " << P_.format(clean_fmt) << "\n"; + return strs.str(); +} + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_KALMAN_FILTER_H_ */ diff --git a/apollo_common/include/apollo_common/math/line_segment2d.h b/apollo_common/include/apollo_common/math/line_segment2d.h new file mode 100644 index 0000000..c5eb41f --- /dev/null +++ b/apollo_common/include/apollo_common/math/line_segment2d.h @@ -0,0 +1,240 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Define the LineSegment2d class. + */ + +#ifndef MODULES_COMMON_MATH_LINE_SEGEMENT2D_H_ +#define MODULES_COMMON_MATH_LINE_SEGEMENT2D_H_ + +#include + +#include "apollo_common/math/vec2d.h" + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +/** + * @class LineSegment2d + * @brief Line segment in 2-D. + */ +class LineSegment2d { + public: + /** + * @brief Empty constructor. + */ + LineSegment2d(); + + /** + * @brief Constructor with start point and end point. + * @param start The start point of the line segment. + * @param end The end point of the line segment. + */ + LineSegment2d(const Vec2d& start, const Vec2d& end); + + /** + * @brief Get the start point. + * @return The start point of the line segment. + */ + const Vec2d& start() const { return start_; } + + /** + * @brief Get the end point. + * @return The end point of the line segment. + */ + const Vec2d& end() const { return end_; } + + /** + * @brief Get the unit direction from the start point to the end point. + * @return The start point of the line segment. + */ + const Vec2d& unit_direction() const { return unit_direction_; } + + /** + * @brief Get the center of the line segment. + * @return The center of the line segment. + */ + Vec2d center() const { return (start_ + end_) / 2.0; } + + /** + * @brief Get the heading of the line segment. + * @return The heading, which is the angle between unit direction and x-axis. + */ + double heading() const { return heading_; } + + /** + * @brief Get the cosine of the heading. + * @return The cosine of the heading. + */ + double cos_heading() const { return unit_direction_.x(); } + + /** + * @brief Get the sine of the heading. + * @return The sine of the heading. + */ + double sin_heading() const { return unit_direction_.y(); } + + /** + * @brief Get the length of the line segment. + * @return The length of the line segment. + */ + double length() const; + + /** + * @brief Get the square of length of the line segment. + * @return The square of length of the line segment. + */ + double length_sqr() const; + + /** + * @brief Compute the shortest distance from a point on the line segment + * to a point in 2-D. + * @param point The point to compute the distance to. + * @return The shortest ditance from points on the line segment to point. + */ + double DistanceTo(const Vec2d& point) const; + + /** + * @brief Compute the shortest distance from a point on the line segment + * to a point in 2-D, and get the nearest point on the line segment. + * @param point The point to compute the distance to. + * @param nearest_pt The nearest point on the line segment + * to the input point. + * @return The shortest ditance from points on the line segment + * to the input point. + */ + double DistanceTo(const Vec2d& point, Vec2d* const nearest_pt) const; + + /** + * @brief Compute the square of the shortest distance from a point + * on the line segment to a point in 2-D. + * @param point The point to compute the squared of the distance to. + * @return The square of the shortest ditance from points + * on the line segment to the input point. + */ + double DistanceSquareTo(const Vec2d& point) const; + + /** + * @brief Compute the square of the shortest distance from a point + * on the line segment to a point in 2-D, + * and get the nearest point on the line segment. + * @param point The point to compute the squared of the distance to. + * @param nearest_pt The nearest point on the line segment + * to the input point. + * @return The shortest ditance from points on the line segment + * to the input point. + */ + double DistanceSquareTo(const Vec2d& point, Vec2d* const nearest_pt) const; + + /** + * @brief Check if a point is within the line segment. + * @param point The point to ckeck if it is within the line segment. + * @return Whether the input point is within the line segment or not. + */ + bool IsPointIn(const Vec2d& point) const; + + /** + * @brief Check if the line segment has an intersect + * with another line segment in 2-D. + * @param other_segment The line segment to check if it has an intersect. + * @return Whether the line segment has an intersect + * with the input other_segment. + */ + bool HasIntersect(const LineSegment2d& other_segment) const; + + /** + * @brief Compute the intersect with another line segment in 2-D if any. + * @param other_segment The line segment to compute the intersect. + * @param point the computed intersect between the line segment and + * the input other_segment. + * @return Whether the line segment has an intersect + * with the input other_segment. + */ + bool GetIntersect(const LineSegment2d& other_segment, + Vec2d* const point) const; + + /** + * @brief Compute the projection of a vector onto the line segment. + * @param point The end of the vector (starting from the start point of the + * line segment) to compute the projection onto the line segment. + * @return The projection of the vector, which is from the start point of + * the line segment to the input point, onto the unit direction. + */ + double ProjectOntoUnit(const Vec2d& point) const; + + /** + * @brief Compute the cross product of a vector onto the line segment. + * @param point The end of the vector (starting from the start point of the + * line segment) to compute the cross product onto the line segment. + * @return The cross product of the unit direction and + * the vector, which is from the start point of + * the line segment to the input point. + */ + double ProductOntoUnit(const Vec2d& point) const; + + /** + * @brief Compute perpendicular foot of a point in 2-D on the straight line + * expanded from the line segment. + * @param point The point to compute the perpendicular foot from. + * @param foot_point The computed perpendicular foot from the input point to + * the straight line expanded from the line segment. + * @return The distance from the input point to the perpendicular foot. + */ + double GetPerpendicularFoot(const Vec2d& point, + Vec2d* const foot_point) const; + + /** + * @brief Get the debug string including the essential information. + * @return Information of the line segment for debugging. + */ + std::string DebugString() const; + + private: + Vec2d start_; + Vec2d end_; + Vec2d unit_direction_; + double heading_ = 0.0; + double length_ = 0.0; +}; + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_LINE_SEGEMENT2D_H_ */ diff --git a/apollo_common/include/apollo_common/math/linear_interpolation.h b/apollo_common/include/apollo_common/math/linear_interpolation.h new file mode 100644 index 0000000..eee5c58 --- /dev/null +++ b/apollo_common/include/apollo_common/math/linear_interpolation.h @@ -0,0 +1,96 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Linear interpolation functions. + */ + +#ifndef MODULES_COMMON_MATH_LINEAR_INTERPOLATION_H_ +#define MODULES_COMMON_MATH_LINEAR_INTERPOLATION_H_ + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +/** + * @brief Linear interpolation between two 1-D points. + * @param x0 The coordinate of the first 1-D point. + * @param t0 The interpolation parameter of the first 1-D point. + * @param x1 The coordinate of the second 1-D point. + * @param t1 The interpolation parameter of the second 1-D point. + * @param t The interpolation parameter for interpolation. + * @param x The coordinate of the interpolated 1-D point. + * @return Interpolated 1-D point. + */ +double lerp(const double x0, const double t0, const double x1, const double t1, + const double t); + +/** + * @brief Linear interpolation between two 2-D points. + * @param x0 The x coordinate of the first 2-D point. + * @param y0 The y coordinate of the first 2-D point. + * @param t0 The interpolation parameter of the first 2-D point. + * @param x1 The x coordinate of the second 2-D point. + * @param y1 The y coordinate of the second 2-D point. + * @param t1 The interpolation parameter of the second 2-D point. + * @param t The interpolation parameter for interpolation. + * @param x The x coordinate of the interpolated 2-D point. + * @param y The y coordinate of the interpolated 2-D point. + */ +void lerp(const double x0, const double y0, const double t0, const double x1, + const double y1, const double t1, const double t, double* x, + double* y); + +/** + * @brief Spherical linear interpolation between two angles. + * The two angles are within range [-M_PI, M_PI). + * @param a0 The value of the first angle. + * @param t0 The interpolation parameter of the first angle. + * @param a1 The value of the second angle. + * @param t1 The interpolation parameter of the second angle. + * @param t The interpolation parameter for interpolation. + * @param a The value of the spherically interpolated angle. + * @return Interpolated angle. + */ +double slerp(const double a0, const double t0, const double a1, const double t1, + const double t); + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_LINEAR_INTERPOLATION_H_ */ diff --git a/apollo_common/include/apollo_common/math/linear_quadratic_regulator.h b/apollo_common/include/apollo_common/math/linear_quadratic_regulator.h new file mode 100644 index 0000000..aa6079a --- /dev/null +++ b/apollo_common/include/apollo_common/math/linear_quadratic_regulator.h @@ -0,0 +1,71 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Solver for discrete-time linear quadratic problem. + */ + +#ifndef MODULES_COMMON_MATH_LINEAR_QUADRATIC_REGULATOR_H_ +#define MODULES_COMMON_MATH_LINEAR_QUADRATIC_REGULATOR_H_ + +#include + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +/** + * @brief Solver for discrete-time linear quadratic problem. + * @param A The system dynamic matrix + * @param B The control matrix + * @param Q The cost matrix for system state + * @param R The cost matrix for control output + * @param tolerance The numerical tolerance for solving + * Algebraic Riccati equation (ARE) + * @param max_num_iteration The maximum iterations for solving ARE + * @param ptr_K The feedback control matrix (pointer) + */ +void SolveLQRProblem(const Eigen::MatrixXd &A, const Eigen::MatrixXd &B, + const Eigen::MatrixXd &Q, const Eigen::MatrixXd &R, + const double tolerance, const uint max_num_iteration, + Eigen::MatrixXd *ptr_K); + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_LINEAR_QUADRATIC_REGULATOR_H_ */ diff --git a/apollo_common/include/apollo_common/math/math_utils.h b/apollo_common/include/apollo_common/math/math_utils.h new file mode 100644 index 0000000..b2b94d4 --- /dev/null +++ b/apollo_common/include/apollo_common/math/math_utils.h @@ -0,0 +1,178 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Math-related util functions. + */ + +#ifndef MODULES_COMMON_MATH_MATH_UTILS_H_ +#define MODULES_COMMON_MATH_MATH_UTILS_H_ + +#include + +#include "apollo_common/math/vec2d.h" + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +/** + * @brief Cross product between two 2-D vectors from the common start point, + * and end at two other points. + * @param start_point The common start point of two vectors in 2-D. + * @param end_point_1 The end point of the first vector. + * @param end_point_2 The end point of the second vector. + * + * @return The cross product result. + */ +double CrossProd(const Vec2d& start_point, const Vec2d& end_point_1, + const Vec2d& end_point_2); + +/** + * @brief Inner product between two 2-D vectors from the common start point, + * and end at two other points. + * @param start_point The common start point of two vectors in 2-D. + * @param end_point_1 The end point of the first vector. + * @param end_point_2 The end point of the second vector. + * + * @return The inner product result. + */ +double InnerProd(const Vec2d& start_point, const Vec2d& end_point_1, + const Vec2d& end_point_2); + +/** + * @brief Cross product between two vectors. + * One vector is formed by 1st and 2nd parameters of the function. + * The other vector is formed by 3rd and 4th parameters of the function. + * @param x0 The x coordinate of the first vector. + * @param y0 The y coordinate of the first vector. + * @param x1 The x coordinate of the second vector. + * @param y1 The y coordinate of the second vector. + * + * @return The cross product result. + */ +double CrossProd(const double x0, const double y0, const double x1, + const double y1); + +/** + * @brief Inner product between two vectors. + * One vector is formed by 1st and 2nd parameters of the function. + * The other vector is formed by 3rd and 4th parameters of the function. + * @param x0 The x coordinate of the first vector. + * @param y0 The y coordinate of the first vector. + * @param x1 The x coordinate of the second vector. + * @param y1 The y coordinate of the second vector. + * + * @return The inner product result. + */ +double InnerProd(const double x0, const double y0, const double x1, + const double y1); + +/** + * @brief Wrap angle to [0, 2 * PI). + * @param angle the original value of the angle. + * @return The wrapped value of the angle. + */ +double WrapAngle(const double angle); + +/** + * @brief Normalize angle to [-PI, PI). + * @param angle the original value of the angle. + * @return The normalized value of the angle. + */ +double NormalizeAngle(const double angle); + +/** + * @brief Get a random integer between two integer values by a random seed. + * @param s The lower bound of the random integer. + * @param t The upper bound of the random integer. + * @param random_seed The random seed. + * @return A random integer between s and t based on the input random_seed. + */ +int RandomInt(const int s, const int t, unsigned int rand_seed = 1); + +/** + * @brief Get a random double between two integer values by a random seed. + * @param s The lower bound of the random double. + * @param t The upper bound of the random double. + * @param random_seed The random seed. + * @return A random double between s and t based on the input random_seed. + */ +double RandomDouble(const double s, const double t, unsigned int rand_seed = 1); + +/** + * @brief Compute squared value. + * @param value The target value to get its squared value. + * @return Squared value of the input value. + */ +template +inline T Square(const T value) { + return value * value; +} + +/** + * @brief Clamp a value between two bounds. + * If the value goes beyond the bounds, return one of the bounds, + * otherwise, return the original value. + * @param value The original value to be clamped. + * @param bound1 One bound to clamp the value. + * @param bound2 The other bound to clamp the value. + * @return The clamped value. + */ +template +T Clamp(const T value, T bound1, T bound2) { + if (bound1 > bound2) { + std::swap(bound1, bound2); + } + + if (value < bound1) { + return bound1; + } else if (value > bound2) { + return bound2; + } + return value; +} + +int double_compare( + const double d1, const double d2, + const double epsilon = std::numeric_limits::epsilon()); + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_UTILS_H_ */ diff --git a/apollo_common/include/apollo_common/math/matrix_operations.h b/apollo_common/include/apollo_common/math/matrix_operations.h new file mode 100644 index 0000000..d8bfa8a --- /dev/null +++ b/apollo_common/include/apollo_common/math/matrix_operations.h @@ -0,0 +1,99 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines some useful matrix operations. + */ + +#ifndef MODULES_COMMON_MATH_MATRIX_OPERATIONS_H_ +#define MODULES_COMMON_MATH_MATRIX_OPERATIONS_H_ + +#include + +#include +#include + +/** + * @namespace apollo::common::math + * @brief The math namespace deals with a number of useful mathematical objects. + */ +namespace apollo { +namespace common { +namespace math { + +/** + * @brief Computes the Moore-Penrose pseudo-inverse of a given square matrix, + * rounding all eigenvalues with absolute value bounded by epsilon to zero. + * + * @param m The square matrix to be pseudo-inverted + * @param epsilon A small positive real number (optional; default is 1.0e-6). + * + * @return Moore-Penrose pseudo-inverse of the given matrix. + */ +template +Eigen::Matrix PseudoInverse(const Eigen::Matrix& m, + const double epsilon = 1.0e-6) { + Eigen::JacobiSVD> svd( + m, Eigen::ComputeFullU | Eigen::ComputeFullV); + return svd.matrixV() * + (svd.singularValues().array().abs() > epsilon) + .select(svd.singularValues().array().inverse(), 0) + .matrix() + .asDiagonal() * + svd.matrixU().adjoint(); +} + +/** + * @brief Implements Tustin's method for converting transfer functions from + * continuous to discrete time domains. + * https://en.wikipedia.org/wiki/Bilinear_transform + * + * @param m_c Matrix + * @param ts Time interval + * + * @return Matrix + */ +template +Eigen::Matrix ContinuousToDiscrete(const Eigen::Matrix& m_c, + const double ts) { + Eigen::Matrix m_identity = Eigen::Matrix::Identity(); + Eigen::Matrix m_d = (m_identity + ts * 0.5 * m_c) * + PseudoInverse(m_identity - ts * 0.5 * m_c); + return m_d; +} + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_MATRIX_OPERATIONS_H_ */ diff --git a/apollo_common/include/apollo_common/math/polygon2d.h b/apollo_common/include/apollo_common/math/polygon2d.h new file mode 100644 index 0000000..812de8c --- /dev/null +++ b/apollo_common/include/apollo_common/math/polygon2d.h @@ -0,0 +1,332 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Define the Polygon2d class. + */ + +#ifndef MODULES_COMMON_MATH_POLYGON2D_H_ +#define MODULES_COMMON_MATH_POLYGON2D_H_ + +#include +#include + +#include "apollo_common/math/box2d.h" +#include "apollo_common/math/line_segment2d.h" +#include "apollo_common/math/vec2d.h" + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +/** + * @class Polygon2d + * @brief The class of polygon in 2-D. + */ +class Polygon2d { + public: + /** + * @brief Empty constructor. + */ + Polygon2d() = default; + + /** + * @brief Constructor which takes a box. + * @param box The box to construct the polygon. + */ + explicit Polygon2d(const Box2d& box); + + /** + * @brief Constructor which takes a vector of points as its vertices. + * @param points The points to construct the polygon. + */ + explicit Polygon2d(std::vector points); + + /** + * @brief Get the vertices of the polygon. + * @return The vertices of the polygon. + */ + const std::vector& points() const { return points_; } + + /** + * @brief Get the edges of the polygon. + * @return The edges of the polygon. + */ + const std::vector& line_segments() const { + return line_segments_; + } + + /** + * @brief Get the number of vertices of the polygon. + * @return The number of vertices of the polygon. + */ + int num_points() const { return num_points_; } + + /** + * @brief Check if the polygon is convex. + * @return Whether the polygon is convex or not. + */ + bool is_convex() const { return is_convex_; } + + /** + * @brief Get the area of the polygon. + * @return The area of the polygon. + */ + double area() const { return area_; } + + /** + * @brief Compute the distance from a point to the boundary of the polygon. + * This distance is equal to the minimal distance from the point + * to the edges of the polygon. + * @param point The point to compute whose distance to the polygon. + * @return The distance from the point to the polygon's boundary. + */ + double DistanceToBoundary(const Vec2d& point) const; + + /** + * @brief Compute the distance from a point to the polygon. If the point is + * within the polygon, return 0. Otherwise, this distance is + * the minimal distance from the point to the edges of the polygon. + * @param point The point to compute whose distance to the polygon. + * @return The distance from the point to the polygon. + */ + double DistanceTo(const Vec2d& point) const; + + /** + * @brief Compute the distance from a line segment to the polygon. + * If the line segment is within the polygon, or it has intersect with + * the polygon, return 0. Otherwise, this distance is + * the minimal distance between the distances from the two ends + * of the line segment to the polygon. + * @param line_segment The line segment to compute whose distance to + * the polygon. + * @return The distance from the line segment to the polygon. + */ + double DistanceTo(const LineSegment2d& line_segment) const; + + /** + * @brief Compute the distance from a box to the polygon. + * If the box is within the polygon, or it has overlap with + * the polygon, return 0. Otherwise, this distance is + * the minimal distance among the distances from the edges + * of the box to the polygon. + * @param box The box to compute whose distance to the polygon. + * @return The distance from the box to the polygon. + */ + double DistanceTo(const Box2d& box) const; + + /** + * @brief Compute the distance from another polygon to the polygon. + * If the other polygon is within this polygon, or it has overlap with + * this polygon, return 0. Otherwise, this distance is + * the minimal distance among the distances from the edges + * of the other polygon to this polygon. + * @param polygon The polygon to compute whose distance to this polygon. + * @return The distance from the other polygon to this polygon. + */ + double DistanceTo(const Polygon2d& polygon) const; + + /** + * @brief Compute the square of distance from a point to the polygon. + * If the point is within the polygon, return 0. Otherwise, + * this square of distance is the minimal square of distance from + * the point to the edges of the polygon. + * @param point The point to compute whose square of distance to the polygon. + * @return The square of distance from the point to the polygon. + */ + double DistanceSquareTo(const Vec2d& point) const; + + /** + * @brief Check if a point is within the polygon. + * @param point The target point. To check if it is within the polygon. + * @return Whether a point is within the polygon or not. + */ + bool IsPointIn(const Vec2d& point) const; + + /** + * @brief Check if a point is on the boundary of the polygon. + * @param point The target point. To check if it is on the boundary + * of the polygon. + * @return Whether a point is on the boundary of the polygon or not. + */ + bool IsPointOnBoundary(const Vec2d& point) const; + + /** + * @brief Check if the polygon contains a line segment. + * @param line_segment The target line segment. To check if the polygon + * contains it. + * @return Whether the polygon contains the line segment or not. + */ + bool IsContain(const LineSegment2d& line_segment) const; + + /** + * @brief Check if the polygon contains another polygon. + * @param polygon The target polygon. To check if this polygon contains it. + * @return Whether this polygon contains another polygon or not. + */ + bool IsContain(const Polygon2d& polygon) const; + + /** + * @brief Compute the convex hull of a group of points. + * @param points The target points. To compute the convex hull of them. + * @param polygon The convex hull of the points. + * @return If successfully compute the convex hull. + */ + static bool ComputeConvexHull(const std::vector& points, + Polygon2d* const polygon); + + /** + * @brief Check if a line segment has overlap with this polygon. + * @param line_segment The target line segment. To check if it has + * overlap with this polygon. + * @return Whether the target line segment has overlap with this + * polygon or not. + */ + bool HasOverlap(const LineSegment2d& line_segment) const; + + /** + * @brief Get the overlap of a line segment and this polygon. If they have + * overlap, output the two ends of the overlapped line segment. + * @param line_segment The target line segment. To get its overlap with + * this polygon. + * @param first First end of the overlapped line segment. + * @param second Second end of the overlapped line segment. + * @return If the target line segment has overlap with this polygon. + */ + bool GetOverlap(const LineSegment2d& line_segment, Vec2d* const first, + Vec2d* const last) const; + + /** + * @brief Get all overlapped line segments of a line segment and this polygon. + * There are possibly multiple overlapped line segments if this + * polygon is not convex. + * @param line_segment The target line segment. To get its all overlapped + * line segments with this polygon. + * @return A group of overlapped line segments. + */ + std::vector GetAllOverlaps( + const LineSegment2d& line_segment) const; + + /** + * @brief Check if this polygon has overlap with another polygon. + * @param polygon The target polygon. To check if it has overlap + * with this polygon. + * @return If this polygon has overlap with another polygon. + */ + bool HasOverlap(const Polygon2d& polygon) const; + + // Only compute overlaps between two convex polygons. + /** + * @brief Compute the overlap of this polygon and the other polygon if any. + * Note: this function only works for computing overlap between + * two convex polygons. + * @param other_polygon The target polygon. To compute its overlap with + * this polygon. + * @param overlap_polygon The overlapped polygon. + * @param If there is a overlapped polygon. + */ + bool ComputeOverlap(const Polygon2d& other_polygon, + Polygon2d* const overlap_polygon) const; + + /** + * @brief Get the axis-aligned bound box of the polygon. + * @return The axis-aligned bound box of the polygon. + */ + AABox2d AABoundingBox() const; + + /** + * @brief Get the bound box according to a heading. + * @param heading The specified heading of the bounding box. + * @return The bound box according to the specified heading. + */ + Box2d BoundingBoxWithHeading(const double heading) const; + + /** + * @brief Get the bounding box with the minimal area. + * @return The bounding box with the minimal area. + */ + Box2d MinAreaBoundingBox() const; + + /** + * @brief Get the extreme points along a heading direction. + * @param heading The specified heading. + * @param first The point on the boundary of this polygon with the minimal + * projection onto the heading direction. + * @param last The point on the boundary of this polygon with the maximal + * projection onto the heading direction. + */ + void ExtremePoints(const double heading, Vec2d* const first, + Vec2d* const last) const; + + /** + * @brief Expand this polygon by a distance. + * @param distance The specified distance. To expand this polygon by it. + * @return The polygon after expansion. + */ + Polygon2d ExpandByDistance(const double distance) const; + + /** + * @brief Get a string containing essential informaiton about the polygon + * for debugging purpose. + * @return Essential informaiton about the polygon for debugging purpose. + */ + std::string DebugString() const; + + private: + void BuildFromPoints(); + int Next(int at) const; + int Prev(int at) const; + + static bool ClipConvexHull(const LineSegment2d& line_segment, + std::vector* const points); + + std::vector points_; + int num_points_ = 0; + std::vector line_segments_; + bool is_convex_ = false; + double area_ = 0.0; + double min_x_ = 0.0; + double max_x_ = 0.0; + double min_y_ = 0.0; + double max_y_ = 0.0; +}; + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_POLYGON2D_H_ */ diff --git a/apollo_common/include/apollo_common/math/quaternion.h b/apollo_common/include/apollo_common/math/quaternion.h new file mode 100644 index 0000000..7d672b1 --- /dev/null +++ b/apollo_common/include/apollo_common/math/quaternion.h @@ -0,0 +1,132 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Contains a number of helper functions related to quaternions. + * The reader should refer to euler_angles_zxy.h for clarifications. + * However, although the vehicle frame defined therein might change, + * the definition of the heading of the car, used below, is permanently fixed: + * 0 at East, pi/2 at North, -pi/2 at South. + */ + +#ifndef MODULES_COMMON_MATH_QUATERNION_H_ +#define MODULES_COMMON_MATH_QUATERNION_H_ + +#include + +#include +#include + +#include "apollo_msgs/proto/common/geometry.pb.h" + +#include "apollo_common/math/euler_angles_zxy.h" +#include "apollo_common/math/math_utils.h" + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +/* + * @brief Returns heading (in radians) in [-PI, PI), with 0 being East. + * Note that x/y/z is East/North/Up. + * + * @param qw Quaternion w-coordinate + * @param qx Quaternion x-coordinate + * @param qy Quaternion y-coordinate + * @param qz Quaternion z-coordinate + * + * @return Heading encoded by given quaternion + */ +inline double QuaternionToHeading(const double qw, const double qx, + const double qy, const double qz) { + EulerAnglesZXYd euler_angles(qw, qx, qy, qz); + // euler_angles.yaw() is zero when the car is pointing North, but + // the heading is zero when the car is pointing East. + return NormalizeAngle(euler_angles.yaw() + M_PI_2); +} + +/* + * @brief Returns heading (in radians) in [-PI, PI), with 0 being East. + * Note that x/y/z is East/North/Up. + * + * @param q Eigen::Quaternion + * + * @return Heading encoded by given quaternion + */ +template +inline double QuaternionToHeading(const Eigen::Quaternion &q) { + return QuaternionToHeading(q.w(), q.x(), q.y(), q.z()); +} + +/* + * @brief Returns a quaternion encoding a rotation with zero roll, zero pitch, + * and the specified heading/yaw. + * Note that heading is zero at East and yaw is zero at North. + * Satisfies QuaternionToHeading(HeadingToQuaternion(h)) = h. + * + * @param heading The heading to encode in the rotation + * + * @return Quaternion encoding rotation by given heading + */ +template +inline Eigen::Quaternion HeadingToQuaternion(const double heading) { + // Note that heading is zero at East and yaw is zero at North. + EulerAnglesZXY euler_angles(heading - M_PI_2); + return euler_angles.ToQuaternion(); +} + +/* + * @brief Applies the rotation defined by a quaternion to a given vector. + * Note that x/y/z is East/North/Up. + * + * @param orientation Quaternion + * @param original Vector (in East-North-Up frame) + * + * @return Rotated vector + */ +inline Eigen::Vector3d QuaternionRotate(const Quaternion &orientation, + const Eigen::Vector3d &original) { + Eigen::Quaternion quaternion(orientation.qw(), orientation.qx(), + orientation.qy(), orientation.qz()); + return quaternion.toRotationMatrix() * original; +} + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_QUATERNION_H_ */ diff --git a/apollo_common/include/apollo_common/math/search.h b/apollo_common/include/apollo_common/math/search.h new file mode 100644 index 0000000..7aebdc8 --- /dev/null +++ b/apollo_common/include/apollo_common/math/search.h @@ -0,0 +1,69 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Search-related functions. + */ + +#ifndef MODULES_COMMON_MATH_SEARCH_H_ +#define MODULES_COMMON_MATH_SEARCH_H_ + +#include + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +/** + * @brief Given a unimodal function defined on the interval, + * find a value on the interval to minimize the function. + * Reference: https://en.wikipedia.org/wiki/Golden-section_search + * @param func The target single-variable function to minimize. + * @param lower_bound The lower bound of the interval. + * @param upper_bound The upper bound of the interval. + * @param tol The tolerance of error. + * @return The value that minimize the function fun. + */ +double GoldenSectionSearch(const std::function& func, + const double lower_bound, const double upper_bound, + const double tol = 1e-6); + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_SEARCH_H_ */ diff --git a/apollo_common/include/apollo_common/math/sin_table.h b/apollo_common/include/apollo_common/math/sin_table.h new file mode 100644 index 0000000..3bb60a3 --- /dev/null +++ b/apollo_common/include/apollo_common/math/sin_table.h @@ -0,0 +1,57 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Exports the SIN_TABLE, used by the Angle class. + */ + +#ifndef MODULES_COMMON_MATH_SIN_TABLE_H_ +#define MODULES_COMMON_MATH_SIN_TABLE_H_ + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +//! Used by Angle class to speed-up computation of trigonometric functions. +#define SIN_TABLE_SIZE 16385 +extern const float SIN_TABLE[SIN_TABLE_SIZE]; + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_SIN_TABLE_H_ */ diff --git a/apollo_common/include/apollo_common/math/vec2d.h b/apollo_common/include/apollo_common/math/vec2d.h new file mode 100644 index 0000000..ceee113 --- /dev/null +++ b/apollo_common/include/apollo_common/math/vec2d.h @@ -0,0 +1,149 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the Vec2d class. + */ + +#ifndef MODULES_COMMON_MATH_VEC2D_H_ +#define MODULES_COMMON_MATH_VEC2D_H_ + +#include +#include + +/** + * @namespace apollo::common::math + * @brief apollo::common::math + */ +namespace apollo { +namespace common { +namespace math { + +constexpr double kMathEpsilon = 1e-10; + +/** + * @class Vec2d + * + * @brief Implements a class of 2-dimensional vectors, + * similar to Eigen::Vector2d. + */ +class Vec2d { + public: + //! Constructor which takes x- and y-coordinates. + constexpr Vec2d(const double x, const double y) noexcept : x_(x), y_(y) {} + + //! Constructor returning the zero vector. + constexpr Vec2d() noexcept : Vec2d(0, 0) {} + + //! Creates a unit-vector with a given angle to the positive x semi-axis + static Vec2d CreateUnitVec2d(const double angle); + + //! Getter for x component + double x() const { return x_; } + + //! Getter for y component + double y() const { return y_; } + + //! Setter for x component + void set_x(const double x) { x_ = x; } + + //! Setter for y component + void set_y(const double y) { y_ = y; } + + //! Gets the length of the vector + double Length() const; + + //! Gets the squared length of the vector + double LengthSquare() const; + + //! Gets the angle between the vector and the positive x semi-axis + double Angle() const; + + //! Returns the unit vector that is co-linear with this vector + void Normalize(); + + //! Returns the distance to the given vector + double DistanceTo(const Vec2d& other) const; + + //! Returns the squared distance to the given vector + double DistanceSquareTo(const Vec2d& other) const; + + //! Returns the "cross" product between these two Vec2d (non-standard). + double CrossProd(const Vec2d& other) const; + + //! Returns the inner product between these two Vec2d. + double InnerProd(const Vec2d& other) const; + + //! Sums two Vec2d + Vec2d operator+(const Vec2d& other) const; + + //! Subtracts two Vec2d + Vec2d operator-(const Vec2d& other) const; + + //! Multiplies Vec2d by a scalar + Vec2d operator*(const double ratio) const; + + //! Divides Vec2d by a scalar + Vec2d operator/(const double ratio) const; + + //! Sums another Vec2d to the current one + Vec2d& operator+=(const Vec2d& other); + + //! Subtracts another Vec2d to the current one + Vec2d& operator-=(const Vec2d& other); + + //! Multiplies this Vec2d by a scalar + Vec2d& operator*=(const double ratio); + + //! Divides this Vec2d by a scalar + Vec2d& operator/=(const double ratio); + + //! Compares two Vec2d + bool operator==(const Vec2d& other) const; + + //! Returns a human-readable string representing this object + std::string DebugString() const; + + protected: + double x_ = 0.0; + double y_ = 0.0; +}; + +//! Multiplies the given Vec2d by a given scalar +Vec2d operator*(const double ratio, const Vec2d& vec); + +} // namespace math +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_MATH_VEC2D_H_ */ diff --git a/apollo_common/include/apollo_common/monitor/monitor.h b/apollo_common/include/apollo_common/monitor/monitor.h new file mode 100644 index 0000000..4c6b290 --- /dev/null +++ b/apollo_common/include/apollo_common/monitor/monitor.h @@ -0,0 +1,94 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file monitor.h + * @brief The class of Monitor + */ + +#ifndef MODULES_MONITOR_MONITOR_H_ +#define MODULES_MONITOR_MONITOR_H_ + +#include +#include +#include +#include + +#include + +#include "apollo_msgs/proto/common/monitor.pb.h" + +#include "apollo_common/monitor/monitor_buffer.h" + +/** + * @namespace apollo::common::monitor + * @brief apollo::common::monitor + */ +namespace apollo { +namespace common { +namespace monitor { + +/** + * class Monitor + * + * @brief This class help collect and publish MonitorMessage pb to monitor + * topic. A module who wants to publish message can use macro + * `MONITOR(log_level, log_msg)` to record messages, and call + * Publish to broadcast the message to other modules. + */ +class Monitor { + public: + /** + * @brief Construct the monitor with the source of the monitor messages. The + * source is usually the module name who publish the monitor messages. + * @param source the source of the monitor messages. + */ + explicit Monitor(const MonitorMessageItem::MessageSource& source) + : source_(source) {} + + /** + * @brief Publish the messages. + * @param messages a list of messages for + */ + virtual void Publish(const std::vector& messages) const; + + private: + virtual void DoPublish(MonitorMessage* message) const; + + MonitorMessageItem::MessageSource source_; +}; + +} // namespace monitor +} // namespace common +} // namespace apollo + +#endif // MODULES_MONITOR_MONITOR_H_ diff --git a/apollo_common/include/apollo_common/monitor/monitor_buffer.h b/apollo_common/include/apollo_common/monitor/monitor_buffer.h new file mode 100644 index 0000000..273afde --- /dev/null +++ b/apollo_common/include/apollo_common/monitor/monitor_buffer.h @@ -0,0 +1,166 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file monitor_buffer.h + * @brief The class of MonitorBuffer + */ + +#ifndef MODULES_MONITOR_MONITOR_BUFFER_H_ +#define MODULES_MONITOR_MONITOR_BUFFER_H_ + +#include +#include +#include +#include + +#include +#include + +#include "apollo_msgs/proto/common/monitor.pb.h" + +/** + * @namespace apollo::common::monitor + * @brief apollo::common::monitor + */ +namespace apollo { +namespace common { +namespace monitor { + +using MessageItem = std::pair; + +class Monitor; + +#define REG_MSG_TYPE(TYPE) \ + MonitorBuffer& TYPE(const std::string& msg) { \ + AddMonitorMsgItem(MonitorMessageItem::TYPE, msg); \ + return *this; \ + } \ + MonitorBuffer& TYPE() { \ + level_ = MonitorMessageItem::TYPE; \ + return *this; \ + } + +/** + * class MonitorBuffer + * + * @brief This class help collect MonitorMessage pb to monitor topic. + * The messages can be published automatically when the MonitorBuffer object's + * destructor is called, or can be published by calling function Publish(). + */ +class MonitorBuffer { + public: + /** + * @brief The constructor of MonitorBuffer. + * @param a Monitor instance pointer; + */ + explicit MonitorBuffer(Monitor* monitor); + + virtual ~MonitorBuffer(); + + /** + * @brief print a log trace for the last recorded message. + */ + void PrintLog(); + + /** + * @brief record an INFO type message + */ + REG_MSG_TYPE(INFO); + + /** + * @brief record a WARN type message + */ + REG_MSG_TYPE(WARN); + + /** + * @brief record an ERROR type message + */ + REG_MSG_TYPE(ERROR); + + /** + * @brief record a FATAL type message + */ + REG_MSG_TYPE(FATAL); + + /** + * @brief Add monitor message with MonitorMessageItem::LogLevel + * @param log_level defined in modules/common/monitor/proto/monitor.proto + * @param msg the string to send to monitor + */ + void AddMonitorMsgItem(const MonitorMessageItem::LogLevel log_level, + const std::string& msg); + + /** + * @brief overload operator << to help join messages + */ + template + MonitorBuffer& operator<<(const T& msg) { + if (monitor_msg_items_.empty() || + monitor_msg_items_.back().first != level_) { + AddMonitorMsgItem(level_, std::to_string(msg)); + } else { + monitor_msg_items_.back().second += std::to_string(msg); + } + return *this; + } + + /** + * @brief overload operator << to help join string messages + */ + MonitorBuffer& operator<<(const std::string& msg); + + /** + * @brief overload operator << to help join char messages + */ + MonitorBuffer& operator<<(const char* msg); + + /** + * @brief publish the monitor messages + */ + void Publish(); + + private: + Monitor* monitor_ = nullptr; + MonitorMessageItem::LogLevel level_ = MonitorMessageItem::INFO; + std::vector monitor_msg_items_; + + FRIEND_TEST(MonitorBufferTest, RegisterMacro); + FRIEND_TEST(MonitorBufferTest, AddMonitorMsgItem); + FRIEND_TEST(MonitorBufferTest, Operator); +}; + +} // namespace monitor +} // namespace common +} // namespace apollo + +#endif // MODULES_MONITOR_MONITOR_BUFFER_H_ diff --git a/apollo_common/include/apollo_common/status/status.h b/apollo_common/include/apollo_common/status/status.h new file mode 100644 index 0000000..30c6c23 --- /dev/null +++ b/apollo_common/include/apollo_common/status/status.h @@ -0,0 +1,153 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + */ + +#ifndef MODULES_COMMON_STATUS_STATUS_H_ +#define MODULES_COMMON_STATUS_STATUS_H_ + +#include + +#include + +#include "apollo_msgs/proto/common/error_code.pb.h" + +/** + * @namespace apollo::common + * @brief apollo::common + */ +namespace apollo { +namespace common { + +/** + * @class Status + * + * @brief A general class to denote the return status of an API call. It + * can either be an OK status for success, or a failure status with error + * message and error code enum. +*/ +class Status { + public: + /** + * @brief Create a success status. + */ + Status() : code_(ErrorCode::OK), msg_() {} + ~Status() = default; + + /** + * @brief Create a status with the specified error code and msg as a + * human-readable string containing more detailed information. + * @param code the error code. + * @param msg the message associated with the error. + */ + Status(ErrorCode code, const std::string& msg) : code_(code), msg_(msg) {} + + /** + * @brief generate a success status. + * @returns a success status + */ + static Status OK() { return Status(); } + + /** + * @brief check whether the return status is OK. + * @returns true if the code is ErrorCode::OK + * false otherwise + */ + bool ok() const { return code_ == ErrorCode::OK; } + + /** + * @brief get the error code + * @returns the error code + */ + ErrorCode code() const { return code_; } + + /** + * @brief defines the logic of testing if two Status are equal + */ + bool operator==(const Status& rh) const { + return (this->code_ == rh.code_) && (this->msg_ == rh.msg_); + } + + /** + * @brief defines the logic of testing if two Status are unequal + */ + bool operator!=(const Status& rh) const { return !(*this == rh); } + + /** + * @brief returns the error message of the status, empty if the status is + * OK. + * @returns the error message + */ + const std::string& error_message() const { return msg_; } + + /** + * @brief returns a string representation in a readable format. + * @returns the string "OK" if success. + * the internal error message otherwise. + */ + std::string ToString() const { + if (ok()) { + return "OK"; + } + return ErrorCode_Name(code_) + ": " + msg_; + } + + /** + * @brief save the error_code and error message to protobuf + * @param the Status protobuf that will store the message. + */ + void Save(StatusPb* status_pb) { + if (!status_pb) { + return; + } + status_pb->set_error_code(code_); + if (!msg_.empty()) { + status_pb->set_msg(msg_); + } + } + + private: + ErrorCode code_; + std::string msg_; +}; + +inline std::ostream& operator<<(std::ostream& os, const Status& s) { + os << s.ToString(); + return os; +} + +} // namespace common +} // namespace apollo + +#endif // MODULES_COMMON_STATUS_STATUS_H_ diff --git a/apollo_common/include/apollo_common/time/time.h b/apollo_common/include/apollo_common/time/time.h new file mode 100644 index 0000000..8fd8c0a --- /dev/null +++ b/apollo_common/include/apollo_common/time/time.h @@ -0,0 +1,243 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * + * @brief This library provides the utilities to deal with timestamps. + * currently our assumption is that every timestamp will be of a + * precision at 1us. + */ +#ifndef MODULES_COMMON_TIME_TIME_H_ +#define MODULES_COMMON_TIME_TIME_H_ + +#include +#include +#include +#include + +#include "apollo_common/macro.h" + +/** + * @namespace apollo::common::time + * @brief apollo::common::time + */ +namespace apollo { +namespace common { +namespace time { + +/** + * @class Duration + * @brief the default Duration is of precision nanoseconds (1e-9 + * seconds). + */ +using Duration = std::chrono::nanoseconds; + +/** + * @class Timestamp + * @brief the default timestamp uses std::chrono::system_clock. The + * system_clock is a system-wide realtime clock. + */ +using Timestamp = std::chrono::time_point; + +static_assert(std::is_same::value, + "The underlying type of the microseconds should be int64."); + +using nanos = std::chrono::nanoseconds; +using micros = std::chrono::microseconds; +using millis = std::chrono::milliseconds; +using seconds = std::chrono::seconds; +using minutes = std::chrono::minutes; +using hours = std::chrono::hours; + +/** + * @brief converts the input duration (nanos) to a 64 bit integer, with + * the unit specified by PrecisionDuration. + * @param duration the input duration that needs to be converted to + * integer. + * @return an integer representing the duration in the specified unit. + */ +template +int64_t AsInt64(const Duration &duration) { + return std::chrono::duration_cast(duration).count(); +} + +/** + * @brief converts the input timestamp (nanos) to a 64 bit integer, with + * the unit specified by PrecisionDuration. + * @param timestamp the input timestamp that needs to be converted to + * integer. + * @return an integer representing the timestamp in the specified unit. + */ +template +int64_t AsInt64(const Timestamp ×tamp) { + return AsInt64(timestamp.time_since_epoch()); +} + +/** + * @brief converts the input duration (nanos) to a double in seconds. + * The original precision will be preserved. + * @param duration the input duration that needs to be converted. + * @return a doule in seconds. + */ +inline double ToSecond(const Duration &duration) { + return static_cast(AsInt64(duration)) * 1e-9; +} + +/** + * @brief converts the input timestamp (nanos) to a double in seconds. + * The original precision will be preserved. + * @param timestamp the input timestamp that needs to be converted. + * @return a doule representing the same timestamp in seconds. + */ +inline double ToSecond(const Timestamp ×tamp) { + return static_cast(AsInt64(timestamp.time_since_epoch())) * + 1e-9; +} + +/** + * @brief converts the integer-represented timestamp to \class + * Timestamp. + * @return a Timestamp object. + */ +template +inline Timestamp FromInt64(int64_t timestamp_value) { + return Timestamp( + std::chrono::duration_cast(PrecisionDuration(timestamp_value))); +} + +/** + * @brief converts the double to \class Timestamp. The input double has + * a unit of seconds. + * @return a Timestamp object. +*/ + +inline Timestamp From(double timestamp_value) { + int64_t nanos_value = static_cast(timestamp_value * 1e9); + return FromInt64(nanos_value); +} + +/** + * @class Clock + * @brief a singleton clock that can be used to get the current current + * timestamp. The source can be either system clock or a mock clock. + * Mock clock is for testing purpose mainly. The mock clock related + * methods are not thread-safe. + */ +class Clock { + public: + static constexpr int64_t PRECISION = + std::chrono::system_clock::duration::period::den / + std::chrono::system_clock::duration::period::num; + + /// PRECISION >= 1000000 means the precision is at least 1us. + static_assert(PRECISION >= 1000000, + "The precision of the system clock should be at least 1 " + "microsecond."); + + /** + * @brief gets the current timestamp. + * @return a Timestamp object representing the current time. + */ + static Timestamp Now() { + return Clock::instance()->is_system_clock_ ? SystemNow() + : Clock::instance()->mock_now_; + } + + /** + * @brief Set the behavior of the \class Clock. + * @param is_system_clock if provided with value TRUE, further call + * to Now() will return timestamp based on the system clock. If + * provided with FALSE, it will use the mock clock instead. + */ + static void UseSystemClock(bool is_system_clock) { + Clock::instance()->is_system_clock_ = is_system_clock; + } + + /** + * @brief Check whether the \class Clock instance is using system clock. + * @return TRUE if it is using system clock, and FALSE otherwise. + */ + static bool IsSystemClock() { return Clock::instance()->is_system_clock_; } + + /** + * @brief This is for mock clock mode only. It will set the timestamp + * for the mock clock. + */ + static void SetNow(const Duration &duration) { + Clock *clock = Clock::instance(); + if (clock->is_system_clock_) { + throw std::runtime_error("Cannot set now when using system clock!"); + } + clock->mock_now_ = Timestamp(duration); + } + + private: + /** + * @brief constructs the \class Clock instance + * @param is_system_clock See UseSystemClock. + */ + Clock(bool is_system_clock) + : is_system_clock_(is_system_clock), mock_now_(Timestamp()) {} + + /** + * @brief Returns the current timestamp based on the system clock. + * @return the current timestamp based on the system clock. + */ + static Timestamp SystemNow() { + return std::chrono::time_point_cast( + std::chrono::system_clock::now()); + } + + /// NOTE: Unless is_system_clock_ and mock_now_ are guarded by a + /// lock or become atomic, having multiple threads calling mock + /// clock related functions are STRICTLY PROHIBITED. + + /// Indicates whether it is in the system clock mode or the mock + /// clock mode. + bool is_system_clock_; + + /// Stores the currently set timestamp, which serves mock clock + /// queries. + Timestamp mock_now_; + + /// Explicitly disable default and move/copy constructors. + DECLARE_SINGLETON(Clock); +}; + +inline Clock::Clock() : Clock(true) {} + +} // namespace time +} // namespace common +} // namespace apollo + +#endif // MODULES_COMMON_TIME_TIME_H_ diff --git a/apollo_common/include/apollo_common/util/factory.h b/apollo_common/include/apollo_common/util/factory.h new file mode 100644 index 0000000..b9f7452 --- /dev/null +++ b/apollo_common/include/apollo_common/util/factory.h @@ -0,0 +1,120 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the Factory class. + */ + +#ifndef MODULES_COMMON_UTIL_FACTORY_H_ +#define MODULES_COMMON_UTIL_FACTORY_H_ + +#include +#include + +#include "apollo_common/log.h" +#include "apollo_common/macro.h" + +/** + * @namespace apollo::common::util + * @brief apollo::common::util + */ +namespace apollo { +namespace common { +namespace util { + +/** + * @class Factory + * @brief Implements a Factory design pattern with Register and Create methods + * + * The objects created by this factory all implement the same interface + * (namely, AbstractProduct). This design pattern is useful in settings where + * multiple implementations of an interface are available, and one wishes to + * defer the choice of the implementation in use. + * + * @param IdentifierType Type used for identifying the registered classes, + * typically std::string. + * @param AbstractProduct The interface implemented by the registered classes + * @param ProductCreator Function returning a pointer to an instance of + * the registered class + * @param MapContainer Internal implementation of the function mapping + * IdentifierType to ProductCreator, by default std::unordered_map + */ +template > +class Factory { + public: + /** + * @brief Registers the class given by the creator function, linking it to id. + * Registration must happen prior to calling CreateObject. + * @param id Identifier of the class being registered + * @param creator Function returning a pointer to an instance of + * the registered class + * @return True iff the key id is still available + */ + bool Register(const IdentifierType& id, ProductCreator creator) { + return producers_.insert(std::make_pair(id, creator)).second; + } + + /** + * @brief Unregisters the class with the given identifier + * @param id The identifier of the class to be unregistered + */ + bool Unregister(const IdentifierType& id) { + return producers_.erase(id) == 1; + } + + /** + * @brief Creates and transfers membership of an object of type matching id. + * Need to register id before CreateObject is called. + * @param id The identifier of the class we which to instantiate + */ + std::unique_ptr CreateObject(const IdentifierType& id) { + auto id_iter = producers_.find(id); + if (id_iter == producers_.end()) { + AERROR << "Factory could not create Object of type : " << id; + return nullptr; + } else { + return std::unique_ptr((id_iter->second)()); + } + } + + private: + MapContainer producers_; +}; + +} // namespace util +} // namespace common +} // namespace apollo + +#endif // MODULES_COMMON_UTIL_FACTORY_H_ diff --git a/apollo_common/include/apollo_common/util/file.h b/apollo_common/include/apollo_common/util/file.h new file mode 100644 index 0000000..7052e3a --- /dev/null +++ b/apollo_common/include/apollo_common/util/file.h @@ -0,0 +1,180 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + */ + +#ifndef MODULES_COMMON_UTIL_FILE_H_ +#define MODULES_COMMON_UTIL_FILE_H_ + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "apollo_common/log.h" +#include "apollo_common/util/util.h" + +/** + * @namespace apollo::common::util + * @brief apollo::common::util + */ +namespace apollo { +namespace common { +namespace util { + +/** + * @brief Sets the content of the file specified by the file_name to be the + * ascii representation of the input protobuf. + * @param message The proto to output to the specified file. + * @param file_name The name of the target file to set the content. + * @return If the action is successful. + */ +template +bool SetProtoToASCIIFile(const MessageType &message, + const std::string &file_name) { + using google::protobuf::io::ZeroCopyOutputStream; + using google::protobuf::io::FileOutputStream; + using google::protobuf::TextFormat; + int file_descriptor = open(file_name.c_str(), O_WRONLY | O_CREAT, S_IRWXU); + if (file_descriptor < 0) { + // Failed to open; + return false; + } + ZeroCopyOutputStream *output = new FileOutputStream(file_descriptor); + bool success = TextFormat::Print(message, output); + delete output; + close(file_descriptor); + return success; +} + +/** + * @brief Parses the content of the file specified by the file_name as ascii + * representation of protobufs, and merges the parsed content to the + * proto. + * @param file_name The name of the file to parse whose content. + * @param message The proto to carry the parsed content in the specified file. + * @return If the action is successful. + */ +template +bool GetProtoFromASCIIFile(const std::string &file_name, MessageType *message) { + using google::protobuf::io::ZeroCopyInputStream; + using google::protobuf::io::FileInputStream; + using google::protobuf::TextFormat; + int file_descriptor = open(file_name.c_str(), O_RDONLY); + if (file_descriptor < 0) { + // Failed to open; + return false; + } + + ZeroCopyInputStream *input = new FileInputStream(file_descriptor); + bool success = TextFormat::Parse(input, message); + delete input; + close(file_descriptor); + return success; +} + +/** + * @brief Parses the content of the file specified by the file_name as binary + * representation of protobufs, and merges the parsed content to the + * proto. + * @param file_name The name of the file to parse whose content. + * @param message The proto to carry the parsed content in the specified file. + * @return If the action is successful. + */ +template +bool GetProtoFromBinaryFile(const std::string &file_name, + MessageType *message) { + std::fstream input(file_name, std::ios::in | std::ios::binary); + return message->ParseFromIstream(&input); +} + +/** + * @brief Parses the content of the file specified by the file_name as a + * representation of protobufs, and merges the parsed content to the + * proto. + * @param file_name The name of the file to parse whose content. + * @param message The proto to carry the parsed content in the specified file. + * @return If the action is successful. + */ +template +bool GetProtoFromFile(const std::string &file_name, MessageType *message) { + if (EndWith(file_name, ".bin")) { + if (!GetProtoFromBinaryFile(file_name, message) && + !GetProtoFromASCIIFile(file_name, message)) { + return false; + } + } else { + if (!GetProtoFromASCIIFile(file_name, message) && + !GetProtoFromBinaryFile(file_name, message)) { + return false; + } + } + return true; +} +/** + * @brief Check if the directory specified by directory_path exists + * and is indeed a directory. + * @param directory_path Directory path. + * @return If the directory specified by directory_path exists + * and is indeed a directory. + */ +bool DirectoryExists(const std::string &directory_path); + +/** + * @brief Check if a specified directory specified by directory_path exists. + * If not, recursively create the directory (and its parents). + * @param directory_path Directory path. + * @return If the directory does exist or its creation is successful. + */ +bool EnsureDirectory(const std::string &directory_path); + +/** + * @brief Remove all the files under a specified directory. Note that + * sub-directories are NOT affected. + * @param directory_path Directory path. + * @return If the action is successful. + */ +bool RemoveAllFiles(const std::string &directory_path); + +} // namespace util +} // namespace common +} // namespace apollo + +#endif // MODULES_COMMON_UTIL_FILE_H_ diff --git a/apollo_common/include/apollo_common/util/string_tokenizer.h b/apollo_common/include/apollo_common/util/string_tokenizer.h new file mode 100644 index 0000000..eb2bc7e --- /dev/null +++ b/apollo_common/include/apollo_common/util/string_tokenizer.h @@ -0,0 +1,103 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the StringTokenizer class + */ + +#ifndef MODULES_COMMON_UTIL_STRING_TOKENIZER_H_ +#define MODULES_COMMON_UTIL_STRING_TOKENIZER_H_ + +#include +#include + +/** + * @namespace apollo::common::util + * @brief apollo::common::util + */ +namespace apollo { +namespace common { +namespace util { + +/** + * @class StringTokenizer + * @brief Used for splitting strings with respect to given delimiters. + */ +class StringTokenizer { + public: + /** + * @brief Constructor + * @param s String to be split + * @param delims Delimiters where the string should be split + */ + StringTokenizer(const std::string& s, const std::string& delims = " "); + + /** + * Destructor + */ + virtual ~StringTokenizer() = default; + + /** + * @brief Static method; creates a vector with the non-empty tokens obtained + * from splitting. + * @param str String to be split + * @param delims Delimiters where the string should be split + * @return A vector of tokens, each a substring of str + * surrounded by delimiters. + */ + static std::vector Split(const std::string& str, + const std::string& delims); + + /** + * @brief The i-th time Next() is called, it returns the i-th token obtained + * from splitting the string fed to the initializer at the given delimiters; + * once the end is reached, will always return "". + * @return A token, which is a substring of the string fed to the initializer + */ + std::string Next(); + + private: + std::string s_; + + std::string delims_; + + size_t index_; + + size_t last_index_; +}; + +} // namespace util +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_UTIL_STRING_TOKENIZER_H_ */ diff --git a/apollo_common/include/apollo_common/util/util.h b/apollo_common/include/apollo_common/util/util.h new file mode 100644 index 0000000..11b01c8 --- /dev/null +++ b/apollo_common/include/apollo_common/util/util.h @@ -0,0 +1,65 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Some util functions. + */ + +#ifndef MODULES_COMMON_UTIL_H_ +#define MODULES_COMMON_UTIL_H_ + +#include + +/** + * @namespace apollo::common::util + * @brief apollo::common::util + */ +namespace apollo { +namespace common { +namespace util { + +/** + * @brief Check if a string ends with a pattern. + * @param original The original string. To see if it ends with some + * specified pattern. + * @param pattern The target pattern. To see if the original string ends + * with it. + * @return Whether the original string ends with the specified pattern. + */ +bool EndWith(const std::string& original, const std::string& pattern); + +} // namespace util +} // namespace common +} // namespace apollo + +#endif // MODULES_COMMON_UTIL_H_ diff --git a/apollo_common/include/apollo_common/vehicle_state/vehicle_state.h b/apollo_common/include/apollo_common/vehicle_state/vehicle_state.h new file mode 100644 index 0000000..bfcf0a8 --- /dev/null +++ b/apollo_common/include/apollo_common/vehicle_state/vehicle_state.h @@ -0,0 +1,209 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ +/** + * @file vehicle_state.h + * + * @brief Declaration of the class VehicleState. + */ +#ifndef MODULES_COMMON_VEHICLE_STATE_VEHICLE_STATE_H_ +#define MODULES_COMMON_VEHICLE_STATE_VEHICLE_STATE_H_ + +#include "apollo_msgs/proto/canbus/chassis.pb.h" +#include "apollo_msgs/proto/localization/localization.pb.h" + +#include + +/** + * @namespace apollo::common::vehicle_state + * @brief apollo::common::vehicle_state + */ +namespace apollo { +namespace common { +namespace vehicle_state { + +/** + * @class VehicleState + * @brief The class of vehicle state. + * It includes basic information and computation + * about the state of the vehicle. + */ +class VehicleState { + public: + /** + * @brief Empty constructor. + */ + VehicleState() = default; + + /** + * @brief Constructor only by information of localization. + * @param localization Localization information of the vehicle. + */ + explicit VehicleState(const localization::LocalizationEstimate &localization); + + /** + * @brief Constructor by information of localization and chassis. + * @param localization Localization information of the vehicle. + * @param chassis Chassis information of the vehicle. + */ + VehicleState(const localization::LocalizationEstimate *localization, + const canbus::Chassis *chassis); + + /** + * @brief Default destructor. + */ + virtual ~VehicleState() = default; + + /** + * @brief Get the x-coordinate of vehicle position. + * @return The x-coordinate of vehicle position. + */ + double x() const; + + /** + * @brief Get the y-coordinate of vehicle position. + * @return The y-coordinate of vehicle position. + */ + double y() const; + + /** + * @brief Get the z coordinate of vehicle position. + * @return The z coordinate of vehicle position. + */ + double z() const; + + /** + * @brief Get the heading of vehicle position, which is the angle + * between the vehicle's heading direction and the x-axis. + * @return The angle between the vehicle's heading direction + * and the x-axis. + */ + double heading() const; + + /** + * @brief Get the vehicle's linear velocity. + * @return The vehicle's linear velocity. + */ + double linear_velocity() const; + + /** + * @brief Get the vehicle's angular velocity. + * @return The vehicle's angular velocity. + */ + double angular_velocity() const; + + /** + * @brief Get the vehicle's linear acceleration. + * @return The vehicle's linear acceleration. + */ + double linear_acceleration() const; + + /** + * @brief Set the x-coordinate of vehicle position. + * @param x The x-coordinate of vehicle position. + */ + void set_x(const double x); + + /** + * @brief Set the y-coordinate of vehicle position. + * @param y The y-coordinate of vehicle position. + */ + void set_y(const double y); + + /** + * @brief Set the z coordinate of vehicle position. + * @param z The z coordinate of vehicle position. + */ + void set_z(const double z); + + /** + * @brief Set the heading of vehicle position, which is the angle + * between the vehicle's heading direction and the x-axis. + * @param heading The angle between the vehicle's heading direction + * and the x-axis. + */ + void set_heading(const double heading); + + /** + * @brief Set the vehicle's linear velocity. + * @param linear_velocity The value to set the vehicle's linear velocity. + */ + void set_linear_velocity(const double linear_velocity); + + /** + * @brief Set the vehicle's angular velocity. + * @param angular_velocity The vehicle's angular velocity. + */ + void set_angular_velocity(const double angular_velocity); + /** + * @brief Estimate future position from current position and heading, + * along a period of time, by constant linear velocity, + * linear acceleration, angular velocity. + * @param t The length of time period. + * @return The estimated future position in time t. + */ + Eigen::Vector2d EstimateFuturePosition(const double t) const; + + /** + * @brief Compute the position of center of mass(COM) of the vehicle, + * given the distance from rear wheels to the center of mass. + * @param rear_to_com_distance Distance from rear wheels to + * the vehicle's center of mass. + * @return The position of the vehicle's center of mass. + */ + Eigen::Vector2d ComputeCOMPosition(const double rear_to_com_distance) const; + + private: + void ConstructExceptLinearVelocity( + const localization::LocalizationEstimate *localization); + + double x_ = 0.0; + + double y_ = 0.0; + + double z_ = 0.0; + + double heading_ = 0.0; + + double linear_v_ = 0.0; + + double angular_v_ = 0.0; + + double linear_a_ = 0.0; + + const localization::LocalizationEstimate *localization_ptr_ = nullptr; +}; + +} // namespace vehicle_state +} // namespace common +} // namespace apollo + +#endif /* MODULES_COMMON_VEHICLE_STATE_VEHICLE_STATE_H_ */ diff --git a/apollo_common/package.xml b/apollo_common/package.xml new file mode 100644 index 0000000..7e00e75 --- /dev/null +++ b/apollo_common/package.xml @@ -0,0 +1,33 @@ + + + apollo_common + 0.0.0 + The apollo_common package + + forrest + TODO + + catkin + + roscpp + roscpp + roscpp + + tf2_msgs + tf2_msgs + tf2_msgs + + tf2_ros + tf2_ros + tf2_ros + + apollo_msgs + apollo_msgs + apollo_msgs + + + + + + + diff --git a/apollo_common/src/adapters/adapter_gflags.cc b/apollo_common/src/adapters/adapter_gflags.cc new file mode 100644 index 0000000..9acc4bb --- /dev/null +++ b/apollo_common/src/adapters/adapter_gflags.cc @@ -0,0 +1,61 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/adapters/adapter_gflags.h" + +DEFINE_string(adapter_config_path, "", "the file path of adapter config file"); + +DEFINE_bool(enable_adapter_dump, false, + "Whether enable dumping the messages to " + "/tmp/adapters//.txt for debugging " + "purposes."); +DEFINE_string(gps_topic, "/apollo/sensor/gnss/odometry", "GPS topic name"); +DEFINE_string(imu_topic, "/apollo/sensor/gnss/corrected_imu", "IMU topic name"); +DEFINE_string(chassis_topic, "/apollo/canbus/chassis", + "chassis topic name"); +DEFINE_string(chassis_detail_topic, "/apollo/canbus/chassis_detail", + "chassis detail topic name"); +DEFINE_string(localization_topic, "/apollo/localization/pose", + "localization topic name"); +DEFINE_string(planning_trajectory_topic, "/apollo/planning", + "planning trajectory topic name"); +DEFINE_string(monitor_topic, "/apollo/monitor", "ROS topic for monitor"); +DEFINE_string(pad_topic, "/apollo/control/pad", "control pad message topic name"); +DEFINE_string(control_command_topic, "/apollo/control", + "control command topic name"); +DEFINE_string(prediction_topic, "/apollo/prediction", "prediction topic name"); +DEFINE_string(perception_obstacle_topic, "/apollo/perception/obstacles", + "perception obstacle topic name"); +DEFINE_string(traffic_light_detection_topic, + "/apollo/perception/traffic_light", + "traffic light detection topic name"); +DEFINE_string(decision_topic, "/apollo/decision", "decision topic name"); diff --git a/apollo_common/src/adapters/adapter_manager.cc b/apollo_common/src/adapters/adapter_manager.cc new file mode 100644 index 0000000..1dc55bf --- /dev/null +++ b/apollo_common/src/adapters/adapter_manager.cc @@ -0,0 +1,131 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/adapters/adapter_manager.h" + +#include "apollo_common/adapters/adapter_gflags.h" +#include "apollo_common/util/util.h" + +namespace apollo { +namespace common { +namespace adapter { + +AdapterManager::AdapterManager() {} + +void AdapterManager::Observe() { + for (const auto observe : instance()->observers_) { + observe(); + } +} + +void AdapterManager::Init() { Init(FLAGS_adapter_config_path); } + +void AdapterManager::Init(const std::string& adapter_config_filename) { + // Parse config file + AdapterManagerConfig configs; + CHECK( + apollo::common::util::GetProtoFromFile(adapter_config_filename, &configs)) + << "Unable to parse adapter config file " << adapter_config_filename; + AINFO << "Init AdapterManger config:" << configs.DebugString(); + Init(configs); +} + +void AdapterManager::Init(const AdapterManagerConfig& configs) { + if (configs.is_ros()) { + instance()->node_handle_.reset(new ros::NodeHandle()); + } + + for (const auto& config : configs.config()) { + switch (config.type()) { + case AdapterConfig::GPS: + EnableGps(FLAGS_gps_topic, config.mode(), + config.message_history_limit()); + break; + case AdapterConfig::IMU: + EnableImu(FLAGS_imu_topic, config.mode(), + config.message_history_limit()); + break; + case AdapterConfig::CHASSIS: + EnableChassis(FLAGS_chassis_topic, config.mode(), + config.message_history_limit()); + break; + case AdapterConfig::LOCALIZATION: + EnableLocalization(FLAGS_localization_topic, config.mode(), + config.message_history_limit()); + break; + case AdapterConfig::PERCEPTION_OBSTACLES: + EnablePerceptionObstacles(FLAGS_perception_obstacle_topic, + config.mode(), + config.message_history_limit()); + break; + case AdapterConfig::TRAFFIC_LIGHT_DETECTION: + EnableTrafficLightDetection(FLAGS_traffic_light_detection_topic, + config.mode(), + config.message_history_limit()); + case AdapterConfig::PAD: + EnablePad(FLAGS_pad_topic, config.mode(), + config.message_history_limit()); + break; + case AdapterConfig::CONTROL_COMMAND: + EnableControlCommand(FLAGS_control_command_topic, config.mode(), + config.message_history_limit()); + break; + case AdapterConfig::PLANNING_TRAJECTORY: + EnablePlanningTrajectory(FLAGS_planning_trajectory_topic, config.mode(), + config.message_history_limit()); + break; + case AdapterConfig::PREDICTION: + EnablePrediction(FLAGS_prediction_topic, config.mode(), + config.message_history_limit()); + break; + case AdapterConfig::MONITOR: + EnableMonitor(FLAGS_monitor_topic, config.mode(), + config.message_history_limit()); + break; + case AdapterConfig::CHASSIS_DETAIL: + EnableChassisDetail(FLAGS_chassis_detail_topic, config.mode(), + config.message_history_limit()); + break; + case AdapterConfig::DECISION: + EnableDecision(FLAGS_decision_topic, config.mode(), + config.message_history_limit()); + break; + default: + AERROR << "Unknown adapter config type!"; + break; + } + } +} + +} // namespace adapter +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/apollo_app.cc b/apollo_common/src/apollo_app.cc new file mode 100644 index 0000000..0c5f9b6 --- /dev/null +++ b/apollo_common/src/apollo_app.cc @@ -0,0 +1,82 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/apollo_app.h" + +#include +#include + +#include +#include + +#include "apollo_common/log.h" +#include "apollo_common/status/status.h" + +// #include "modules/hmi/utils/hmi_status_helper.h" + +namespace apollo { +namespace common { + +int ApolloApp::Spin() { + ros::AsyncSpinner spinner(1); + auto status = Init(); + if (!status.ok()) { + AERROR << Name() << " Init failed: " << status; + return -1; + } + status = Start(); + if (!status.ok()) { + AERROR << Name() << " Start failed: " << status; + return -2; + } + spinner.start(); + ros::waitForShutdown(); + Stop(); + AINFO << Name() << " exited."; + return 0; +} + +void apollo_app_sigint_handler(int signal_num) { + AINFO << "Received signal: " << signal_num; + if (signal_num != SIGINT) { + return; + } + bool static is_stopping = false; + if (is_stopping) { + return; + } + is_stopping = true; + ros::shutdown(); +} + +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/configs/config_gflags.cc b/apollo_common/src/configs/config_gflags.cc new file mode 100644 index 0000000..8f9610b --- /dev/null +++ b/apollo_common/src/configs/config_gflags.cc @@ -0,0 +1,36 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/configs/config_gflags.h" + +DEFINE_string(vehicle_config_path, "apollo_common/data/mkz_config.pb.txt", + "the file path of vehicle config file"); diff --git a/apollo_common/src/configs/vehicle_config_helper.cc b/apollo_common/src/configs/vehicle_config_helper.cc new file mode 100644 index 0000000..7b65bd5 --- /dev/null +++ b/apollo_common/src/configs/vehicle_config_helper.cc @@ -0,0 +1,64 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/configs/config_gflags.h" +#include "apollo_common/configs/vehicle_config_helper.h" +#include "apollo_common/util/file.h" + +namespace apollo { +namespace common { +namespace config { + +VehicleConfig VehicleConfigHelper::vehicle_config_; + +VehicleConfigHelper::VehicleConfigHelper() {} + +void VehicleConfigHelper::Init() { Init(FLAGS_vehicle_config_path); } + +void VehicleConfigHelper::Init(const std::string& config_file) { + VehicleConfig params; + CHECK(apollo::common::util::GetProtoFromFile(config_file, ¶ms)) + << "Unable to parse adapter config file " << config_file; + Init(params); +} + +void VehicleConfigHelper::Init(const VehicleConfig& vehicle_params) { + vehicle_config_ = vehicle_params; +} + +const VehicleConfig& VehicleConfigHelper::GetConfig() { + return vehicle_config_; +} + +} // namespace config +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/math/aabox2d.cc b/apollo_common/src/math/aabox2d.cc new file mode 100644 index 0000000..7032681 --- /dev/null +++ b/apollo_common/src/math/aabox2d.cc @@ -0,0 +1,173 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/math/aabox2d.h" + +#include +#include +#include + +#include "apollo_common/log.h" +#include "apollo_common/math/math_utils.h" + +namespace apollo { +namespace common { +namespace math { + +AABox2d::AABox2d(const Vec2d& center, const double length, const double width) + : center_(center), + length_(length), + width_(width), + half_length_(length / 2.0), + half_width_(width / 2.0) { + CHECK_GT(length_, -kMathEpsilon); + CHECK_GT(width_, -kMathEpsilon); +} + +AABox2d::AABox2d(const Vec2d& one_corner, const Vec2d& opposite_corner) + : AABox2d((one_corner + opposite_corner) / 2.0, + std::abs(one_corner.x() - opposite_corner.x()), + std::abs(one_corner.y() - opposite_corner.y())) {} + +AABox2d::AABox2d(const std::vector& points) { + CHECK(!points.empty()); + double min_x = points[0].x(); + double max_x = points[0].x(); + double min_y = points[0].y(); + double max_y = points[0].y(); + for (const auto& point : points) { + min_x = std::min(min_x, point.x()); + max_x = std::max(max_x, point.x()); + min_y = std::min(min_y, point.y()); + max_y = std::max(max_y, point.y()); + } + + center_ = {(min_x + max_x) / 2.0, (min_y + max_y) / 2.0}; + length_ = max_x - min_x; + width_ = max_y - min_y; + half_length_ = length_ / 2.0; + half_width_ = width_ / 2.0; +} + +void AABox2d::GetAllCorners(std::vector* const corners) const { + CHECK_NOTNULL(corners)->clear(); + corners->reserve(4); + corners->emplace_back(center_.x() + half_length_, center_.y() - half_width_); + corners->emplace_back(center_.x() + half_length_, center_.y() + half_width_); + corners->emplace_back(center_.x() - half_length_, center_.y() + half_width_); + corners->emplace_back(center_.x() - half_length_, center_.y() - half_width_); +} + +bool AABox2d::IsPointIn(const Vec2d& point) const { + return std::abs(point.x() - center_.x()) <= half_length_ + kMathEpsilon && + std::abs(point.y() - center_.y()) <= half_width_ + kMathEpsilon; +} + +bool AABox2d::IsPointOnBoundary(const Vec2d& point) const { + const double dx = std::abs(point.x() - center_.x()); + const double dy = std::abs(point.y() - center_.y()); + return (std::abs(dx - half_length_) <= kMathEpsilon && + dy <= half_width_ + kMathEpsilon) || + (std::abs(dy - half_width_) <= kMathEpsilon && + dx <= half_length_ + kMathEpsilon); +} + +double AABox2d::DistanceTo(const Vec2d& point) const { + const double dx = std::abs(point.x() - center_.x()) - half_length_; + const double dy = std::abs(point.y() - center_.y()) - half_width_; + if (dx <= 0.0) { + return std::max(0.0, dy); + } + if (dy <= 0.0) { + return dx; + } + return hypot(dx, dy); +} + +double AABox2d::DistanceTo(const AABox2d& box) const { + const double dx = + std::abs(box.center_x() - center_.x()) - box.half_length() - half_length_; + const double dy = + std::abs(box.center_y() - center_.y()) - box.half_width() - half_width_; + if (dx <= 0.0) { + return std::max(0.0, dy); + } + if (dy <= 0.0) { + return dx; + } + return hypot(dx, dy); +} + +bool AABox2d::HasOverlap(const AABox2d& box) const { + return std::abs(box.center_x() - center_.x()) <= + box.half_length() + half_length_ && + std::abs(box.center_y() - center_.y()) <= + box.half_width() + half_width_; +} + +void AABox2d::Shift(const Vec2d& shift_vec) { center_ += shift_vec; } + +void AABox2d::MergeFrom(const AABox2d& other_box) { + const double x1 = std::min(min_x(), other_box.min_x()); + const double x2 = std::max(max_x(), other_box.max_x()); + const double y1 = std::min(min_y(), other_box.min_y()); + const double y2 = std::max(max_y(), other_box.max_y()); + center_ = Vec2d((x1 + x2) / 2.0, (y1 + y2) / 2.0); + length_ = x2 - x1; + width_ = y2 - y1; + half_length_ = length_ / 2.0; + half_width_ = width_ / 2.0; +} + +void AABox2d::MergeFrom(const Vec2d& other_point) { + const double x1 = std::min(min_x(), other_point.x()); + const double x2 = std::max(max_x(), other_point.x()); + const double y1 = std::min(min_y(), other_point.y()); + const double y2 = std::max(max_y(), other_point.y()); + center_ = Vec2d((x1 + x2) / 2.0, (y1 + y2) / 2.0); + length_ = x2 - x1; + width_ = y2 - y1; + half_length_ = length_ / 2.0; + half_width_ = width_ / 2.0; +} + +std::string AABox2d::DebugString() const { + std::ostringstream sout; + sout << "aabox2d ( center = " << center_.DebugString() + << " length = " << length_ << " width = " << width_ << " )"; + sout.flush(); + return sout.str(); +} + +} // namespace math +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/math/angle.cc b/apollo_common/src/math/angle.cc new file mode 100644 index 0000000..a40aa21 --- /dev/null +++ b/apollo_common/src/math/angle.cc @@ -0,0 +1,81 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/math/angle.h" + +#include "apollo_common/math/sin_table.h" + +namespace apollo { +namespace common { +namespace math { + +float sin(Angle16 a) { + auto idx = a.raw(); + if (idx < -Angle16::RAW_PI_2) { + idx += Angle16::RAW_PI; + return -SIN_TABLE[idx % SIN_TABLE_SIZE]; + } + if (idx < 0) { + return -SIN_TABLE[(-idx) % SIN_TABLE_SIZE]; + } + if (idx < Angle16::RAW_PI_2) { + return SIN_TABLE[idx % SIN_TABLE_SIZE]; + } + idx = Angle16::RAW_PI - idx; + return SIN_TABLE[idx % SIN_TABLE_SIZE]; +} + +float cos(Angle16 a) { + Angle16 b(Angle16::RAW_PI_2 - a.raw()); + return sin(b); +} + +float tan(Angle16 a) { return sin(a) / cos(a); } + +float sin(Angle8 a) { + Angle16 b(a.raw() << 8); + return sin(b); +} + +float cos(Angle8 a) { + Angle16 b(a.raw() << 8); + return cos(b); +} + +float tan(Angle8 a) { + Angle16 b(a.raw() << 8); + return tan(b); +} + +} // namespace math +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/math/box2d.cc b/apollo_common/src/math/box2d.cc new file mode 100644 index 0000000..986a095 --- /dev/null +++ b/apollo_common/src/math/box2d.cc @@ -0,0 +1,331 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/math/box2d.h" + +#include +#include +#include +#include + +#include "apollo_common/log.h" +#include "apollo_common/math/math_utils.h" +#include "apollo_common/math/polygon2d.h" + +namespace apollo { +namespace common { +namespace math { +namespace { + +double PtSegDistance(double query_x, double query_y, double start_x, + double start_y, double end_x, double end_y, + double length) { + const double x0 = query_x - start_x; + const double y0 = query_y - start_y; + const double dx = end_x - start_x; + const double dy = end_y - start_y; + const double proj = x0 * dx + y0 * dy; + if (proj <= 0.0) { + return hypot(x0, y0); + } + if (proj >= length * length) { + return hypot(x0 - dx, y0 - dy); + } + return std::abs(x0 * dy - y0 * dx) / length; +} + +} // namespace + +Box2d::Box2d(const Vec2d& center, const double heading, const double length, + const double width) + : center_(center), + length_(length), + width_(width), + half_length_(length / 2.0), + half_width_(width / 2.0), + heading_(heading), + cos_heading_(cos(heading)), + sin_heading_(sin(heading)) { + CHECK_GT(length_, -kMathEpsilon); + CHECK_GT(width_, -kMathEpsilon); +} + +Box2d::Box2d(const LineSegment2d& axis, const double width) + : center_(axis.center()), + length_(axis.length()), + width_(width), + half_length_(axis.length() / 2.0), + half_width_(width / 2.0), + heading_(axis.heading()), + cos_heading_(axis.cos_heading()), + sin_heading_(axis.sin_heading()) { + CHECK_GT(length_, -kMathEpsilon); + CHECK_GT(width_, -kMathEpsilon); +} + +Box2d::Box2d(const AABox2d& aabox) + : center_(aabox.center()), + length_(aabox.length()), + width_(aabox.width()), + half_length_(aabox.half_length()), + half_width_(aabox.half_width()), + heading_(0.0), + cos_heading_(1.0), + sin_heading_(0.0) { + CHECK_GT(length_, -kMathEpsilon); + CHECK_GT(width_, -kMathEpsilon); +} + +Box2d Box2d::CreateAABox(const Vec2d& one_corner, + const Vec2d& opposite_corner) { + const double x1 = std::min(one_corner.x(), opposite_corner.x()); + const double x2 = std::max(one_corner.x(), opposite_corner.x()); + const double y1 = std::min(one_corner.y(), opposite_corner.y()); + const double y2 = std::max(one_corner.y(), opposite_corner.y()); + return Box2d({(x1 + x2) / 2.0, (y1 + y2) / 2.0}, 0.0, x2 - x1, y2 - y1); +} + +void Box2d::GetAllCorners(std::vector* const corners) const { + if (corners == nullptr) { + return; + } + const double dx1 = cos_heading_ * half_length_; + const double dy1 = sin_heading_ * half_length_; + const double dx2 = sin_heading_ * half_width_; + const double dy2 = -cos_heading_ * half_width_; + corners->clear(); + corners->reserve(4); + corners->emplace_back(center_.x() + dx1 + dx2, center_.y() + dy1 + dy2); + corners->emplace_back(center_.x() + dx1 - dx2, center_.y() + dy1 - dy2); + corners->emplace_back(center_.x() - dx1 - dx2, center_.y() - dy1 - dy2); + corners->emplace_back(center_.x() - dx1 + dx2, center_.y() - dy1 + dy2); +} + +bool Box2d::IsPointIn(const Vec2d& point) const { + const double x0 = point.x() - center_.x(); + const double y0 = point.y() - center_.y(); + const double dx = std::abs(x0 * cos_heading_ + y0 * sin_heading_); + const double dy = std::abs(-x0 * sin_heading_ + y0 * cos_heading_); + return dx <= half_length_ + kMathEpsilon && dy <= half_width_ + kMathEpsilon; +} + +bool Box2d::IsPointOnBoundary(const Vec2d& point) const { + const double x0 = point.x() - center_.x(); + const double y0 = point.y() - center_.y(); + const double dx = std::abs(x0 * cos_heading_ + y0 * sin_heading_); + const double dy = std::abs(x0 * sin_heading_ - y0 * cos_heading_); + return (std::abs(dx - half_length_) <= kMathEpsilon && + dy <= half_width_ + kMathEpsilon) || + (std::abs(dy - half_width_) <= kMathEpsilon && + dx <= half_length_ + kMathEpsilon); +} + +double Box2d::DistanceTo(const Vec2d& point) const { + const double x0 = point.x() - center_.x(); + const double y0 = point.y() - center_.y(); + const double dx = + std::abs(x0 * cos_heading_ + y0 * sin_heading_) - half_length_; + const double dy = + std::abs(x0 * sin_heading_ - y0 * cos_heading_) - half_width_; + if (dx <= 0.0) { + return std::max(0.0, dy); + } + if (dy <= 0.0) { + return dx; + } + return hypot(dx, dy); +} + +bool Box2d::HasOverlap(const LineSegment2d& line_segment) const { + if (line_segment.length() <= kMathEpsilon) { + return IsPointIn(line_segment.start()); + } + return DistanceTo(line_segment) <= kMathEpsilon; +} + +double Box2d::DistanceTo(const LineSegment2d& line_segment) const { + if (line_segment.length() <= kMathEpsilon) { + return DistanceTo(line_segment.start()); + } + const double ref_x1 = line_segment.start().x() - center_.x(); + const double ref_y1 = line_segment.start().y() - center_.y(); + double x1 = ref_x1 * cos_heading_ + ref_y1 * sin_heading_; + double y1 = ref_x1 * sin_heading_ - ref_y1 * cos_heading_; + double box_x = half_length_; + double box_y = half_width_; + int gx1 = (x1 >= box_x ? 1 : (x1 <= -box_x ? -1 : 0)); + int gy1 = (y1 >= box_y ? 1 : (y1 <= -box_y ? -1 : 0)); + if (gx1 == 0 && gy1 == 0) { + return 0.0; + } + const double ref_x2 = line_segment.end().x() - center_.x(); + const double ref_y2 = line_segment.end().y() - center_.y(); + double x2 = ref_x2 * cos_heading_ + ref_y2 * sin_heading_; + double y2 = ref_x2 * sin_heading_ - ref_y2 * cos_heading_; + int gx2 = (x2 >= box_x ? 1 : (x2 <= -box_x ? -1 : 0)); + int gy2 = (y2 >= box_y ? 1 : (y2 <= -box_y ? -1 : 0)); + if (gx2 == 0 && gy2 == 0) { + return 0.0; + } + if (gx1 < 0 || (gx1 == 0 && gx2 < 0)) { + x1 = -x1; + gx1 = -gx1; + x2 = -x2; + gx2 = -gx2; + } + if (gy1 < 0 || (gy1 == 0 && gy2 < 0)) { + y1 = -y1; + gy1 = -gy1; + y2 = -y2; + gy2 = -gy2; + } + if (gx1 < gy1 || (gx1 == gy1 && gx2 < gy2)) { + std::swap(x1, y1); + std::swap(gx1, gy1); + std::swap(x2, y2); + std::swap(gx2, gy2); + std::swap(box_x, box_y); + } + if (gx1 == 1 && gy1 == 1) { + switch (gx2 * 3 + gy2) { + case 4: + return PtSegDistance(box_x, box_y, x1, y1, x2, y2, + line_segment.length()); + case 3: + return (x1 > x2) ? (x2 - box_x) + : PtSegDistance(box_x, box_y, x1, y1, x2, y2, + line_segment.length()); + case 2: + return (x1 > x2) ? PtSegDistance(box_x, -box_y, x1, y1, x2, y2, + line_segment.length()) + : PtSegDistance(box_x, box_y, x1, y1, x2, y2, + line_segment.length()); + case -1: + return CrossProd({x1, y1}, {x2, y2}, {box_x, -box_y}) >= 0.0 + ? 0.0 + : PtSegDistance(box_x, -box_y, x1, y1, x2, y2, + line_segment.length()); + case -4: + return CrossProd({x1, y1}, {x2, y2}, {box_x, -box_y}) <= 0.0 + ? PtSegDistance(box_x, -box_y, x1, y1, x2, y2, + line_segment.length()) + : (CrossProd({x1, y1}, {x2, y2}, {-box_x, box_y}) <= 0.0 + ? 0.0 + : PtSegDistance(-box_x, box_y, x1, y1, x2, y2, + line_segment.length())); + } + } else { + switch (gx2 * 3 + gy2) { + case 4: + return (x1 < x2) ? (x1 - box_x) + : PtSegDistance(box_x, box_y, x1, y1, x2, y2, + line_segment.length()); + case 3: + return std::min(x1, x2) - box_x; + case 1: + case -2: + return CrossProd({x1, y1}, {x2, y2}, {box_x, box_y}) <= 0.0 + ? 0.0 + : PtSegDistance(box_x, box_y, x1, y1, x2, y2, + line_segment.length()); + case -3: + return 0.0; + } + } + CHECK(0) << "unimplemented state: " << gx1 << " " << gy1 << " " << gx2 << " " + << gy2; + return 0.0; +} + +double Box2d::DistanceTo(const Box2d& box) const { + return Polygon2d(box).DistanceTo(*this); +} + +bool Box2d::HasOverlap(const Box2d& box) const { + const double shift_x = box.center_x() - center_.x(); + const double shift_y = box.center_y() - center_.y(); + + const double dx1 = cos_heading_ * half_length_; + const double dy1 = sin_heading_ * half_length_; + const double dx2 = sin_heading_ * half_width_; + const double dy2 = -cos_heading_ * half_width_; + const double dx3 = box.cos_heading() * box.half_length(); + const double dy3 = box.sin_heading() * box.half_length(); + const double dx4 = box.sin_heading() * box.half_width(); + const double dy4 = -box.cos_heading() * box.half_width(); + + return std::abs(shift_x * cos_heading_ + shift_y * sin_heading_) <= + std::abs(dx3 * cos_heading_ + dy3 * sin_heading_) + + std::abs(dx4 * cos_heading_ + dy4 * sin_heading_) + + half_length_ && + std::abs(shift_x * sin_heading_ - shift_y * cos_heading_) <= + std::abs(dx3 * sin_heading_ - dy3 * cos_heading_) + + std::abs(dx4 * sin_heading_ - dy4 * cos_heading_) + + half_width_ && + std::abs(shift_x * box.cos_heading() + shift_y * box.sin_heading()) <= + std::abs(dx1 * box.cos_heading() + dy1 * box.sin_heading()) + + std::abs(dx2 * box.cos_heading() + dy2 * box.sin_heading()) + + box.half_length() && + std::abs(shift_x * box.sin_heading() - shift_y * box.cos_heading()) <= + std::abs(dx1 * box.sin_heading() - dy1 * box.cos_heading()) + + std::abs(dx2 * box.sin_heading() - dy2 * box.cos_heading()) + + box.half_width(); +} + +AABox2d Box2d::GetAABox() const { + const double dx1 = std::abs(cos_heading_ * half_length_); + const double dy1 = std::abs(sin_heading_ * half_length_); + const double dx2 = std::abs(sin_heading_ * half_width_); + const double dy2 = std::abs(cos_heading_ * half_width_); + return AABox2d(center_, (dx1 + dx2) * 2.0, (dy1 + dy2) * 2.0); +} + +void Box2d::RotateFromCenter(const double rotate_angle) { + heading_ = NormalizeAngle(heading_ + rotate_angle); + cos_heading_ = std::cos(heading_); + sin_heading_ = std::sin(heading_); +} + +void Box2d::Shift(const Vec2d& shift_vec) { center_ += shift_vec; } + +std::string Box2d::DebugString() const { + std::ostringstream sout; + sout << "box2d ( center = " << center_.DebugString() + << " heading = " << heading_ << " length = " << length_ + << " width = " << width_ << " )"; + sout.flush(); + return sout.str(); +} + +} // namespace math +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/math/integral.cc b/apollo_common/src/math/integral.cc new file mode 100644 index 0000000..e45e7d9 --- /dev/null +++ b/apollo_common/src/math/integral.cc @@ -0,0 +1,69 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/math/integral.h" + +namespace apollo { +namespace common { +namespace math { + +double GaussLegendre(const std::function& func, + const double lower_bound, + const double upper_bound) { + double t = (upper_bound - lower_bound) * 0.5; + double m = (upper_bound + lower_bound) * 0.5; + + std::array w; + w[0] = 0.5688888889; + w[1] = 0.4786286705; + w[2] = 0.4786286705; + w[3] = 0.2369268851; + w[4] = 0.2369268851; + + std::array x; + x[0] = 0.0; + x[1] = 0.5384693101; + x[2] = -0.5384693101; + x[3] = 0.9061798459; + x[4] = -0.9061798459; + + double integral = 0.0; + for (size_t i = 0; i < 5; ++i) { + integral += w[i] * func(t * x[i] + m); + } + + return integral * t; +} + +} // namespace math +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/math/line_segment2d.cc b/apollo_common/src/math/line_segment2d.cc new file mode 100644 index 0000000..e2cb6db --- /dev/null +++ b/apollo_common/src/math/line_segment2d.cc @@ -0,0 +1,241 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/math/line_segment2d.h" + +#include +#include +#include +#include + +#include "apollo_common/log.h" +#include "apollo_common/math/math_utils.h" + +namespace apollo { +namespace common { +namespace math { +namespace { + +bool IsWithin(double val, double bound1, double bound2) { + if (bound1 > bound2) { + std::swap(bound1, bound2); + } + return val >= bound1 - kMathEpsilon && val <= bound2 + kMathEpsilon; +} + +} // namespace + +LineSegment2d::LineSegment2d() { unit_direction_ = Vec2d(1, 0); } + +LineSegment2d::LineSegment2d(const Vec2d& start, const Vec2d& end) + : start_(start), end_(end) { + const double dx = end_.x() - start_.x(); + const double dy = end_.y() - start_.y(); + length_ = hypot(dx, dy); + unit_direction_ = + (length_ <= kMathEpsilon ? Vec2d(0, 0) + : Vec2d(dx / length_, dy / length_)); + heading_ = unit_direction_.Angle(); +} + +double LineSegment2d::length() const { return length_; } + +double LineSegment2d::length_sqr() const { return length_ * length_; } + +double LineSegment2d::DistanceTo(const Vec2d& point) const { + if (length_ <= kMathEpsilon) { + return point.DistanceTo(start_); + } + const double x0 = point.x() - start_.x(); + const double y0 = point.y() - start_.y(); + const double proj = x0 * unit_direction_.x() + y0 * unit_direction_.y(); + if (proj <= 0.0) { + return hypot(x0, y0); + } + if (proj >= length_) { + return point.DistanceTo(end_); + } + return std::abs(x0 * unit_direction_.y() - y0 * unit_direction_.x()); +} + +double LineSegment2d::DistanceTo(const Vec2d& point, + Vec2d* const nearest_pt) const { + CHECK_NOTNULL(nearest_pt); + if (length_ <= kMathEpsilon) { + *nearest_pt = start_; + return point.DistanceTo(start_); + } + const double x0 = point.x() - start_.x(); + const double y0 = point.y() - start_.y(); + const double proj = x0 * unit_direction_.x() + y0 * unit_direction_.y(); + if (proj < 0.0) { + *nearest_pt = start_; + return hypot(x0, y0); + } + if (proj > length_) { + *nearest_pt = end_; + return point.DistanceTo(end_); + } + *nearest_pt = start_ + unit_direction_ * proj; + return std::abs(x0 * unit_direction_.y() - y0 * unit_direction_.x()); +} + +double LineSegment2d::DistanceSquareTo(const Vec2d& point) const { + if (length_ <= kMathEpsilon) { + return point.DistanceSquareTo(start_); + } + const double x0 = point.x() - start_.x(); + const double y0 = point.y() - start_.y(); + const double proj = x0 * unit_direction_.x() + y0 * unit_direction_.y(); + if (proj <= 0.0) { + return Square(x0) + Square(y0); + } + if (proj >= length_) { + return point.DistanceSquareTo(end_); + } + return Square(x0 * unit_direction_.y() - y0 * unit_direction_.x()); +} + +double LineSegment2d::DistanceSquareTo(const Vec2d& point, + Vec2d* const nearest_pt) const { + CHECK_NOTNULL(nearest_pt); + if (length_ <= kMathEpsilon) { + *nearest_pt = start_; + return point.DistanceSquareTo(start_); + } + const double x0 = point.x() - start_.x(); + const double y0 = point.y() - start_.y(); + const double proj = x0 * unit_direction_.x() + y0 * unit_direction_.y(); + if (proj <= 0.0) { + *nearest_pt = start_; + return Square(x0) + Square(y0); + } + if (proj >= length_) { + *nearest_pt = end_; + return point.DistanceSquareTo(end_); + } + *nearest_pt = start_ + unit_direction_ * proj; + return Square(x0 * unit_direction_.y() - y0 * unit_direction_.x()); +} + +bool LineSegment2d::IsPointIn(const Vec2d& point) const { + if (length_ <= kMathEpsilon) { + return std::abs(point.x() - start_.x()) <= kMathEpsilon && + std::abs(point.y() - start_.y()) <= kMathEpsilon; + } + const double prod = CrossProd(point, start_, end_); + if (std::abs(prod) > kMathEpsilon) { + return false; + } + return IsWithin(point.x(), start_.x(), end_.x()) && + IsWithin(point.y(), start_.y(), end_.y()); +} + +double LineSegment2d::ProjectOntoUnit(const Vec2d& point) const { + return unit_direction_.InnerProd(point - start_); +} + +double LineSegment2d::ProductOntoUnit(const Vec2d& point) const { + return unit_direction_.CrossProd(point - start_); +} + +bool LineSegment2d::HasIntersect(const LineSegment2d& other_segment) const { + Vec2d point; + return GetIntersect(other_segment, &point); +} + +bool LineSegment2d::GetIntersect(const LineSegment2d& other_segment, + Vec2d* const point) const { + CHECK_NOTNULL(point); + if (IsPointIn(other_segment.start())) { + *point = other_segment.start(); + return true; + } + if (IsPointIn(other_segment.end())) { + *point = other_segment.end(); + return true; + } + if (other_segment.IsPointIn(start_)) { + *point = start_; + return true; + } + if (other_segment.IsPointIn(end_)) { + *point = end_; + return true; + } + if (length_ <= kMathEpsilon || other_segment.length() <= kMathEpsilon) { + return false; + } + const double cc1 = CrossProd(start_, end_, other_segment.start()); + const double cc2 = CrossProd(start_, end_, other_segment.end()); + if (cc1 * cc2 >= -kMathEpsilon) { + return false; + } + const double cc3 = + CrossProd(other_segment.start(), other_segment.end(), start_); + const double cc4 = + CrossProd(other_segment.start(), other_segment.end(), end_); + if (cc3 * cc4 >= -kMathEpsilon) { + return false; + } + const double ratio = cc4 / (cc4 - cc3); + *point = Vec2d(start_.x() * ratio + end_.x() * (1.0 - ratio), + start_.y() * ratio + end_.y() * (1.0 - ratio)); + return true; +} + +// return distance with perpendicular foot point. +double LineSegment2d::GetPerpendicularFoot(const Vec2d& point, + Vec2d* const foot_point) const { + CHECK_NOTNULL(foot_point); + if (length_ <= kMathEpsilon) { + *foot_point = start_; + return point.DistanceTo(start_); + } + const double x0 = point.x() - start_.x(); + const double y0 = point.y() - start_.y(); + const double proj = x0 * unit_direction_.x() + y0 * unit_direction_.y(); + *foot_point = start_ + unit_direction_ * proj; + return std::abs(x0 * unit_direction_.y() - y0 * unit_direction_.x()); +} + +std::string LineSegment2d::DebugString() const { + std::ostringstream sout; + sout << "segment2d ( start = " << start_.DebugString() + << " end = " << end_.DebugString() << " )"; + sout.flush(); + return sout.str(); +} + +} // namespace math +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/math/linear_interpolation.cc b/apollo_common/src/math/linear_interpolation.cc new file mode 100644 index 0000000..b4d8982 --- /dev/null +++ b/apollo_common/src/math/linear_interpolation.cc @@ -0,0 +1,84 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/math/linear_interpolation.h" + +#include + +#include "apollo_common/log.h" +#include "apollo_common/math/math_utils.h" + +namespace apollo { +namespace common { +namespace math { + +double lerp(const double x0, const double t0, const double x1, const double t1, + const double t) { + if (std::abs(t1 - t0) <= kMathEpsilon) { + AERROR << "input time difference is too small"; + return x0; + } + double r = (t - t0) / (t1 - t0); + double x = x0 + r * (x1 - x0); + return x; +} + +void lerp(const double x0, const double y0, const double t0, const double x1, + const double y1, const double t1, const double t, double* x, + double* y) { + *x = lerp(x0, t0, x1, t1, t); + *y = lerp(y0, t0, y1, t1, t); +} + +double slerp(const double a0, const double t0, const double a1, const double t1, + const double t) { + if (std::abs(t1 - t0) <= kMathEpsilon) { + AERROR << "input time difference is too small"; + return NormalizeAngle(a0); + } + double a0_n = NormalizeAngle(a0); + double a1_n = NormalizeAngle(a1); + double d = a1_n - a0_n; + if (d > M_PI) { + d = d - 2 * M_PI; + } else if (d < -M_PI) { + d = d + 2 * M_PI; + } + + double r = (t - t0) / (t1 - t0); + double a = a0_n + d * r; + return NormalizeAngle(a); +} + +} // namespace math +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/math/linear_quadratic_regulator.cc b/apollo_common/src/math/linear_quadratic_regulator.cc new file mode 100644 index 0000000..041ed74 --- /dev/null +++ b/apollo_common/src/math/linear_quadratic_regulator.cc @@ -0,0 +1,90 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ +#include "apollo_common/math/linear_quadratic_regulator.h" + +#include + +#include "apollo_common/log.h" + +namespace apollo { +namespace common { +namespace math { + +using Matrix = Eigen::MatrixXd; + +void SolveLQRProblem(const Matrix &A, const Matrix &B, + const Matrix &Q, const Matrix &R, + const double tolerance, const uint max_num_iteration, + Matrix *ptr_K) { + if (A.rows() != A.cols() || + B.rows() != A.rows() || + Q.rows() != Q.cols() || + Q.rows() != A.rows() || + R.rows() != R.cols() || + R.rows() != B.cols()) { + AERROR << "One or more matrices have incompatible dimensions."; + return; + } + + Matrix AT = A.transpose(); + Matrix BT = B.transpose(); + + // Solves a discrete-time Algebraic Riccati equation (DARE) + // Calculate Matrix Difference Riccati Equation, initialize P and Q + Matrix P = Q; + uint num_iteration = 0; + double diff = 0.0; + while (num_iteration++ < max_num_iteration) { + Matrix P_next = AT * P * A - + AT * P * B * (R + BT * P * B).inverse() * BT * P * A + + Q; + // check the difference between P and P_next + diff = fabs((P_next - P).maxCoeff()); + P = P_next; + + if (diff < tolerance) { + break; + } + } + + if (num_iteration >= max_num_iteration) { + AWARN << "lqr_not_convergence, last_diff_is:" << diff; + } else { + ADEBUG << "Number of iterations until convergence: " << num_iteration + << ", max difference: " << diff; + } + *ptr_K = (R + BT * P * B).inverse() * BT * P * A; +} + +} // namespace math +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/math/math_utils.cc b/apollo_common/src/math/math_utils.cc new file mode 100644 index 0000000..902b1ea --- /dev/null +++ b/apollo_common/src/math/math_utils.cc @@ -0,0 +1,99 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/math/math_utils.h" + +#include + +#include + +namespace apollo { +namespace common { +namespace math { + +double CrossProd(const Vec2d& start_point, const Vec2d& end_point_1, + const Vec2d& end_point_2) { + return (end_point_1 - start_point).CrossProd(end_point_2 - start_point); +} + +double InnerProd(const Vec2d& start_point, const Vec2d& end_point_1, + const Vec2d& end_point_2) { + return (end_point_1 - start_point).InnerProd(end_point_2 - start_point); +} + +double CrossProd(const double x0, const double y0, const double x1, + const double y1) { + return x0 * y1 - x1 * y0; +} + +double InnerProd(const double x0, const double y0, const double x1, + const double y1) { + return x0 * x1 + y0 * y1; +} + +double WrapAngle(const double angle) { + const double new_angle = std::fmod(angle, M_PI * 2.0); + return new_angle < 0 ? new_angle + M_PI * 2.0 : new_angle; +} + +double NormalizeAngle(const double angle) { + const double new_angle = std::fmod(angle + M_PI, M_PI * 2.0); + return (new_angle < 0 ? new_angle + M_PI * 2.0 : new_angle) - M_PI; +} + +int RandomInt(const int s, const int t, unsigned int rand_seed) { + if (s >= t) { + return s; + } + return s + rand_r(&rand_seed) % (t - s + 1); +} + +double RandomDouble(const double s, const double t, unsigned int rand_seed) { + return s + (t - s) / 16383.0 * (rand_r(&rand_seed) & 16383); +} + +int double_compare(const double d1, const double d2, const double epsilon) { + DCHECK(!std::isnan(d1)); + DCHECK(!std::isnan(d2)); + + if ((d1 - d2) > std::fmax(std::fabs(d1), std::fabs(d2)) * epsilon) { + return 1; + } else if ((d2 - d1) > std::fmax(std::fabs(d1), std::fabs(d2)) * epsilon) { + return -1; + } else { + return 0; + } +} + +} // namespace math +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/math/polygon2d.cc b/apollo_common/src/math/polygon2d.cc new file mode 100644 index 0000000..5f96566 --- /dev/null +++ b/apollo_common/src/math/polygon2d.cc @@ -0,0 +1,610 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/math/polygon2d.h" + +#include +#include +#include +#include +#include + +#include "apollo_common/log.h" +#include "apollo_common/math/math_utils.h" + +namespace apollo { +namespace common { +namespace math { + +Polygon2d::Polygon2d(const Box2d& box) { + box.GetAllCorners(&points_); + BuildFromPoints(); +} + +Polygon2d::Polygon2d(std::vector points) : points_(std::move(points)) { + BuildFromPoints(); +} + +double Polygon2d::DistanceTo(const Vec2d& point) const { + CHECK_GE(points_.size(), 3); + if (IsPointIn(point)) { + return 0.0; + } + double distance = std::numeric_limits::infinity(); + for (int i = 0; i < num_points_; ++i) { + distance = std::min(distance, line_segments_[i].DistanceTo(point)); + } + return distance; +} + +double Polygon2d::DistanceSquareTo(const Vec2d& point) const { + CHECK_GE(points_.size(), 3); + if (IsPointIn(point)) { + return 0.0; + } + double distance_sqr = std::numeric_limits::infinity(); + for (int i = 0; i < num_points_; ++i) { + distance_sqr = + std::min(distance_sqr, line_segments_[i].DistanceSquareTo(point)); + } + return distance_sqr; +} + +double Polygon2d::DistanceTo(const LineSegment2d& line_segment) const { + if (line_segment.length() <= kMathEpsilon) { + return DistanceTo(line_segment.start()); + } + CHECK_GE(points_.size(), 3); + if (IsPointIn(line_segment.center())) { + return 0.0; + } + if (std::any_of(line_segments_.begin(), line_segments_.end(), + [&](const LineSegment2d& poly_seg) { + return poly_seg.HasIntersect(line_segment); + })) { + return 0.0; + } + + double distance = std::min(DistanceTo(line_segment.start()), + DistanceTo(line_segment.end())); + for (int i = 0; i < num_points_; ++i) { + distance = std::min(distance, line_segment.DistanceTo(points_[i])); + } + return distance; +} + +double Polygon2d::DistanceTo(const Box2d& box) const { + CHECK_GE(points_.size(), 3); + return DistanceTo(Polygon2d(box)); +} + +double Polygon2d::DistanceTo(const Polygon2d& polygon) const { + CHECK_GE(points_.size(), 3); + CHECK_GE(polygon.num_points(), 3); + + if (IsPointIn(polygon.points()[0])) { + return 0.0; + } + if (polygon.IsPointIn(points_[0])) { + return 0.0; + } + double distance = std::numeric_limits::infinity(); + for (int i = 0; i < num_points_; ++i) { + distance = std::min(distance, polygon.DistanceTo(line_segments_[i])); + } + return distance; +} + +double Polygon2d::DistanceToBoundary(const Vec2d& point) const { + double distance = std::numeric_limits::infinity(); + for (int i = 0; i < num_points_; ++i) { + distance = std::min(distance, line_segments_[i].DistanceTo(point)); + } + return distance; +} + +bool Polygon2d::IsPointOnBoundary(const Vec2d& point) const { + CHECK_GE(points_.size(), 3); + return std::any_of( + line_segments_.begin(), line_segments_.end(), + [&](const LineSegment2d& poly_seg) { return poly_seg.IsPointIn(point); }); +} + +bool Polygon2d::IsPointIn(const Vec2d& point) const { + CHECK_GE(points_.size(), 3); + if (IsPointOnBoundary(point)) { + return true; + } + int j = num_points_ - 1; + int c = 0; + for (int i = 0; i < num_points_; ++i) { + if ((points_[i].y() > point.y()) != (points_[j].y() > point.y())) { + const double side = CrossProd(point, points_[i], points_[j]); + if (points_[i].y() < points_[j].y() ? side > 0.0 : side < 0.0) { + ++c; + } + } + j = i; + } + return c & 1; +} + +bool Polygon2d::HasOverlap(const Polygon2d& polygon) const { + CHECK_GE(points_.size(), 3); + return DistanceTo(polygon) <= kMathEpsilon; +} + +bool Polygon2d::IsContain(const LineSegment2d& line_segment) const { + if (line_segment.length() <= kMathEpsilon) { + return IsPointIn(line_segment.start()); + } + CHECK_GE(points_.size(), 3); + if (!IsPointIn(line_segment.start())) { + return false; + } + if (!IsPointIn(line_segment.end())) { + return false; + } + if (!is_convex_) { + std::vector overlaps = GetAllOverlaps(line_segment); + double total_length = 0; + for (const auto& overlap_seg : overlaps) { + total_length += overlap_seg.length(); + } + return total_length >= line_segment.length() - kMathEpsilon; + } + return true; +} + +bool Polygon2d::IsContain(const Polygon2d& polygon) const { + CHECK_GE(points_.size(), 3); + if (area_ < polygon.area() - kMathEpsilon) { + return false; + } + if (!IsPointIn(polygon.points()[0])) { + return false; + } + const auto& line_segments = polygon.line_segments(); + return std::all_of(line_segments.begin(), line_segments.end(), + [&](const LineSegment2d& line_segment) { + return IsContain(line_segment); + }); +} + +int Polygon2d::Next(int at) const { return at >= num_points_ - 1 ? 0 : at + 1; } + +int Polygon2d::Prev(int at) const { return at == 0 ? num_points_ - 1 : at - 1; } + +void Polygon2d::BuildFromPoints() { + num_points_ = points_.size(); + CHECK_GE(num_points_, 3); + + // Make sure the points are in ccw order. + area_ = 0.0; + for (int i = 1; i < num_points_; ++i) { + area_ += CrossProd(points_[0], points_[i - 1], points_[i]); + } + if (area_ < 0) { + area_ = -area_; + std::reverse(points_.begin(), points_.end()); + } + area_ /= 2.0; + CHECK_GT(area_, kMathEpsilon); + + // Construct line_segments. + line_segments_.reserve(num_points_); + for (int i = 0; i < num_points_; ++i) { + line_segments_.emplace_back(points_[i], points_[Next(i)]); + } + + // Check convexity. + is_convex_ = true; + for (int i = 0; i < num_points_; ++i) { + if (CrossProd(points_[Prev(i)], points_[i], points_[Next(i)]) <= + -kMathEpsilon) { + is_convex_ = false; + break; + } + } + + // Compute aabox. + min_x_ = points_[0].x(); + max_x_ = points_[0].x(); + min_y_ = points_[0].y(); + max_y_ = points_[0].y(); + for (const auto& point : points_) { + min_x_ = std::min(min_x_, point.x()); + max_x_ = std::max(max_x_, point.x()); + min_y_ = std::min(min_y_, point.y()); + max_y_ = std::max(max_y_, point.y()); + } +} + +bool Polygon2d::ComputeConvexHull(const std::vector& points, + Polygon2d* const polygon) { + CHECK_NOTNULL(polygon); + const int n = points.size(); + if (n < 3) { + return false; + } + std::vector sorted_indices(n); + for (int i = 0; i < n; ++i) { + sorted_indices[i] = i; + } + std::sort(sorted_indices.begin(), sorted_indices.end(), + [&](const int idx1, const int idx2) { + const Vec2d& pt1 = points[idx1]; + const Vec2d& pt2 = points[idx2]; + const double dx = pt1.x() - pt2.x(); + if (std::abs(dx) > kMathEpsilon) { + return dx < 0.0; + } + return pt1.y() < pt2.y(); + }); + int count = 0; + std::vector results; + results.reserve(n); + int last_count = 1; + for (int i = 0; i < n + n; ++i) { + if (i == n) { + last_count = count; + } + const int idx = sorted_indices[(i < n) ? i : (n + n - 1 - i)]; + const Vec2d& pt = points[idx]; + while (count > last_count && + CrossProd(points[results[count - 2]], points[results[count - 1]], + pt) <= kMathEpsilon) { + results.pop_back(); + --count; + } + results.push_back(idx); + ++count; + } + --count; + if (count < 3) { + return false; + } + std::vector result_points; + result_points.reserve(count); + for (int i = 0; i < count; ++i) { + result_points.push_back(points[results[i]]); + } + *polygon = Polygon2d(result_points); + return true; +} + +bool Polygon2d::ClipConvexHull(const LineSegment2d& line_segment, + std::vector* const points) { + if (line_segment.length() <= kMathEpsilon) { + return true; + } + CHECK_NOTNULL(points); + const int n = points->size(); + if (n < 3) { + return false; + } + std::vector prod(n); + std::vector side(n); + for (int i = 0; i < n; ++i) { + prod[i] = CrossProd(line_segment.start(), line_segment.end(), (*points)[i]); + if (std::abs(prod[i]) <= kMathEpsilon) { + side[i] = 0; + } else { + side[i] = ((prod[i] < 0) ? -1 : 1); + } + } + + std::vector new_points; + for (int i = 0; i < n; ++i) { + if (side[i] >= 0) { + new_points.push_back((*points)[i]); + } + const int j = ((i == n - 1) ? 0 : (i + 1)); + if (side[i] * side[j] < 0) { + const double ratio = prod[j] / (prod[j] - prod[i]); + new_points.emplace_back( + (*points)[i].x() * ratio + (*points)[j].x() * (1.0 - ratio), + (*points)[i].y() * ratio + (*points)[j].y() * (1.0 - ratio)); + } + } + + points->swap(new_points); + return points->size() >= 3; +} + +bool Polygon2d::ComputeOverlap(const Polygon2d& other_polygon, + Polygon2d* const overlap_polygon) const { + CHECK_GE(points_.size(), 3); + CHECK_NOTNULL(overlap_polygon); + CHECK(is_convex_ && other_polygon.is_convex()); + std::vector points = other_polygon.points(); + for (int i = 0; i < num_points_; ++i) { + if (!ClipConvexHull(line_segments_[i], &points)) { + return false; + } + } + return ComputeConvexHull(points, overlap_polygon); +} + +bool Polygon2d::HasOverlap(const LineSegment2d& line_segment) const { + CHECK_GE(points_.size(), 3); + Vec2d first; + Vec2d last; + return GetOverlap(line_segment, &first, &last); +} + +bool Polygon2d::GetOverlap(const LineSegment2d& line_segment, + Vec2d* const first, Vec2d* const last) const { + CHECK_GE(points_.size(), 3); + CHECK_NOTNULL(first); + CHECK_NOTNULL(last); + + if (line_segment.length() <= kMathEpsilon) { + if (!IsPointIn(line_segment.start())) { + return false; + } + *first = line_segment.start(); + *last = line_segment.start(); + return true; + } + + double min_proj = line_segment.length(); + double max_proj = 0; + if (IsPointIn(line_segment.start())) { + *first = line_segment.start(); + min_proj = 0.0; + } + if (IsPointIn(line_segment.end())) { + *last = line_segment.end(); + max_proj = line_segment.length(); + } + for (const auto& poly_seg : line_segments_) { + Vec2d pt; + if (poly_seg.GetIntersect(line_segment, &pt)) { + const double proj = line_segment.ProjectOntoUnit(pt); + if (proj < min_proj) { + min_proj = proj; + *first = pt; + } + if (proj > max_proj) { + max_proj = proj; + *last = pt; + } + } + } + return min_proj <= max_proj + kMathEpsilon; +} + +std::vector Polygon2d::GetAllOverlaps( + const LineSegment2d& line_segment) const { + CHECK_GE(points_.size(), 3); + + if (line_segment.length() <= kMathEpsilon) { + std::vector overlaps; + if (IsPointIn(line_segment.start())) { + overlaps.push_back(line_segment); + } + return overlaps; + } + std::vector projections; + if (IsPointIn(line_segment.start())) { + projections.push_back(0.0); + } + if (IsPointIn(line_segment.end())) { + projections.push_back(line_segment.length()); + } + for (const auto& poly_seg : line_segments_) { + Vec2d pt; + if (poly_seg.GetIntersect(line_segment, &pt)) { + projections.push_back(line_segment.ProjectOntoUnit(pt)); + } + } + std::sort(projections.begin(), projections.end()); + std::vector> overlaps; + for (size_t i = 0; i + 1 < projections.size(); ++i) { + const double start_proj = projections[i]; + const double end_proj = projections[i + 1]; + if (end_proj - start_proj <= kMathEpsilon) { + continue; + } + const Vec2d reference_point = + line_segment.start() + + (start_proj + end_proj) / 2.0 * line_segment.unit_direction(); + if (!IsPointIn(reference_point)) { + continue; + } + if (overlaps.empty() || + start_proj > overlaps.back().second + kMathEpsilon) { + overlaps.emplace_back(start_proj, end_proj); + } else { + overlaps.back().second = end_proj; + } + } + std::vector overlap_line_segments; + for (const auto& overlap : overlaps) { + overlap_line_segments.emplace_back( + line_segment.start() + overlap.first * line_segment.unit_direction(), + line_segment.start() + overlap.second * line_segment.unit_direction()); + } + return overlap_line_segments; +} + +void Polygon2d::ExtremePoints(const double heading, Vec2d* const first, + Vec2d* const last) const { + CHECK_GE(points_.size(), 3); + CHECK_NOTNULL(first); + CHECK_NOTNULL(last); + + const Vec2d direction_vec = Vec2d::CreateUnitVec2d(heading); + double min_proj = std::numeric_limits::infinity(); + double max_proj = -std::numeric_limits::infinity(); + for (const auto& pt : points_) { + const double proj = pt.InnerProd(direction_vec); + if (proj < min_proj) { + min_proj = proj; + *first = pt; + } + if (proj > max_proj) { + max_proj = proj; + *last = pt; + } + } +} + +AABox2d Polygon2d::AABoundingBox() const { + return AABox2d({min_x_, min_y_}, {max_x_, max_y_}); +} + +Box2d Polygon2d::BoundingBoxWithHeading(const double heading) const { + CHECK_GE(points_.size(), 3); + const Vec2d direction_vec = Vec2d::CreateUnitVec2d(heading); + Vec2d px1; + Vec2d px2; + Vec2d py1; + Vec2d py2; + ExtremePoints(heading, &px1, &px2); + ExtremePoints(heading - M_PI_2, &py1, &py2); + const double x1 = px1.InnerProd(direction_vec); + const double x2 = px2.InnerProd(direction_vec); + const double y1 = py1.CrossProd(direction_vec); + const double y2 = py2.CrossProd(direction_vec); + return Box2d( + (x1 + x2) / 2.0 * direction_vec + + (y1 + y2) / 2.0 * Vec2d(direction_vec.y(), -direction_vec.x()), + heading, x2 - x1, y2 - y1); +} + +Box2d Polygon2d::MinAreaBoundingBox() const { + CHECK_GE(points_.size(), 3); + if (!is_convex_) { + Polygon2d convex_polygon; + ComputeConvexHull(points_, &convex_polygon); + CHECK(convex_polygon.is_convex()); + return convex_polygon.MinAreaBoundingBox(); + } + double min_area = std::numeric_limits::infinity(); + double min_area_at_heading = 0.0; + int left_most = 0; + int right_most = 0; + int top_most = 0; + for (int i = 0; i < num_points_; ++i) { + const auto& line_segment = line_segments_[i]; + double proj = 0.0; + double min_proj = line_segment.ProjectOntoUnit(points_[left_most]); + while ((proj = line_segment.ProjectOntoUnit(points_[Prev(left_most)])) < + min_proj) { + min_proj = proj; + left_most = Prev(left_most); + } + while ((proj = line_segment.ProjectOntoUnit(points_[Next(left_most)])) < + min_proj) { + min_proj = proj; + left_most = Next(left_most); + } + double max_proj = line_segment.ProjectOntoUnit(points_[right_most]); + while ((proj = line_segment.ProjectOntoUnit(points_[Prev(right_most)])) > + max_proj) { + max_proj = proj; + right_most = Prev(right_most); + } + while ((proj = line_segment.ProjectOntoUnit(points_[Next(right_most)])) > + max_proj) { + max_proj = proj; + right_most = Next(right_most); + } + double prod = 0.0; + double max_prod = line_segment.ProductOntoUnit(points_[top_most]); + while ((prod = line_segment.ProductOntoUnit(points_[Prev(top_most)])) > + max_prod) { + max_prod = prod; + top_most = Prev(top_most); + } + while ((prod = line_segment.ProductOntoUnit(points_[Next(top_most)])) > + max_prod) { + max_prod = prod; + top_most = Next(top_most); + } + const double area = max_prod * (max_proj - min_proj); + if (area < min_area) { + min_area = area; + min_area_at_heading = line_segment.heading(); + } + } + return BoundingBoxWithHeading(min_area_at_heading); +} + +Polygon2d Polygon2d::ExpandByDistance(const double distance) const { + if (!is_convex_) { + Polygon2d convex_polygon; + ComputeConvexHull(points_, &convex_polygon); + CHECK(convex_polygon.is_convex()); + return convex_polygon.ExpandByDistance(distance); + } + const double kMinAngle = 0.1; + std::vector points; + for (int i = 0; i < num_points_; ++i) { + const double start_angle = line_segments_[Prev(i)].heading() - M_PI_2; + const double end_angle = line_segments_[i].heading() - M_PI_2; + const double diff = WrapAngle(end_angle - start_angle); + if (diff <= kMathEpsilon) { + points.push_back(points_[i] + + Vec2d::CreateUnitVec2d(start_angle) * distance); + } else { + const int count = static_cast(diff / kMinAngle) + 1; + for (int k = 0; k <= count; ++k) { + const double angle = + start_angle + + diff * static_cast(k) / static_cast(count); + points.push_back(points_[i] + Vec2d::CreateUnitVec2d(angle) * distance); + } + } + } + Polygon2d new_polygon; + CHECK(ComputeConvexHull(points, &new_polygon)); + return new_polygon; +} + +std::string Polygon2d::DebugString() const { + std::ostringstream sout; + sout << "polygon2d ( num_points = " << num_points_ << " points = ("; + for (const auto& pt : points_) { + sout << " " << pt.DebugString(); + } + sout << " ) " << (is_convex_ ? "convex" : "non-convex") + << " area = " << area_ << " )"; + sout.flush(); + return sout.str(); +} + +} // namespace math +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/math/search.cc b/apollo_common/src/math/search.cc new file mode 100644 index 0000000..7764b19 --- /dev/null +++ b/apollo_common/src/math/search.cc @@ -0,0 +1,68 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/math/search.h" + +#include + +namespace apollo { +namespace common { +namespace math { + +double GoldenSectionSearch(const std::function& func, + const double lower_bound, const double upper_bound, + const double tol) { + constexpr double gr = 1.618033989; // (sqrt(5) + 1) / 2 + + double a = lower_bound; + double b = upper_bound; + + double t = (b - a) / gr; + double c = b - t; + double d = a + t; + + while (std::abs(c - d) > tol) { + if (func(c) < func(d)) { + b = d; + } else { + a = c; + } + t = (b - a) / gr; + c = b - t; + d = a + t; + } + return (a + b) * 0.5; +} + +} // namespace math +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/math/sin_table.cc b/apollo_common/src/math/sin_table.cc new file mode 100644 index 0000000..0cea998 --- /dev/null +++ b/apollo_common/src/math/sin_table.cc @@ -0,0 +1,3322 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +// Do NOT modify this file. It was generated by gen_sin_table.py. + +#include "apollo_common/math/sin_table.h" + +namespace apollo { +namespace common { +namespace math { + +const float SIN_TABLE[16385] = { + 0.000000000f, 0.000095874f, 0.000191748f, 0.000287621f, 0.000383495f, + 0.000479369f, 0.000575243f, 0.000671117f, 0.000766990f, 0.000862864f, + 0.000958738f, 0.001054612f, 0.001150485f, 0.001246359f, 0.001342233f, + 0.001438106f, 0.001533980f, 0.001629854f, 0.001725728f, 0.001821601f, + 0.001917475f, 0.002013348f, 0.002109222f, 0.002205096f, 0.002300969f, + 0.002396843f, 0.002492716f, 0.002588590f, 0.002684463f, 0.002780337f, + 0.002876210f, 0.002972083f, 0.003067957f, 0.003163830f, 0.003259703f, + 0.003355577f, 0.003451450f, 0.003547323f, 0.003643196f, 0.003739069f, + 0.003834943f, 0.003930816f, 0.004026689f, 0.004122562f, 0.004218435f, + 0.004314308f, 0.004410180f, 0.004506053f, 0.004601926f, 0.004697799f, + 0.004793672f, 0.004889544f, 0.004985417f, 0.005081289f, 0.005177162f, + 0.005273035f, 0.005368907f, 0.005464779f, 0.005560652f, 0.005656524f, + 0.005752396f, 0.005848268f, 0.005944141f, 0.006040013f, 0.006135885f, + 0.006231757f, 0.006327629f, 0.006423500f, 0.006519372f, 0.006615244f, + 0.006711116f, 0.006806987f, 0.006902859f, 0.006998730f, 0.007094602f, + 0.007190473f, 0.007286344f, 0.007382215f, 0.007478087f, 0.007573958f, + 0.007669829f, 0.007765700f, 0.007861571f, 0.007957441f, 0.008053312f, + 0.008149183f, 0.008245053f, 0.008340924f, 0.008436794f, 0.008532665f, + 0.008628535f, 0.008724405f, 0.008820275f, 0.008916145f, 0.009012015f, + 0.009107885f, 0.009203755f, 0.009299624f, 0.009395494f, 0.009491364f, + 0.009587233f, 0.009683102f, 0.009778972f, 0.009874841f, 0.009970710f, + 0.010066579f, 0.010162448f, 0.010258317f, 0.010354185f, 0.010450054f, + 0.010545922f, 0.010641791f, 0.010737659f, 0.010833527f, 0.010929396f, + 0.011025264f, 0.011121131f, 0.011216999f, 0.011312867f, 0.011408735f, + 0.011504602f, 0.011600470f, 0.011696337f, 0.011792204f, 0.011888071f, + 0.011983938f, 0.012079805f, 0.012175672f, 0.012271538f, 0.012367405f, + 0.012463271f, 0.012559138f, 0.012655004f, 0.012750870f, 0.012846736f, + 0.012942602f, 0.013038467f, 0.013134333f, 0.013230198f, 0.013326064f, + 0.013421929f, 0.013517794f, 0.013613659f, 0.013709524f, 0.013805389f, + 0.013901253f, 0.013997118f, 0.014092982f, 0.014188846f, 0.014284710f, + 0.014380574f, 0.014476438f, 0.014572302f, 0.014668165f, 0.014764029f, + 0.014859892f, 0.014955755f, 0.015051618f, 0.015147481f, 0.015243344f, + 0.015339206f, 0.015435069f, 0.015530931f, 0.015626793f, 0.015722655f, + 0.015818517f, 0.015914379f, 0.016010240f, 0.016106102f, 0.016201963f, + 0.016297824f, 0.016393685f, 0.016489546f, 0.016585407f, 0.016681267f, + 0.016777128f, 0.016872988f, 0.016968848f, 0.017064708f, 0.017160568f, + 0.017256427f, 0.017352287f, 0.017448146f, 0.017544005f, 0.017639864f, + 0.017735723f, 0.017831582f, 0.017927440f, 0.018023298f, 0.018119156f, + 0.018215014f, 0.018310872f, 0.018406730f, 0.018502587f, 0.018598445f, + 0.018694302f, 0.018790159f, 0.018886016f, 0.018981872f, 0.019077729f, + 0.019173585f, 0.019269441f, 0.019365297f, 0.019461153f, 0.019557008f, + 0.019652864f, 0.019748719f, 0.019844574f, 0.019940429f, 0.020036283f, + 0.020132138f, 0.020227992f, 0.020323846f, 0.020419700f, 0.020515554f, + 0.020611407f, 0.020707261f, 0.020803114f, 0.020898967f, 0.020994819f, + 0.021090672f, 0.021186524f, 0.021282376f, 0.021378228f, 0.021474080f, + 0.021569932f, 0.021665783f, 0.021761634f, 0.021857485f, 0.021953336f, + 0.022049187f, 0.022145037f, 0.022240887f, 0.022336737f, 0.022432587f, + 0.022528437f, 0.022624286f, 0.022720135f, 0.022815984f, 0.022911833f, + 0.023007681f, 0.023103530f, 0.023199378f, 0.023295226f, 0.023391073f, + 0.023486921f, 0.023582768f, 0.023678615f, 0.023774462f, 0.023870309f, + 0.023966155f, 0.024062001f, 0.024157847f, 0.024253693f, 0.024349538f, + 0.024445383f, 0.024541229f, 0.024637073f, 0.024732918f, 0.024828762f, + 0.024924606f, 0.025020450f, 0.025116294f, 0.025212137f, 0.025307981f, + 0.025403824f, 0.025499666f, 0.025595509f, 0.025691351f, 0.025787193f, + 0.025883035f, 0.025978877f, 0.026074718f, 0.026170559f, 0.026266400f, + 0.026362240f, 0.026458081f, 0.026553921f, 0.026649761f, 0.026745600f, + 0.026841440f, 0.026937279f, 0.027033118f, 0.027128956f, 0.027224795f, + 0.027320633f, 0.027416471f, 0.027512308f, 0.027608146f, 0.027703983f, + 0.027799820f, 0.027895656f, 0.027991493f, 0.028087329f, 0.028183165f, + 0.028279000f, 0.028374836f, 0.028470671f, 0.028566505f, 0.028662340f, + 0.028758174f, 0.028854008f, 0.028949842f, 0.029045676f, 0.029141509f, + 0.029237342f, 0.029333174f, 0.029429007f, 0.029524839f, 0.029620671f, + 0.029716502f, 0.029812334f, 0.029908165f, 0.030003996f, 0.030099826f, + 0.030195656f, 0.030291486f, 0.030387316f, 0.030483145f, 0.030578974f, + 0.030674803f, 0.030770632f, 0.030866460f, 0.030962288f, 0.031058116f, + 0.031153943f, 0.031249770f, 0.031345597f, 0.031441424f, 0.031537250f, + 0.031633076f, 0.031728901f, 0.031824727f, 0.031920552f, 0.032016377f, + 0.032112201f, 0.032208025f, 0.032303849f, 0.032399673f, 0.032495496f, + 0.032591319f, 0.032687142f, 0.032782964f, 0.032878787f, 0.032974608f, + 0.033070430f, 0.033166251f, 0.033262072f, 0.033357893f, 0.033453713f, + 0.033549533f, 0.033645352f, 0.033741172f, 0.033836991f, 0.033932810f, + 0.034028628f, 0.034124446f, 0.034220264f, 0.034316081f, 0.034411899f, + 0.034507716f, 0.034603532f, 0.034699348f, 0.034795164f, 0.034890980f, + 0.034986795f, 0.035082610f, 0.035178425f, 0.035274239f, 0.035370053f, + 0.035465867f, 0.035561680f, 0.035657493f, 0.035753305f, 0.035849118f, + 0.035944930f, 0.036040742f, 0.036136553f, 0.036232364f, 0.036328175f, + 0.036423985f, 0.036519795f, 0.036615605f, 0.036711414f, 0.036807223f, + 0.036903032f, 0.036998840f, 0.037094648f, 0.037190456f, 0.037286263f, + 0.037382070f, 0.037477876f, 0.037573683f, 0.037669489f, 0.037765294f, + 0.037861099f, 0.037956904f, 0.038052709f, 0.038148513f, 0.038244317f, + 0.038340120f, 0.038435924f, 0.038531726f, 0.038627529f, 0.038723331f, + 0.038819132f, 0.038914934f, 0.039010735f, 0.039106535f, 0.039202336f, + 0.039298136f, 0.039393935f, 0.039489734f, 0.039585533f, 0.039681332f, + 0.039777130f, 0.039872928f, 0.039968725f, 0.040064522f, 0.040160319f, + 0.040256115f, 0.040351911f, 0.040447706f, 0.040543501f, 0.040639296f, + 0.040735091f, 0.040830885f, 0.040926678f, 0.041022472f, 0.041118265f, + 0.041214057f, 0.041309849f, 0.041405641f, 0.041501432f, 0.041597223f, + 0.041693014f, 0.041788804f, 0.041884594f, 0.041980384f, 0.042076173f, + 0.042171961f, 0.042267750f, 0.042363538f, 0.042459325f, 0.042555112f, + 0.042650899f, 0.042746685f, 0.042842471f, 0.042938257f, 0.043034042f, + 0.043129827f, 0.043225611f, 0.043321395f, 0.043417179f, 0.043512962f, + 0.043608745f, 0.043704527f, 0.043800309f, 0.043896091f, 0.043991872f, + 0.044087653f, 0.044183433f, 0.044279213f, 0.044374993f, 0.044470772f, + 0.044566551f, 0.044662329f, 0.044758107f, 0.044853884f, 0.044949661f, + 0.045045438f, 0.045141214f, 0.045236990f, 0.045332766f, 0.045428541f, + 0.045524315f, 0.045620090f, 0.045715863f, 0.045811637f, 0.045907410f, + 0.046003182f, 0.046098954f, 0.046194726f, 0.046290497f, 0.046386268f, + 0.046482038f, 0.046577808f, 0.046673578f, 0.046769347f, 0.046865116f, + 0.046960884f, 0.047056652f, 0.047152419f, 0.047248186f, 0.047343952f, + 0.047439719f, 0.047535484f, 0.047631249f, 0.047727014f, 0.047822778f, + 0.047918542f, 0.048014306f, 0.048110069f, 0.048205831f, 0.048301593f, + 0.048397355f, 0.048493116f, 0.048588877f, 0.048684637f, 0.048780397f, + 0.048876157f, 0.048971916f, 0.049067674f, 0.049163432f, 0.049259190f, + 0.049354947f, 0.049450704f, 0.049546460f, 0.049642216f, 0.049737971f, + 0.049833726f, 0.049929481f, 0.050025235f, 0.050120988f, 0.050216741f, + 0.050312494f, 0.050408246f, 0.050503998f, 0.050599749f, 0.050695500f, + 0.050791250f, 0.050887000f, 0.050982749f, 0.051078498f, 0.051174247f, + 0.051269994f, 0.051365742f, 0.051461489f, 0.051557235f, 0.051652982f, + 0.051748727f, 0.051844472f, 0.051940217f, 0.052035961f, 0.052131705f, + 0.052227448f, 0.052323191f, 0.052418933f, 0.052514675f, 0.052610416f, + 0.052706157f, 0.052801897f, 0.052897637f, 0.052993376f, 0.053089115f, + 0.053184853f, 0.053280591f, 0.053376328f, 0.053472065f, 0.053567802f, + 0.053663538f, 0.053759273f, 0.053855008f, 0.053950742f, 0.054046476f, + 0.054142210f, 0.054237943f, 0.054333675f, 0.054429407f, 0.054525138f, + 0.054620869f, 0.054716600f, 0.054812330f, 0.054908059f, 0.055003788f, + 0.055099516f, 0.055195244f, 0.055290972f, 0.055386699f, 0.055482425f, + 0.055578151f, 0.055673876f, 0.055769601f, 0.055865325f, 0.055961049f, + 0.056056773f, 0.056152495f, 0.056248218f, 0.056343939f, 0.056439661f, + 0.056535381f, 0.056631101f, 0.056726821f, 0.056822540f, 0.056918259f, + 0.057013977f, 0.057109695f, 0.057205412f, 0.057301128f, 0.057396844f, + 0.057492560f, 0.057588275f, 0.057683989f, 0.057779703f, 0.057875416f, + 0.057971129f, 0.058066842f, 0.058162553f, 0.058258265f, 0.058353975f, + 0.058449685f, 0.058545395f, 0.058641104f, 0.058736813f, 0.058832521f, + 0.058928228f, 0.059023935f, 0.059119641f, 0.059215347f, 0.059311052f, + 0.059406757f, 0.059502461f, 0.059598165f, 0.059693868f, 0.059789571f, + 0.059885273f, 0.059980974f, 0.060076675f, 0.060172375f, 0.060268075f, + 0.060363775f, 0.060459473f, 0.060555171f, 0.060650869f, 0.060746566f, + 0.060842262f, 0.060937958f, 0.061033654f, 0.061129348f, 0.061225043f, + 0.061320736f, 0.061416429f, 0.061512122f, 0.061607814f, 0.061703505f, + 0.061799196f, 0.061894886f, 0.061990576f, 0.062086265f, 0.062181954f, + 0.062277642f, 0.062373329f, 0.062469016f, 0.062564702f, 0.062660388f, + 0.062756073f, 0.062851758f, 0.062947442f, 0.063043125f, 0.063138808f, + 0.063234490f, 0.063330172f, 0.063425853f, 0.063521533f, 0.063617213f, + 0.063712892f, 0.063808571f, 0.063904249f, 0.063999927f, 0.064095604f, + 0.064191280f, 0.064286956f, 0.064382631f, 0.064478306f, 0.064573980f, + 0.064669653f, 0.064765326f, 0.064860998f, 0.064956670f, 0.065052341f, + 0.065148011f, 0.065243681f, 0.065339350f, 0.065435019f, 0.065530687f, + 0.065626354f, 0.065722021f, 0.065817687f, 0.065913353f, 0.066009018f, + 0.066104682f, 0.066200346f, 0.066296009f, 0.066391672f, 0.066487334f, + 0.066582995f, 0.066678656f, 0.066774316f, 0.066869975f, 0.066965634f, + 0.067061293f, 0.067156950f, 0.067252607f, 0.067348264f, 0.067443920f, + 0.067539575f, 0.067635229f, 0.067730883f, 0.067826537f, 0.067922189f, + 0.068017841f, 0.068113493f, 0.068209144f, 0.068304794f, 0.068400443f, + 0.068496092f, 0.068591741f, 0.068687388f, 0.068783035f, 0.068878682f, + 0.068974328f, 0.069069973f, 0.069165617f, 0.069261261f, 0.069356904f, + 0.069452547f, 0.069548189f, 0.069643830f, 0.069739471f, 0.069835111f, + 0.069930750f, 0.070026389f, 0.070122027f, 0.070217665f, 0.070313302f, + 0.070408938f, 0.070504573f, 0.070600208f, 0.070695843f, 0.070791476f, + 0.070887109f, 0.070982741f, 0.071078373f, 0.071174004f, 0.071269634f, + 0.071365264f, 0.071460893f, 0.071556521f, 0.071652149f, 0.071747776f, + 0.071843402f, 0.071939028f, 0.072034653f, 0.072130278f, 0.072225901f, + 0.072321524f, 0.072417147f, 0.072512769f, 0.072608390f, 0.072704010f, + 0.072799630f, 0.072895249f, 0.072990867f, 0.073086485f, 0.073182102f, + 0.073277718f, 0.073373334f, 0.073468949f, 0.073564564f, 0.073660177f, + 0.073755790f, 0.073851403f, 0.073947014f, 0.074042625f, 0.074138236f, + 0.074233845f, 0.074329454f, 0.074425062f, 0.074520670f, 0.074616277f, + 0.074711883f, 0.074807488f, 0.074903093f, 0.074998697f, 0.075094301f, + 0.075189904f, 0.075285506f, 0.075381107f, 0.075476708f, 0.075572308f, + 0.075667907f, 0.075763506f, 0.075859103f, 0.075954701f, 0.076050297f, + 0.076145893f, 0.076241488f, 0.076337082f, 0.076432676f, 0.076528269f, + 0.076623861f, 0.076719453f, 0.076815044f, 0.076910634f, 0.077006223f, + 0.077101812f, 0.077197400f, 0.077292988f, 0.077388574f, 0.077484160f, + 0.077579745f, 0.077675330f, 0.077770914f, 0.077866497f, 0.077962079f, + 0.078057661f, 0.078153242f, 0.078248822f, 0.078344401f, 0.078439980f, + 0.078535558f, 0.078631135f, 0.078726712f, 0.078822288f, 0.078917863f, + 0.079013437f, 0.079109011f, 0.079204584f, 0.079300156f, 0.079395728f, + 0.079491299f, 0.079586869f, 0.079682438f, 0.079778007f, 0.079873574f, + 0.079969142f, 0.080064708f, 0.080160274f, 0.080255838f, 0.080351403f, + 0.080446966f, 0.080542529f, 0.080638091f, 0.080733652f, 0.080829212f, + 0.080924772f, 0.081020331f, 0.081115889f, 0.081211447f, 0.081307004f, + 0.081402560f, 0.081498115f, 0.081593669f, 0.081689223f, 0.081784776f, + 0.081880328f, 0.081975880f, 0.082071431f, 0.082166981f, 0.082262530f, + 0.082358078f, 0.082453626f, 0.082549173f, 0.082644719f, 0.082740265f, + 0.082835809f, 0.082931353f, 0.083026896f, 0.083122439f, 0.083217980f, + 0.083313521f, 0.083409061f, 0.083504601f, 0.083600139f, 0.083695677f, + 0.083791214f, 0.083886750f, 0.083982286f, 0.084077820f, 0.084173354f, + 0.084268888f, 0.084364420f, 0.084459952f, 0.084555482f, 0.084651013f, + 0.084746542f, 0.084842070f, 0.084937598f, 0.085033125f, 0.085128651f, + 0.085224177f, 0.085319701f, 0.085415225f, 0.085510748f, 0.085606270f, + 0.085701792f, 0.085797312f, 0.085892832f, 0.085988351f, 0.086083870f, + 0.086179387f, 0.086274904f, 0.086370420f, 0.086465935f, 0.086561449f, + 0.086656963f, 0.086752476f, 0.086847987f, 0.086943499f, 0.087039009f, + 0.087134519f, 0.087230027f, 0.087325535f, 0.087421042f, 0.087516549f, + 0.087612054f, 0.087707559f, 0.087803063f, 0.087898566f, 0.087994068f, + 0.088089570f, 0.088185070f, 0.088280570f, 0.088376069f, 0.088471568f, + 0.088567065f, 0.088662562f, 0.088758058f, 0.088853553f, 0.088949047f, + 0.089044540f, 0.089140033f, 0.089235524f, 0.089331015f, 0.089426505f, + 0.089521995f, 0.089617483f, 0.089712971f, 0.089808457f, 0.089903943f, + 0.089999429f, 0.090094913f, 0.090190396f, 0.090285879f, 0.090381361f, + 0.090476842f, 0.090572322f, 0.090667801f, 0.090763280f, 0.090858758f, + 0.090954234f, 0.091049710f, 0.091145185f, 0.091240660f, 0.091336133f, + 0.091431606f, 0.091527078f, 0.091622549f, 0.091718019f, 0.091813488f, + 0.091908956f, 0.092004424f, 0.092099891f, 0.092195357f, 0.092290822f, + 0.092386286f, 0.092481749f, 0.092577212f, 0.092672673f, 0.092768134f, + 0.092863594f, 0.092959053f, 0.093054511f, 0.093149969f, 0.093245425f, + 0.093340881f, 0.093436336f, 0.093531790f, 0.093627243f, 0.093722695f, + 0.093818146f, 0.093913597f, 0.094009047f, 0.094104495f, 0.094199943f, + 0.094295390f, 0.094390837f, 0.094486282f, 0.094581726f, 0.094677170f, + 0.094772613f, 0.094868054f, 0.094963495f, 0.095058935f, 0.095154375f, + 0.095249813f, 0.095345250f, 0.095440687f, 0.095536123f, 0.095631558f, + 0.095726991f, 0.095822425f, 0.095917857f, 0.096013288f, 0.096108718f, + 0.096204148f, 0.096299577f, 0.096395004f, 0.096490431f, 0.096585857f, + 0.096681282f, 0.096776707f, 0.096872130f, 0.096967552f, 0.097062974f, + 0.097158395f, 0.097253814f, 0.097349233f, 0.097444651f, 0.097540068f, + 0.097635485f, 0.097730900f, 0.097826314f, 0.097921728f, 0.098017140f, + 0.098112552f, 0.098207963f, 0.098303373f, 0.098398782f, 0.098494190f, + 0.098589597f, 0.098685003f, 0.098780409f, 0.098875813f, 0.098971217f, + 0.099066619f, 0.099162021f, 0.099257422f, 0.099352822f, 0.099448221f, + 0.099543619f, 0.099639016f, 0.099734412f, 0.099829807f, 0.099925202f, + 0.100020595f, 0.100115988f, 0.100211379f, 0.100306770f, 0.100402160f, + 0.100497549f, 0.100592937f, 0.100688324f, 0.100783710f, 0.100879095f, + 0.100974479f, 0.101069863f, 0.101165245f, 0.101260627f, 0.101356007f, + 0.101451387f, 0.101546765f, 0.101642143f, 0.101737520f, 0.101832896f, + 0.101928271f, 0.102023645f, 0.102119018f, 0.102214390f, 0.102309761f, + 0.102405131f, 0.102500501f, 0.102595869f, 0.102691236f, 0.102786603f, + 0.102881968f, 0.102977333f, 0.103072697f, 0.103168059f, 0.103263421f, + 0.103358782f, 0.103454142f, 0.103549501f, 0.103644859f, 0.103740215f, + 0.103835572f, 0.103930927f, 0.104026281f, 0.104121634f, 0.104216986f, + 0.104312337f, 0.104407688f, 0.104503037f, 0.104598385f, 0.104693733f, + 0.104789079f, 0.104884425f, 0.104979769f, 0.105075113f, 0.105170455f, + 0.105265797f, 0.105361138f, 0.105456477f, 0.105551816f, 0.105647154f, + 0.105742490f, 0.105837826f, 0.105933161f, 0.106028495f, 0.106123828f, + 0.106219160f, 0.106314491f, 0.106409821f, 0.106505150f, 0.106600478f, + 0.106695805f, 0.106791131f, 0.106886456f, 0.106981780f, 0.107077103f, + 0.107172425f, 0.107267746f, 0.107363066f, 0.107458385f, 0.107553704f, + 0.107649021f, 0.107744337f, 0.107839652f, 0.107934966f, 0.108030279f, + 0.108125592f, 0.108220903f, 0.108316213f, 0.108411522f, 0.108506831f, + 0.108602138f, 0.108697444f, 0.108792749f, 0.108888053f, 0.108983357f, + 0.109078659f, 0.109173960f, 0.109269260f, 0.109364560f, 0.109459858f, + 0.109555155f, 0.109650451f, 0.109745746f, 0.109841041f, 0.109936334f, + 0.110031626f, 0.110126917f, 0.110222207f, 0.110317496f, 0.110412785f, + 0.110508072f, 0.110603358f, 0.110698643f, 0.110793927f, 0.110889210f, + 0.110984492f, 0.111079773f, 0.111175053f, 0.111270332f, 0.111365610f, + 0.111460887f, 0.111556163f, 0.111651437f, 0.111746711f, 0.111841984f, + 0.111937256f, 0.112032527f, 0.112127796f, 0.112223065f, 0.112318333f, + 0.112413599f, 0.112508865f, 0.112604129f, 0.112699393f, 0.112794655f, + 0.112889917f, 0.112985177f, 0.113080437f, 0.113175695f, 0.113270952f, + 0.113366208f, 0.113461464f, 0.113556718f, 0.113651971f, 0.113747223f, + 0.113842474f, 0.113937724f, 0.114032973f, 0.114128221f, 0.114223468f, + 0.114318713f, 0.114413958f, 0.114509202f, 0.114604445f, 0.114699686f, + 0.114794927f, 0.114890166f, 0.114985404f, 0.115080642f, 0.115175878f, + 0.115271113f, 0.115366348f, 0.115461581f, 0.115556813f, 0.115652044f, + 0.115747274f, 0.115842503f, 0.115937730f, 0.116032957f, 0.116128183f, + 0.116223407f, 0.116318631f, 0.116413853f, 0.116509075f, 0.116604295f, + 0.116699514f, 0.116794733f, 0.116889950f, 0.116985166f, 0.117080381f, + 0.117175595f, 0.117270807f, 0.117366019f, 0.117461230f, 0.117556439f, + 0.117651648f, 0.117746855f, 0.117842062f, 0.117937267f, 0.118032471f, + 0.118127674f, 0.118222876f, 0.118318077f, 0.118413277f, 0.118508475f, + 0.118603673f, 0.118698870f, 0.118794065f, 0.118889259f, 0.118984453f, + 0.119079645f, 0.119174836f, 0.119270026f, 0.119365215f, 0.119460403f, + 0.119555589f, 0.119650775f, 0.119745959f, 0.119841143f, 0.119936325f, + 0.120031506f, 0.120126686f, 0.120221865f, 0.120317043f, 0.120412220f, + 0.120507396f, 0.120602570f, 0.120697744f, 0.120792916f, 0.120888087f, + 0.120983257f, 0.121078426f, 0.121173594f, 0.121268761f, 0.121363927f, + 0.121459091f, 0.121554255f, 0.121649417f, 0.121744578f, 0.121839738f, + 0.121934897f, 0.122030055f, 0.122125212f, 0.122220367f, 0.122315522f, + 0.122410675f, 0.122505827f, 0.122600979f, 0.122696128f, 0.122791277f, + 0.122886425f, 0.122981572f, 0.123076717f, 0.123171861f, 0.123267005f, + 0.123362147f, 0.123457288f, 0.123552427f, 0.123647566f, 0.123742704f, + 0.123837840f, 0.123932975f, 0.124028109f, 0.124123242f, 0.124218374f, + 0.124313505f, 0.124408634f, 0.124503763f, 0.124598890f, 0.124694016f, + 0.124789141f, 0.124884265f, 0.124979387f, 0.125074509f, 0.125169629f, + 0.125264748f, 0.125359867f, 0.125454983f, 0.125550099f, 0.125645214f, + 0.125740327f, 0.125835439f, 0.125930551f, 0.126025661f, 0.126120769f, + 0.126215877f, 0.126310984f, 0.126406089f, 0.126501193f, 0.126596296f, + 0.126691398f, 0.126786499f, 0.126881598f, 0.126976696f, 0.127071794f, + 0.127166890f, 0.127261985f, 0.127357078f, 0.127452171f, 0.127547262f, + 0.127642352f, 0.127737441f, 0.127832529f, 0.127927616f, 0.128022701f, + 0.128117785f, 0.128212869f, 0.128307950f, 0.128403031f, 0.128498111f, + 0.128593189f, 0.128688266f, 0.128783342f, 0.128878417f, 0.128973491f, + 0.129068563f, 0.129163635f, 0.129258705f, 0.129353774f, 0.129448841f, + 0.129543908f, 0.129638973f, 0.129734037f, 0.129829100f, 0.129924162f, + 0.130019223f, 0.130114282f, 0.130209340f, 0.130304397f, 0.130399453f, + 0.130494508f, 0.130589561f, 0.130684613f, 0.130779664f, 0.130874714f, + 0.130969763f, 0.131064810f, 0.131159856f, 0.131254901f, 0.131349945f, + 0.131444987f, 0.131540029f, 0.131635069f, 0.131730108f, 0.131825145f, + 0.131920182f, 0.132015217f, 0.132110251f, 0.132205284f, 0.132300316f, + 0.132395346f, 0.132490375f, 0.132585403f, 0.132680430f, 0.132775456f, + 0.132870480f, 0.132965503f, 0.133060525f, 0.133155546f, 0.133250565f, + 0.133345583f, 0.133440600f, 0.133535616f, 0.133630631f, 0.133725644f, + 0.133820656f, 0.133915667f, 0.134010677f, 0.134105685f, 0.134200692f, + 0.134295698f, 0.134390703f, 0.134485706f, 0.134580709f, 0.134675709f, + 0.134770709f, 0.134865708f, 0.134960705f, 0.135055701f, 0.135150696f, + 0.135245689f, 0.135340682f, 0.135435673f, 0.135530663f, 0.135625651f, + 0.135720638f, 0.135815624f, 0.135910609f, 0.136005593f, 0.136100575f, + 0.136195556f, 0.136290536f, 0.136385515f, 0.136480492f, 0.136575468f, + 0.136670443f, 0.136765416f, 0.136860389f, 0.136955360f, 0.137050329f, + 0.137145298f, 0.137240265f, 0.137335231f, 0.137430196f, 0.137525159f, + 0.137620122f, 0.137715083f, 0.137810042f, 0.137905001f, 0.137999958f, + 0.138094914f, 0.138189868f, 0.138284822f, 0.138379774f, 0.138474724f, + 0.138569674f, 0.138664622f, 0.138759569f, 0.138854515f, 0.138949459f, + 0.139044402f, 0.139139344f, 0.139234285f, 0.139329224f, 0.139424162f, + 0.139519099f, 0.139614034f, 0.139708968f, 0.139803901f, 0.139898833f, + 0.139993763f, 0.140088692f, 0.140183620f, 0.140278546f, 0.140373472f, + 0.140468395f, 0.140563318f, 0.140658239f, 0.140753159f, 0.140848078f, + 0.140942995f, 0.141037912f, 0.141132826f, 0.141227740f, 0.141322652f, + 0.141417563f, 0.141512473f, 0.141607381f, 0.141702288f, 0.141797194f, + 0.141892098f, 0.141987001f, 0.142081903f, 0.142176804f, 0.142271703f, + 0.142366601f, 0.142461497f, 0.142556392f, 0.142651286f, 0.142746179f, + 0.142841070f, 0.142935960f, 0.143030849f, 0.143125736f, 0.143220623f, + 0.143315507f, 0.143410391f, 0.143505273f, 0.143600154f, 0.143695033f, + 0.143789911f, 0.143884788f, 0.143979664f, 0.144074538f, 0.144169411f, + 0.144264282f, 0.144359152f, 0.144454021f, 0.144548889f, 0.144643755f, + 0.144738620f, 0.144833484f, 0.144928346f, 0.145023207f, 0.145118066f, + 0.145212925f, 0.145307782f, 0.145402637f, 0.145497491f, 0.145592344f, + 0.145687196f, 0.145782046f, 0.145876895f, 0.145971742f, 0.146066589f, + 0.146161434f, 0.146256277f, 0.146351119f, 0.146445960f, 0.146540800f, + 0.146635638f, 0.146730474f, 0.146825310f, 0.146920144f, 0.147014977f, + 0.147109808f, 0.147204638f, 0.147299467f, 0.147394294f, 0.147489120f, + 0.147583945f, 0.147678768f, 0.147773590f, 0.147868410f, 0.147963230f, + 0.148058047f, 0.148152864f, 0.148247679f, 0.148342493f, 0.148437305f, + 0.148532116f, 0.148626926f, 0.148721734f, 0.148816541f, 0.148911346f, + 0.149006151f, 0.149100953f, 0.149195755f, 0.149290555f, 0.149385354f, + 0.149480151f, 0.149574947f, 0.149669741f, 0.149764535f, 0.149859326f, + 0.149954117f, 0.150048906f, 0.150143694f, 0.150238480f, 0.150333265f, + 0.150428048f, 0.150522831f, 0.150617611f, 0.150712391f, 0.150807169f, + 0.150901945f, 0.150996721f, 0.151091494f, 0.151186267f, 0.151281038f, + 0.151375808f, 0.151470576f, 0.151565343f, 0.151660108f, 0.151754872f, + 0.151849635f, 0.151944396f, 0.152039156f, 0.152133915f, 0.152228672f, + 0.152323428f, 0.152418182f, 0.152512935f, 0.152607686f, 0.152702437f, + 0.152797185f, 0.152891933f, 0.152986678f, 0.153081423f, 0.153176166f, + 0.153270908f, 0.153365648f, 0.153460387f, 0.153555124f, 0.153649860f, + 0.153744595f, 0.153839328f, 0.153934060f, 0.154028790f, 0.154123519f, + 0.154218247f, 0.154312973f, 0.154407698f, 0.154502421f, 0.154597143f, + 0.154691863f, 0.154786582f, 0.154881300f, 0.154976016f, 0.155070731f, + 0.155165444f, 0.155260156f, 0.155354867f, 0.155449576f, 0.155544283f, + 0.155638990f, 0.155733694f, 0.155828398f, 0.155923100f, 0.156017800f, + 0.156112499f, 0.156207197f, 0.156301893f, 0.156396588f, 0.156491281f, + 0.156585973f, 0.156680663f, 0.156775352f, 0.156870040f, 0.156964726f, + 0.157059410f, 0.157154094f, 0.157248775f, 0.157343456f, 0.157438134f, + 0.157532812f, 0.157627488f, 0.157722162f, 0.157816835f, 0.157911507f, + 0.158006177f, 0.158100846f, 0.158195513f, 0.158290179f, 0.158384843f, + 0.158479506f, 0.158574168f, 0.158668828f, 0.158763486f, 0.158858143f, + 0.158952799f, 0.159047453f, 0.159142106f, 0.159236757f, 0.159331407f, + 0.159426055f, 0.159520702f, 0.159615347f, 0.159709991f, 0.159804634f, + 0.159899275f, 0.159993914f, 0.160088552f, 0.160183189f, 0.160277824f, + 0.160372457f, 0.160467089f, 0.160561720f, 0.160656349f, 0.160750977f, + 0.160845603f, 0.160940228f, 0.161034851f, 0.161129473f, 0.161224093f, + 0.161318712f, 0.161413329f, 0.161507945f, 0.161602560f, 0.161697172f, + 0.161791784f, 0.161886394f, 0.161981002f, 0.162075609f, 0.162170215f, + 0.162264819f, 0.162359421f, 0.162454022f, 0.162548621f, 0.162643219f, + 0.162737816f, 0.162832411f, 0.162927004f, 0.163021596f, 0.163116187f, + 0.163210776f, 0.163305363f, 0.163399949f, 0.163494534f, 0.163589117f, + 0.163683698f, 0.163778278f, 0.163872857f, 0.163967434f, 0.164062009f, + 0.164156583f, 0.164251156f, 0.164345727f, 0.164440296f, 0.164534864f, + 0.164629430f, 0.164723995f, 0.164818559f, 0.164913120f, 0.165007681f, + 0.165102240f, 0.165196797f, 0.165291353f, 0.165385907f, 0.165480460f, + 0.165575011f, 0.165669561f, 0.165764109f, 0.165858656f, 0.165953201f, + 0.166047744f, 0.166142286f, 0.166236827f, 0.166331366f, 0.166425904f, + 0.166520440f, 0.166614974f, 0.166709507f, 0.166804038f, 0.166898568f, + 0.166993096f, 0.167087623f, 0.167182148f, 0.167276672f, 0.167371194f, + 0.167465715f, 0.167560234f, 0.167654752f, 0.167749268f, 0.167843782f, + 0.167938295f, 0.168032806f, 0.168127316f, 0.168221824f, 0.168316331f, + 0.168410836f, 0.168505340f, 0.168599842f, 0.168694343f, 0.168788842f, + 0.168883339f, 0.168977835f, 0.169072329f, 0.169166822f, 0.169261313f, + 0.169355803f, 0.169450291f, 0.169544778f, 0.169639263f, 0.169733746f, + 0.169828228f, 0.169922708f, 0.170017187f, 0.170111664f, 0.170206140f, + 0.170300614f, 0.170395087f, 0.170489558f, 0.170584027f, 0.170678495f, + 0.170772961f, 0.170867426f, 0.170961889f, 0.171056350f, 0.171150810f, + 0.171245269f, 0.171339725f, 0.171434181f, 0.171528634f, 0.171623086f, + 0.171717537f, 0.171811986f, 0.171906433f, 0.172000879f, 0.172095323f, + 0.172189766f, 0.172284207f, 0.172378646f, 0.172473084f, 0.172567520f, + 0.172661955f, 0.172756388f, 0.172850820f, 0.172945249f, 0.173039678f, + 0.173134105f, 0.173228530f, 0.173322953f, 0.173417375f, 0.173511796f, + 0.173606214f, 0.173700631f, 0.173795047f, 0.173889461f, 0.173983873f, + 0.174078284f, 0.174172693f, 0.174267101f, 0.174361507f, 0.174455911f, + 0.174550314f, 0.174644715f, 0.174739115f, 0.174833513f, 0.174927909f, + 0.175022304f, 0.175116697f, 0.175211088f, 0.175305478f, 0.175399867f, + 0.175494253f, 0.175588638f, 0.175683022f, 0.175777404f, 0.175871784f, + 0.175966163f, 0.176060540f, 0.176154915f, 0.176249289f, 0.176343661f, + 0.176438031f, 0.176532400f, 0.176626768f, 0.176721133f, 0.176815497f, + 0.176909860f, 0.177004220f, 0.177098580f, 0.177192937f, 0.177287293f, + 0.177381647f, 0.177476000f, 0.177570351f, 0.177664700f, 0.177759048f, + 0.177853394f, 0.177947739f, 0.178042081f, 0.178136423f, 0.178230762f, + 0.178325100f, 0.178419436f, 0.178513771f, 0.178608104f, 0.178702435f, + 0.178796765f, 0.178891093f, 0.178985420f, 0.179079744f, 0.179174067f, + 0.179268389f, 0.179362709f, 0.179457027f, 0.179551343f, 0.179645658f, + 0.179739972f, 0.179834283f, 0.179928593f, 0.180022901f, 0.180117208f, + 0.180211513f, 0.180305816f, 0.180400118f, 0.180494418f, 0.180588716f, + 0.180683013f, 0.180777308f, 0.180871601f, 0.180965893f, 0.181060183f, + 0.181154471f, 0.181248758f, 0.181343043f, 0.181437327f, 0.181531608f, + 0.181625888f, 0.181720167f, 0.181814443f, 0.181908718f, 0.182002992f, + 0.182097263f, 0.182191533f, 0.182285802f, 0.182380068f, 0.182474333f, + 0.182568597f, 0.182662858f, 0.182757118f, 0.182851376f, 0.182945633f, + 0.183039888f, 0.183134141f, 0.183228393f, 0.183322643f, 0.183416891f, + 0.183511137f, 0.183605382f, 0.183699625f, 0.183793867f, 0.183888106f, + 0.183982344f, 0.184076581f, 0.184170815f, 0.184265048f, 0.184359279f, + 0.184453509f, 0.184547737f, 0.184641963f, 0.184736188f, 0.184830410f, + 0.184924631f, 0.185018851f, 0.185113069f, 0.185207285f, 0.185301499f, + 0.185395711f, 0.185489922f, 0.185584131f, 0.185678339f, 0.185772545f, + 0.185866749f, 0.185960951f, 0.186055152f, 0.186149351f, 0.186243548f, + 0.186337743f, 0.186431937f, 0.186526129f, 0.186620320f, 0.186714508f, + 0.186808695f, 0.186902880f, 0.186997064f, 0.187091246f, 0.187185426f, + 0.187279604f, 0.187373781f, 0.187467955f, 0.187562129f, 0.187656300f, + 0.187750470f, 0.187844638f, 0.187938804f, 0.188032969f, 0.188127131f, + 0.188221292f, 0.188315452f, 0.188409609f, 0.188503765f, 0.188597919f, + 0.188692072f, 0.188786223f, 0.188880371f, 0.188974519f, 0.189068664f, + 0.189162808f, 0.189256950f, 0.189351090f, 0.189445229f, 0.189539365f, + 0.189633500f, 0.189727634f, 0.189821765f, 0.189915895f, 0.190010023f, + 0.190104149f, 0.190198274f, 0.190292397f, 0.190386518f, 0.190480637f, + 0.190574755f, 0.190668871f, 0.190762985f, 0.190857097f, 0.190951208f, + 0.191045316f, 0.191139423f, 0.191233529f, 0.191327632f, 0.191421734f, + 0.191515834f, 0.191609932f, 0.191704029f, 0.191798123f, 0.191892216f, + 0.191986308f, 0.192080397f, 0.192174485f, 0.192268571f, 0.192362655f, + 0.192456737f, 0.192550818f, 0.192644897f, 0.192738974f, 0.192833049f, + 0.192927122f, 0.193021194f, 0.193115264f, 0.193209332f, 0.193303399f, + 0.193397463f, 0.193491526f, 0.193585587f, 0.193679647f, 0.193773704f, + 0.193867760f, 0.193961814f, 0.194055866f, 0.194149916f, 0.194243965f, + 0.194338012f, 0.194432057f, 0.194526100f, 0.194620142f, 0.194714181f, + 0.194808219f, 0.194902255f, 0.194996290f, 0.195090322f, 0.195184353f, + 0.195278382f, 0.195372409f, 0.195466434f, 0.195560458f, 0.195654479f, + 0.195748499f, 0.195842517f, 0.195936534f, 0.196030548f, 0.196124561f, + 0.196218572f, 0.196312581f, 0.196406588f, 0.196500594f, 0.196594598f, + 0.196688600f, 0.196782600f, 0.196876598f, 0.196970594f, 0.197064589f, + 0.197158582f, 0.197252573f, 0.197346562f, 0.197440550f, 0.197534535f, + 0.197628519f, 0.197722501f, 0.197816481f, 0.197910460f, 0.198004436f, + 0.198098411f, 0.198192384f, 0.198286355f, 0.198380324f, 0.198474291f, + 0.198568257f, 0.198662221f, 0.198756183f, 0.198850143f, 0.198944101f, + 0.199038057f, 0.199132012f, 0.199225965f, 0.199319916f, 0.199413865f, + 0.199507812f, 0.199601758f, 0.199695701f, 0.199789643f, 0.199883583f, + 0.199977521f, 0.200071457f, 0.200165392f, 0.200259324f, 0.200353255f, + 0.200447184f, 0.200541111f, 0.200635036f, 0.200728960f, 0.200822881f, + 0.200916801f, 0.201010719f, 0.201104635f, 0.201198549f, 0.201292461f, + 0.201386372f, 0.201480280f, 0.201574187f, 0.201668092f, 0.201761995f, + 0.201855896f, 0.201949796f, 0.202043693f, 0.202137589f, 0.202231482f, + 0.202325374f, 0.202419264f, 0.202513153f, 0.202607039f, 0.202700923f, + 0.202794806f, 0.202888687f, 0.202982565f, 0.203076442f, 0.203170318f, + 0.203264191f, 0.203358062f, 0.203451932f, 0.203545799f, 0.203639665f, + 0.203733529f, 0.203827391f, 0.203921251f, 0.204015110f, 0.204108966f, + 0.204202821f, 0.204296673f, 0.204390524f, 0.204484373f, 0.204578220f, + 0.204672065f, 0.204765908f, 0.204859750f, 0.204953589f, 0.205047427f, + 0.205141263f, 0.205235097f, 0.205328928f, 0.205422759f, 0.205516587f, + 0.205610413f, 0.205704237f, 0.205798060f, 0.205891881f, 0.205985699f, + 0.206079516f, 0.206173331f, 0.206267144f, 0.206360955f, 0.206454765f, + 0.206548572f, 0.206642377f, 0.206736181f, 0.206829983f, 0.206923782f, + 0.207017580f, 0.207111376f, 0.207205170f, 0.207298962f, 0.207392753f, + 0.207486541f, 0.207580327f, 0.207674112f, 0.207767895f, 0.207861675f, + 0.207955454f, 0.208049231f, 0.208143006f, 0.208236779f, 0.208330550f, + 0.208424319f, 0.208518087f, 0.208611852f, 0.208705615f, 0.208799377f, + 0.208893137f, 0.208986894f, 0.209080650f, 0.209174404f, 0.209268156f, + 0.209361906f, 0.209455654f, 0.209549400f, 0.209643145f, 0.209736887f, + 0.209830627f, 0.209924366f, 0.210018102f, 0.210111837f, 0.210205570f, + 0.210299300f, 0.210393029f, 0.210486756f, 0.210580481f, 0.210674204f, + 0.210767925f, 0.210861644f, 0.210955361f, 0.211049077f, 0.211142790f, + 0.211236501f, 0.211330211f, 0.211423918f, 0.211517624f, 0.211611327f, + 0.211705029f, 0.211798729f, 0.211892427f, 0.211986122f, 0.212079816f, + 0.212173508f, 0.212267198f, 0.212360886f, 0.212454572f, 0.212548256f, + 0.212641938f, 0.212735619f, 0.212829297f, 0.212922973f, 0.213016648f, + 0.213110320f, 0.213203990f, 0.213297659f, 0.213391325f, 0.213484990f, + 0.213578652f, 0.213672313f, 0.213765972f, 0.213859628f, 0.213953283f, + 0.214046936f, 0.214140587f, 0.214234235f, 0.214327882f, 0.214421527f, + 0.214515170f, 0.214608811f, 0.214702450f, 0.214796087f, 0.214889722f, + 0.214983355f, 0.215076986f, 0.215170615f, 0.215264242f, 0.215357867f, + 0.215451491f, 0.215545112f, 0.215638731f, 0.215732348f, 0.215825963f, + 0.215919577f, 0.216013188f, 0.216106797f, 0.216200404f, 0.216294010f, + 0.216387613f, 0.216481214f, 0.216574814f, 0.216668411f, 0.216762006f, + 0.216855600f, 0.216949191f, 0.217042780f, 0.217136368f, 0.217229953f, + 0.217323536f, 0.217417118f, 0.217510697f, 0.217604275f, 0.217697850f, + 0.217791423f, 0.217884995f, 0.217978564f, 0.218072132f, 0.218165697f, + 0.218259260f, 0.218352822f, 0.218446381f, 0.218539938f, 0.218633494f, + 0.218727047f, 0.218820598f, 0.218914148f, 0.219007695f, 0.219101240f, + 0.219194783f, 0.219288325f, 0.219381864f, 0.219475401f, 0.219568936f, + 0.219662469f, 0.219756001f, 0.219849530f, 0.219943057f, 0.220036582f, + 0.220130105f, 0.220223626f, 0.220317145f, 0.220410662f, 0.220504177f, + 0.220597690f, 0.220691201f, 0.220784710f, 0.220878217f, 0.220971722f, + 0.221065224f, 0.221158725f, 0.221252224f, 0.221345721f, 0.221439215f, + 0.221532708f, 0.221626199f, 0.221719687f, 0.221813174f, 0.221906658f, + 0.222000141f, 0.222093621f, 0.222187099f, 0.222280576f, 0.222374050f, + 0.222467522f, 0.222560992f, 0.222654461f, 0.222747927f, 0.222841391f, + 0.222934853f, 0.223028313f, 0.223121771f, 0.223215226f, 0.223308680f, + 0.223402132f, 0.223495582f, 0.223589029f, 0.223682475f, 0.223775918f, + 0.223869360f, 0.223962799f, 0.224056237f, 0.224149672f, 0.224243105f, + 0.224336536f, 0.224429965f, 0.224523392f, 0.224616817f, 0.224710240f, + 0.224803661f, 0.224897080f, 0.224990497f, 0.225083911f, 0.225177324f, + 0.225270734f, 0.225364143f, 0.225457549f, 0.225550954f, 0.225644356f, + 0.225737756f, 0.225831154f, 0.225924550f, 0.226017944f, 0.226111336f, + 0.226204726f, 0.226298113f, 0.226391499f, 0.226484882f, 0.226578264f, + 0.226671643f, 0.226765020f, 0.226858396f, 0.226951769f, 0.227045140f, + 0.227138509f, 0.227231876f, 0.227325240f, 0.227418603f, 0.227511964f, + 0.227605322f, 0.227698679f, 0.227792033f, 0.227885385f, 0.227978735f, + 0.228072083f, 0.228165429f, 0.228258773f, 0.228352115f, 0.228445454f, + 0.228538792f, 0.228632127f, 0.228725461f, 0.228818792f, 0.228912121f, + 0.229005448f, 0.229098773f, 0.229192096f, 0.229285416f, 0.229378735f, + 0.229472051f, 0.229565366f, 0.229658678f, 0.229751988f, 0.229845296f, + 0.229938602f, 0.230031906f, 0.230125208f, 0.230218507f, 0.230311805f, + 0.230405100f, 0.230498393f, 0.230591685f, 0.230684974f, 0.230778260f, + 0.230871545f, 0.230964828f, 0.231058108f, 0.231151387f, 0.231244663f, + 0.231337937f, 0.231431209f, 0.231524479f, 0.231617747f, 0.231711012f, + 0.231804276f, 0.231897537f, 0.231990796f, 0.232084054f, 0.232177309f, + 0.232270561f, 0.232363812f, 0.232457061f, 0.232550307f, 0.232643551f, + 0.232736793f, 0.232830033f, 0.232923271f, 0.233016507f, 0.233109741f, + 0.233202972f, 0.233296201f, 0.233389429f, 0.233482654f, 0.233575876f, + 0.233669097f, 0.233762316f, 0.233855532f, 0.233948746f, 0.234041959f, + 0.234135169f, 0.234228376f, 0.234321582f, 0.234414786f, 0.234507987f, + 0.234601186f, 0.234694383f, 0.234787578f, 0.234880771f, 0.234973961f, + 0.235067150f, 0.235160336f, 0.235253520f, 0.235346702f, 0.235439882f, + 0.235533059f, 0.235626235f, 0.235719408f, 0.235812579f, 0.235905748f, + 0.235998915f, 0.236092080f, 0.236185242f, 0.236278402f, 0.236371560f, + 0.236464716f, 0.236557870f, 0.236651021f, 0.236744171f, 0.236837318f, + 0.236930463f, 0.237023606f, 0.237116747f, 0.237209885f, 0.237303021f, + 0.237396156f, 0.237489288f, 0.237582417f, 0.237675545f, 0.237768670f, + 0.237861794f, 0.237954915f, 0.238048033f, 0.238141150f, 0.238234265f, + 0.238327377f, 0.238420487f, 0.238513595f, 0.238606701f, 0.238699804f, + 0.238792905f, 0.238886004f, 0.238979101f, 0.239072196f, 0.239165289f, + 0.239258379f, 0.239351467f, 0.239444553f, 0.239537637f, 0.239630718f, + 0.239723798f, 0.239816875f, 0.239909950f, 0.240003022f, 0.240096093f, + 0.240189161f, 0.240282227f, 0.240375291f, 0.240468353f, 0.240561412f, + 0.240654470f, 0.240747525f, 0.240840578f, 0.240933628f, 0.241026677f, + 0.241119723f, 0.241212767f, 0.241305808f, 0.241398848f, 0.241491885f, + 0.241584920f, 0.241677953f, 0.241770984f, 0.241864012f, 0.241957039f, + 0.242050063f, 0.242143084f, 0.242236104f, 0.242329121f, 0.242422136f, + 0.242515149f, 0.242608160f, 0.242701168f, 0.242794174f, 0.242887178f, + 0.242980180f, 0.243073179f, 0.243166177f, 0.243259172f, 0.243352164f, + 0.243445155f, 0.243538143f, 0.243631129f, 0.243724113f, 0.243817095f, + 0.243910074f, 0.244003051f, 0.244096026f, 0.244188998f, 0.244281969f, + 0.244374937f, 0.244467903f, 0.244560866f, 0.244653828f, 0.244746787f, + 0.244839744f, 0.244932698f, 0.245025651f, 0.245118601f, 0.245211549f, + 0.245304494f, 0.245397438f, 0.245490379f, 0.245583318f, 0.245676254f, + 0.245769188f, 0.245862121f, 0.245955050f, 0.246047978f, 0.246140903f, + 0.246233826f, 0.246326747f, 0.246419665f, 0.246512582f, 0.246605496f, + 0.246698407f, 0.246791317f, 0.246884224f, 0.246977129f, 0.247070031f, + 0.247162932f, 0.247255830f, 0.247348726f, 0.247441619f, 0.247534510f, + 0.247627399f, 0.247720286f, 0.247813171f, 0.247906053f, 0.247998933f, + 0.248091810f, 0.248184685f, 0.248277558f, 0.248370429f, 0.248463298f, + 0.248556164f, 0.248649028f, 0.248741889f, 0.248834749f, 0.248927606f, + 0.249020460f, 0.249113313f, 0.249206163f, 0.249299011f, 0.249391857f, + 0.249484700f, 0.249577541f, 0.249670380f, 0.249763216f, 0.249856050f, + 0.249948882f, 0.250041711f, 0.250134539f, 0.250227364f, 0.250320186f, + 0.250413007f, 0.250505825f, 0.250598640f, 0.250691454f, 0.250784265f, + 0.250877074f, 0.250969880f, 0.251062684f, 0.251155486f, 0.251248286f, + 0.251341083f, 0.251433878f, 0.251526671f, 0.251619461f, 0.251712249f, + 0.251805035f, 0.251897818f, 0.251990599f, 0.252083378f, 0.252176154f, + 0.252268929f, 0.252361700f, 0.252454470f, 0.252547237f, 0.252640002f, + 0.252732764f, 0.252825525f, 0.252918282f, 0.253011038f, 0.253103791f, + 0.253196542f, 0.253289291f, 0.253382037f, 0.253474781f, 0.253567522f, + 0.253660262f, 0.253752999f, 0.253845733f, 0.253938466f, 0.254031195f, + 0.254123923f, 0.254216648f, 0.254309371f, 0.254402092f, 0.254494810f, + 0.254587526f, 0.254680240f, 0.254772951f, 0.254865660f, 0.254958366f, + 0.255051070f, 0.255143772f, 0.255236472f, 0.255329169f, 0.255421864f, + 0.255514556f, 0.255607246f, 0.255699934f, 0.255792619f, 0.255885302f, + 0.255977983f, 0.256070662f, 0.256163338f, 0.256256011f, 0.256348682f, + 0.256441351f, 0.256534018f, 0.256626682f, 0.256719344f, 0.256812004f, + 0.256904661f, 0.256997316f, 0.257089968f, 0.257182618f, 0.257275266f, + 0.257367911f, 0.257460554f, 0.257553195f, 0.257645833f, 0.257738469f, + 0.257831102f, 0.257923733f, 0.258016362f, 0.258108988f, 0.258201612f, + 0.258294234f, 0.258386853f, 0.258479470f, 0.258572085f, 0.258664697f, + 0.258757307f, 0.258849914f, 0.258942519f, 0.259035122f, 0.259127722f, + 0.259220320f, 0.259312915f, 0.259405508f, 0.259498099f, 0.259590687f, + 0.259683273f, 0.259775857f, 0.259868438f, 0.259961017f, 0.260053593f, + 0.260146167f, 0.260238739f, 0.260331308f, 0.260423875f, 0.260516439f, + 0.260609001f, 0.260701561f, 0.260794118f, 0.260886673f, 0.260979225f, + 0.261071775f, 0.261164323f, 0.261256868f, 0.261349411f, 0.261441951f, + 0.261534489f, 0.261627025f, 0.261719558f, 0.261812089f, 0.261904617f, + 0.261997143f, 0.262089667f, 0.262182188f, 0.262274707f, 0.262367223f, + 0.262459737f, 0.262552249f, 0.262644758f, 0.262737265f, 0.262829769f, + 0.262922271f, 0.263014770f, 0.263107267f, 0.263199762f, 0.263292254f, + 0.263384744f, 0.263477231f, 0.263569716f, 0.263662199f, 0.263754679f, + 0.263847157f, 0.263939632f, 0.264032105f, 0.264124575f, 0.264217043f, + 0.264309509f, 0.264401972f, 0.264494432f, 0.264586891f, 0.264679346f, + 0.264771800f, 0.264864251f, 0.264956699f, 0.265049145f, 0.265141589f, + 0.265234030f, 0.265326469f, 0.265418905f, 0.265511339f, 0.265603771f, + 0.265696200f, 0.265788626f, 0.265881050f, 0.265973472f, 0.266065891f, + 0.266158308f, 0.266250722f, 0.266343134f, 0.266435544f, 0.266527951f, + 0.266620355f, 0.266712757f, 0.266805157f, 0.266897554f, 0.266989949f, + 0.267082341f, 0.267174731f, 0.267267119f, 0.267359503f, 0.267451886f, + 0.267544266f, 0.267636643f, 0.267729019f, 0.267821391f, 0.267913761f, + 0.268006129f, 0.268098494f, 0.268190857f, 0.268283217f, 0.268375575f, + 0.268467931f, 0.268560283f, 0.268652634f, 0.268744982f, 0.268837327f, + 0.268929670f, 0.269022011f, 0.269114349f, 0.269206685f, 0.269299018f, + 0.269391348f, 0.269483677f, 0.269576002f, 0.269668326f, 0.269760646f, + 0.269852965f, 0.269945280f, 0.270037594f, 0.270129905f, 0.270222213f, + 0.270314519f, 0.270406822f, 0.270499123f, 0.270591421f, 0.270683717f, + 0.270776011f, 0.270868302f, 0.270960590f, 0.271052876f, 0.271145160f, + 0.271237441f, 0.271329719f, 0.271421995f, 0.271514268f, 0.271606539f, + 0.271698808f, 0.271791074f, 0.271883337f, 0.271975598f, 0.272067857f, + 0.272160113f, 0.272252366f, 0.272344617f, 0.272436866f, 0.272529112f, + 0.272621355f, 0.272713596f, 0.272805835f, 0.272898071f, 0.272990304f, + 0.273082535f, 0.273174764f, 0.273266990f, 0.273359213f, 0.273451434f, + 0.273543652f, 0.273635868f, 0.273728082f, 0.273820292f, 0.273912501f, + 0.274004707f, 0.274096910f, 0.274189111f, 0.274281309f, 0.274373505f, + 0.274465698f, 0.274557889f, 0.274650077f, 0.274742262f, 0.274834445f, + 0.274926626f, 0.275018804f, 0.275110980f, 0.275203153f, 0.275295323f, + 0.275387491f, 0.275479656f, 0.275571819f, 0.275663980f, 0.275756137f, + 0.275848293f, 0.275940445f, 0.276032596f, 0.276124743f, 0.276216888f, + 0.276309031f, 0.276401171f, 0.276493309f, 0.276585444f, 0.276677576f, + 0.276769706f, 0.276861833f, 0.276953958f, 0.277046080f, 0.277138200f, + 0.277230317f, 0.277322432f, 0.277414544f, 0.277506653f, 0.277598760f, + 0.277690865f, 0.277782967f, 0.277875066f, 0.277967163f, 0.278059257f, + 0.278151348f, 0.278243438f, 0.278335524f, 0.278427608f, 0.278519689f, + 0.278611768f, 0.278703845f, 0.278795918f, 0.278887989f, 0.278980058f, + 0.279072124f, 0.279164187f, 0.279256248f, 0.279348307f, 0.279440362f, + 0.279532416f, 0.279624466f, 0.279716514f, 0.279808560f, 0.279900603f, + 0.279992643f, 0.280084681f, 0.280176716f, 0.280268749f, 0.280360779f, + 0.280452806f, 0.280544831f, 0.280636853f, 0.280728873f, 0.280820890f, + 0.280912905f, 0.281004917f, 0.281096926f, 0.281188933f, 0.281280937f, + 0.281372939f, 0.281464938f, 0.281556934f, 0.281648928f, 0.281740920f, + 0.281832908f, 0.281924894f, 0.282016878f, 0.282108859f, 0.282200837f, + 0.282292813f, 0.282384786f, 0.282476757f, 0.282568725f, 0.282660690f, + 0.282752653f, 0.282844613f, 0.282936570f, 0.283028525f, 0.283120478f, + 0.283212428f, 0.283304375f, 0.283396319f, 0.283488261f, 0.283580201f, + 0.283672137f, 0.283764071f, 0.283856003f, 0.283947932f, 0.284039858f, + 0.284131782f, 0.284223703f, 0.284315621f, 0.284407537f, 0.284499450f, + 0.284591361f, 0.284683269f, 0.284775174f, 0.284867077f, 0.284958977f, + 0.285050875f, 0.285142770f, 0.285234662f, 0.285326552f, 0.285418439f, + 0.285510323f, 0.285602205f, 0.285694084f, 0.285785961f, 0.285877835f, + 0.285969706f, 0.286061575f, 0.286153441f, 0.286245304f, 0.286337165f, + 0.286429023f, 0.286520879f, 0.286612731f, 0.286704582f, 0.286796429f, + 0.286888274f, 0.286980117f, 0.287071956f, 0.287163793f, 0.287255628f, + 0.287347460f, 0.287439289f, 0.287531115f, 0.287622939f, 0.287714760f, + 0.287806579f, 0.287898395f, 0.287990208f, 0.288082019f, 0.288173827f, + 0.288265632f, 0.288357435f, 0.288449235f, 0.288541032f, 0.288632827f, + 0.288724619f, 0.288816408f, 0.288908195f, 0.288999979f, 0.289091761f, + 0.289183539f, 0.289275315f, 0.289367089f, 0.289458860f, 0.289550628f, + 0.289642393f, 0.289734156f, 0.289825916f, 0.289917674f, 0.290009429f, + 0.290101181f, 0.290192930f, 0.290284677f, 0.290376421f, 0.290468163f, + 0.290559902f, 0.290651638f, 0.290743371f, 0.290835102f, 0.290926830f, + 0.291018556f, 0.291110279f, 0.291201999f, 0.291293716f, 0.291385431f, + 0.291477143f, 0.291568852f, 0.291660559f, 0.291752263f, 0.291843965f, + 0.291935663f, 0.292027359f, 0.292119053f, 0.292210743f, 0.292302431f, + 0.292394116f, 0.292485799f, 0.292577479f, 0.292669156f, 0.292760831f, + 0.292852502f, 0.292944171f, 0.293035838f, 0.293127502f, 0.293219163f, + 0.293310821f, 0.293402477f, 0.293494130f, 0.293585780f, 0.293677427f, + 0.293769072f, 0.293860714f, 0.293952354f, 0.294043991f, 0.294135625f, + 0.294227256f, 0.294318885f, 0.294410511f, 0.294502134f, 0.294593754f, + 0.294685372f, 0.294776987f, 0.294868600f, 0.294960209f, 0.295051816f, + 0.295143421f, 0.295235022f, 0.295326621f, 0.295418217f, 0.295509811f, + 0.295601401f, 0.295692989f, 0.295784574f, 0.295876157f, 0.295967737f, + 0.296059314f, 0.296150888f, 0.296242460f, 0.296334029f, 0.296425595f, + 0.296517159f, 0.296608719f, 0.296700277f, 0.296791833f, 0.296883385f, + 0.296974935f, 0.297066482f, 0.297158027f, 0.297249568f, 0.297341107f, + 0.297432643f, 0.297524177f, 0.297615707f, 0.297707235f, 0.297798761f, + 0.297890283f, 0.297981803f, 0.298073320f, 0.298164834f, 0.298256346f, + 0.298347855f, 0.298439361f, 0.298530864f, 0.298622365f, 0.298713862f, + 0.298805358f, 0.298896850f, 0.298988339f, 0.299079826f, 0.299171310f, + 0.299262792f, 0.299354270f, 0.299445746f, 0.299537219f, 0.299628690f, + 0.299720157f, 0.299811622f, 0.299903084f, 0.299994543f, 0.300086000f, + 0.300177454f, 0.300268905f, 0.300360353f, 0.300451799f, 0.300543241f, + 0.300634681f, 0.300726119f, 0.300817553f, 0.300908985f, 0.301000414f, + 0.301091840f, 0.301183263f, 0.301274684f, 0.301366102f, 0.301457517f, + 0.301548929f, 0.301640339f, 0.301731746f, 0.301823150f, 0.301914551f, + 0.302005949f, 0.302097345f, 0.302188738f, 0.302280128f, 0.302371515f, + 0.302462900f, 0.302554282f, 0.302645661f, 0.302737037f, 0.302828410f, + 0.302919781f, 0.303011149f, 0.303102514f, 0.303193876f, 0.303285236f, + 0.303376593f, 0.303467947f, 0.303559298f, 0.303650646f, 0.303741992f, + 0.303833334f, 0.303924674f, 0.304016012f, 0.304107346f, 0.304198678f, + 0.304290006f, 0.304381332f, 0.304472656f, 0.304563976f, 0.304655294f, + 0.304746609f, 0.304837921f, 0.304929230f, 0.305020536f, 0.305111840f, + 0.305203141f, 0.305294439f, 0.305385734f, 0.305477026f, 0.305568316f, + 0.305659602f, 0.305750886f, 0.305842168f, 0.305933446f, 0.306024721f, + 0.306115994f, 0.306207264f, 0.306298531f, 0.306389795f, 0.306481057f, + 0.306572315f, 0.306663571f, 0.306754824f, 0.306846074f, 0.306937322f, + 0.307028566f, 0.307119808f, 0.307211047f, 0.307302283f, 0.307393516f, + 0.307484747f, 0.307575974f, 0.307667199f, 0.307758421f, 0.307849640f, + 0.307940856f, 0.308032070f, 0.308123280f, 0.308214488f, 0.308305693f, + 0.308396895f, 0.308488094f, 0.308579291f, 0.308670485f, 0.308761675f, + 0.308852863f, 0.308944048f, 0.309035231f, 0.309126410f, 0.309217587f, + 0.309308760f, 0.309399931f, 0.309491099f, 0.309582264f, 0.309673427f, + 0.309764586f, 0.309855743f, 0.309946897f, 0.310038048f, 0.310129196f, + 0.310220341f, 0.310311484f, 0.310402623f, 0.310493760f, 0.310584894f, + 0.310676025f, 0.310767153f, 0.310858278f, 0.310949400f, 0.311040520f, + 0.311131637f, 0.311222751f, 0.311313862f, 0.311404970f, 0.311496075f, + 0.311587177f, 0.311678277f, 0.311769374f, 0.311860467f, 0.311951558f, + 0.312042646f, 0.312133732f, 0.312224814f, 0.312315893f, 0.312406970f, + 0.312498044f, 0.312589115f, 0.312680183f, 0.312771248f, 0.312862310f, + 0.312953369f, 0.313044426f, 0.313135479f, 0.313226530f, 0.313317578f, + 0.313408623f, 0.313499665f, 0.313590704f, 0.313681740f, 0.313772774f, + 0.313863804f, 0.313954832f, 0.314045857f, 0.314136879f, 0.314227898f, + 0.314318914f, 0.314409927f, 0.314500937f, 0.314591945f, 0.314682949f, + 0.314773951f, 0.314864950f, 0.314955946f, 0.315046939f, 0.315137929f, + 0.315228916f, 0.315319900f, 0.315410882f, 0.315501860f, 0.315592836f, + 0.315683808f, 0.315774778f, 0.315865745f, 0.315956709f, 0.316047670f, + 0.316138628f, 0.316229584f, 0.316320536f, 0.316411485f, 0.316502432f, + 0.316593376f, 0.316684316f, 0.316775254f, 0.316866189f, 0.316957121f, + 0.317048050f, 0.317138976f, 0.317229899f, 0.317320820f, 0.317411737f, + 0.317502652f, 0.317593563f, 0.317684472f, 0.317775378f, 0.317866281f, + 0.317957180f, 0.318048077f, 0.318138971f, 0.318229863f, 0.318320751f, + 0.318411636f, 0.318502518f, 0.318593398f, 0.318684274f, 0.318775148f, + 0.318866018f, 0.318956886f, 0.319047751f, 0.319138613f, 0.319229472f, + 0.319320328f, 0.319411181f, 0.319502031f, 0.319592878f, 0.319683722f, + 0.319774563f, 0.319865402f, 0.319956237f, 0.320047070f, 0.320137899f, + 0.320228726f, 0.320319549f, 0.320410370f, 0.320501188f, 0.320592003f, + 0.320682815f, 0.320773623f, 0.320864429f, 0.320955232f, 0.321046032f, + 0.321136830f, 0.321227624f, 0.321318415f, 0.321409203f, 0.321499989f, + 0.321590771f, 0.321681550f, 0.321772327f, 0.321863100f, 0.321953871f, + 0.322044638f, 0.322135403f, 0.322226164f, 0.322316923f, 0.322407679f, + 0.322498432f, 0.322589181f, 0.322679928f, 0.322770672f, 0.322861413f, + 0.322952151f, 0.323042886f, 0.323133618f, 0.323224347f, 0.323315073f, + 0.323405796f, 0.323496516f, 0.323587233f, 0.323677947f, 0.323768658f, + 0.323859367f, 0.323950072f, 0.324040774f, 0.324131473f, 0.324222170f, + 0.324312863f, 0.324403553f, 0.324494240f, 0.324584925f, 0.324675606f, + 0.324766285f, 0.324856960f, 0.324947632f, 0.325038302f, 0.325128968f, + 0.325219632f, 0.325310292f, 0.325400950f, 0.325491604f, 0.325582256f, + 0.325672904f, 0.325763550f, 0.325854192f, 0.325944832f, 0.326035468f, + 0.326126102f, 0.326216732f, 0.326307360f, 0.326397984f, 0.326488606f, + 0.326579224f, 0.326669840f, 0.326760452f, 0.326851062f, 0.326941668f, + 0.327032272f, 0.327122872f, 0.327213470f, 0.327304064f, 0.327394656f, + 0.327485244f, 0.327575830f, 0.327666412f, 0.327756992f, 0.327847568f, + 0.327938141f, 0.328028712f, 0.328119279f, 0.328209844f, 0.328300405f, + 0.328390963f, 0.328481519f, 0.328572071f, 0.328662620f, 0.328753166f, + 0.328843710f, 0.328934250f, 0.329024787f, 0.329115321f, 0.329205852f, + 0.329296380f, 0.329386905f, 0.329477428f, 0.329567947f, 0.329658463f, + 0.329748975f, 0.329839485f, 0.329929992f, 0.330020496f, 0.330110997f, + 0.330201495f, 0.330291990f, 0.330382481f, 0.330472970f, 0.330563456f, + 0.330653938f, 0.330744418f, 0.330834894f, 0.330925368f, 0.331015838f, + 0.331106306f, 0.331196770f, 0.331287231f, 0.331377690f, 0.331468145f, + 0.331558597f, 0.331649046f, 0.331739492f, 0.331829935f, 0.331920375f, + 0.332010812f, 0.332101246f, 0.332191677f, 0.332282105f, 0.332372530f, + 0.332462951f, 0.332553370f, 0.332643785f, 0.332734198f, 0.332824607f, + 0.332915014f, 0.333005417f, 0.333095817f, 0.333186215f, 0.333276609f, + 0.333367000f, 0.333457388f, 0.333547773f, 0.333638155f, 0.333728533f, + 0.333818909f, 0.333909282f, 0.333999651f, 0.334090018f, 0.334180381f, + 0.334270742f, 0.334361099f, 0.334451453f, 0.334541805f, 0.334632153f, + 0.334722498f, 0.334812840f, 0.334903179f, 0.334993514f, 0.335083847f, + 0.335174177f, 0.335264503f, 0.335354827f, 0.335445147f, 0.335535464f, + 0.335625779f, 0.335716090f, 0.335806398f, 0.335896703f, 0.335987005f, + 0.336077303f, 0.336167599f, 0.336257892f, 0.336348181f, 0.336438468f, + 0.336528751f, 0.336619031f, 0.336709308f, 0.336799582f, 0.336889853f, + 0.336980121f, 0.337070386f, 0.337160648f, 0.337250906f, 0.337341162f, + 0.337431414f, 0.337521663f, 0.337611909f, 0.337702153f, 0.337792392f, + 0.337882629f, 0.337972863f, 0.338063094f, 0.338153321f, 0.338243546f, + 0.338333767f, 0.338423985f, 0.338514200f, 0.338604412f, 0.338694621f, + 0.338784827f, 0.338875029f, 0.338965229f, 0.339055425f, 0.339145619f, + 0.339235809f, 0.339325996f, 0.339416180f, 0.339506361f, 0.339596538f, + 0.339686713f, 0.339776884f, 0.339867053f, 0.339957218f, 0.340047380f, + 0.340137539f, 0.340227695f, 0.340317848f, 0.340407997f, 0.340498144f, + 0.340588287f, 0.340678427f, 0.340768564f, 0.340858698f, 0.340948829f, + 0.341038956f, 0.341129081f, 0.341219202f, 0.341309321f, 0.341399436f, + 0.341489548f, 0.341579656f, 0.341669762f, 0.341759865f, 0.341849964f, + 0.341940060f, 0.342030154f, 0.342120243f, 0.342210330f, 0.342300414f, + 0.342390495f, 0.342480572f, 0.342570646f, 0.342660717f, 0.342750785f, + 0.342840850f, 0.342930912f, 0.343020970f, 0.343111026f, 0.343201078f, + 0.343291127f, 0.343381173f, 0.343471215f, 0.343561255f, 0.343651291f, + 0.343741325f, 0.343831355f, 0.343921382f, 0.344011405f, 0.344101426f, + 0.344191443f, 0.344281458f, 0.344371469f, 0.344461477f, 0.344551482f, + 0.344641483f, 0.344731482f, 0.344821477f, 0.344911469f, 0.345001458f, + 0.345091444f, 0.345181426f, 0.345271406f, 0.345361382f, 0.345451355f, + 0.345541325f, 0.345631292f, 0.345721255f, 0.345811216f, 0.345901173f, + 0.345991127f, 0.346081078f, 0.346171025f, 0.346260970f, 0.346350911f, + 0.346440849f, 0.346530784f, 0.346620716f, 0.346710644f, 0.346800570f, + 0.346890492f, 0.346980411f, 0.347070327f, 0.347160239f, 0.347250149f, + 0.347340055f, 0.347429958f, 0.347519858f, 0.347609754f, 0.347699648f, + 0.347789538f, 0.347879425f, 0.347969309f, 0.348059190f, 0.348149067f, + 0.348238941f, 0.348328812f, 0.348418680f, 0.348508545f, 0.348598406f, + 0.348688265f, 0.348778120f, 0.348867971f, 0.348957820f, 0.349047666f, + 0.349137508f, 0.349227347f, 0.349317183f, 0.349407015f, 0.349496844f, + 0.349586671f, 0.349676494f, 0.349766313f, 0.349856130f, 0.349945943f, + 0.350035753f, 0.350125560f, 0.350215364f, 0.350305164f, 0.350394961f, + 0.350484755f, 0.350574546f, 0.350664334f, 0.350754118f, 0.350843899f, + 0.350933677f, 0.351023452f, 0.351113223f, 0.351202991f, 0.351292756f, + 0.351382518f, 0.351472276f, 0.351562032f, 0.351651784f, 0.351741532f, + 0.351831278f, 0.351921020f, 0.352010759f, 0.352100495f, 0.352190228f, + 0.352279957f, 0.352369684f, 0.352459406f, 0.352549126f, 0.352638843f, + 0.352728556f, 0.352818266f, 0.352907972f, 0.352997676f, 0.353087376f, + 0.353177073f, 0.353266767f, 0.353356457f, 0.353446145f, 0.353535829f, + 0.353625509f, 0.353715187f, 0.353804861f, 0.353894532f, 0.353984200f, + 0.354073864f, 0.354163525f, 0.354253183f, 0.354342838f, 0.354432490f, + 0.354522138f, 0.354611783f, 0.354701424f, 0.354791063f, 0.354880698f, + 0.354970330f, 0.355059958f, 0.355149584f, 0.355239206f, 0.355328825f, + 0.355418440f, 0.355508053f, 0.355597662f, 0.355687267f, 0.355776870f, + 0.355866469f, 0.355956065f, 0.356045658f, 0.356135247f, 0.356224833f, + 0.356314416f, 0.356403996f, 0.356493572f, 0.356583145f, 0.356672715f, + 0.356762281f, 0.356851845f, 0.356941405f, 0.357030961f, 0.357120515f, + 0.357210065f, 0.357299611f, 0.357389155f, 0.357478695f, 0.357568232f, + 0.357657766f, 0.357747296f, 0.357836823f, 0.357926347f, 0.358015868f, + 0.358105385f, 0.358194899f, 0.358284409f, 0.358373917f, 0.358463421f, + 0.358552921f, 0.358642419f, 0.358731913f, 0.358821404f, 0.358910891f, + 0.359000376f, 0.359089857f, 0.359179334f, 0.359268809f, 0.359358280f, + 0.359447747f, 0.359537212f, 0.359626673f, 0.359716131f, 0.359805585f, + 0.359895037f, 0.359984484f, 0.360073929f, 0.360163370f, 0.360252808f, + 0.360342243f, 0.360431674f, 0.360521102f, 0.360610527f, 0.360699949f, + 0.360789367f, 0.360878781f, 0.360968193f, 0.361057601f, 0.361147006f, + 0.361236407f, 0.361325806f, 0.361415200f, 0.361504592f, 0.361593980f, + 0.361683365f, 0.361772747f, 0.361862125f, 0.361951500f, 0.362040871f, + 0.362130240f, 0.362219605f, 0.362308966f, 0.362398325f, 0.362487680f, + 0.362577031f, 0.362666379f, 0.362755724f, 0.362845066f, 0.362934404f, + 0.363023739f, 0.363113071f, 0.363202399f, 0.363291724f, 0.363381046f, + 0.363470364f, 0.363559679f, 0.363648990f, 0.363738299f, 0.363827603f, + 0.363916905f, 0.364006203f, 0.364095498f, 0.364184790f, 0.364274078f, + 0.364363363f, 0.364452644f, 0.364541922f, 0.364631197f, 0.364720468f, + 0.364809736f, 0.364899001f, 0.364988262f, 0.365077520f, 0.365166775f, + 0.365256026f, 0.365345274f, 0.365434519f, 0.365523760f, 0.365612998f, + 0.365702232f, 0.365791463f, 0.365880691f, 0.365969916f, 0.366059137f, + 0.366148354f, 0.366237569f, 0.366326780f, 0.366415987f, 0.366505191f, + 0.366594392f, 0.366683590f, 0.366772784f, 0.366861974f, 0.366951162f, + 0.367040346f, 0.367129526f, 0.367218704f, 0.367307877f, 0.367397048f, + 0.367486215f, 0.367575379f, 0.367664539f, 0.367753696f, 0.367842850f, + 0.367932000f, 0.368021147f, 0.368110290f, 0.368199430f, 0.368288567f, + 0.368377700f, 0.368466830f, 0.368555956f, 0.368645080f, 0.368734199f, + 0.368823316f, 0.368912429f, 0.369001538f, 0.369090644f, 0.369179747f, + 0.369268847f, 0.369357943f, 0.369447035f, 0.369536124f, 0.369625210f, + 0.369714293f, 0.369803372f, 0.369892447f, 0.369981519f, 0.370070588f, + 0.370159654f, 0.370248716f, 0.370337774f, 0.370426829f, 0.370515881f, + 0.370604930f, 0.370693975f, 0.370783016f, 0.370872054f, 0.370961089f, + 0.371050120f, 0.371139148f, 0.371228173f, 0.371317194f, 0.371406212f, + 0.371495226f, 0.371584237f, 0.371673244f, 0.371762248f, 0.371851249f, + 0.371940246f, 0.372029240f, 0.372118230f, 0.372207217f, 0.372296201f, + 0.372385181f, 0.372474158f, 0.372563131f, 0.372652101f, 0.372741067f, + 0.372830030f, 0.372918990f, 0.373007946f, 0.373096898f, 0.373185848f, + 0.373274793f, 0.373363736f, 0.373452675f, 0.373541610f, 0.373630542f, + 0.373719471f, 0.373808396f, 0.373897318f, 0.373986237f, 0.374075151f, + 0.374164063f, 0.374252971f, 0.374341876f, 0.374430777f, 0.374519675f, + 0.374608569f, 0.374697460f, 0.374786347f, 0.374875231f, 0.374964112f, + 0.375052989f, 0.375141862f, 0.375230732f, 0.375319599f, 0.375408462f, + 0.375497322f, 0.375586178f, 0.375675031f, 0.375763881f, 0.375852727f, + 0.375941569f, 0.376030408f, 0.376119244f, 0.376208076f, 0.376296905f, + 0.376385730f, 0.376474552f, 0.376563370f, 0.376652185f, 0.376740997f, + 0.376829805f, 0.376918609f, 0.377007410f, 0.377096208f, 0.377185002f, + 0.377273793f, 0.377362580f, 0.377451363f, 0.377540144f, 0.377628920f, + 0.377717694f, 0.377806463f, 0.377895230f, 0.377983993f, 0.378072752f, + 0.378161508f, 0.378250260f, 0.378339009f, 0.378427755f, 0.378516497f, + 0.378605235f, 0.378693970f, 0.378782702f, 0.378871430f, 0.378960155f, + 0.379048876f, 0.379137593f, 0.379226308f, 0.379315018f, 0.379403725f, + 0.379492429f, 0.379581129f, 0.379669826f, 0.379758519f, 0.379847209f, + 0.379935895f, 0.380024578f, 0.380113257f, 0.380201933f, 0.380290605f, + 0.380379274f, 0.380467939f, 0.380556601f, 0.380645259f, 0.380733914f, + 0.380822565f, 0.380911213f, 0.380999857f, 0.381088498f, 0.381177135f, + 0.381265769f, 0.381354399f, 0.381443026f, 0.381531650f, 0.381620269f, + 0.381708885f, 0.381797498f, 0.381886107f, 0.381974713f, 0.382063315f, + 0.382151914f, 0.382240509f, 0.382329101f, 0.382417689f, 0.382506274f, + 0.382594855f, 0.382683432f, 0.382772006f, 0.382860577f, 0.382949144f, + 0.383037708f, 0.383126268f, 0.383214824f, 0.383303377f, 0.383391926f, + 0.383480472f, 0.383569015f, 0.383657554f, 0.383746089f, 0.383834621f, + 0.383923149f, 0.384011674f, 0.384100195f, 0.384188713f, 0.384277227f, + 0.384365737f, 0.384454245f, 0.384542748f, 0.384631248f, 0.384719745f, + 0.384808238f, 0.384896727f, 0.384985213f, 0.385073695f, 0.385162174f, + 0.385250649f, 0.385339121f, 0.385427589f, 0.385516054f, 0.385604515f, + 0.385692972f, 0.385781426f, 0.385869877f, 0.385958324f, 0.386046767f, + 0.386135207f, 0.386223643f, 0.386312076f, 0.386400505f, 0.386488931f, + 0.386577353f, 0.386665771f, 0.386754186f, 0.386842598f, 0.386931006f, + 0.387019410f, 0.387107811f, 0.387196208f, 0.387284601f, 0.387372991f, + 0.387461378f, 0.387549761f, 0.387638140f, 0.387726516f, 0.387814888f, + 0.387903257f, 0.387991622f, 0.388079983f, 0.388168341f, 0.388256696f, + 0.388345047f, 0.388433394f, 0.388521738f, 0.388610078f, 0.388698414f, + 0.388786747f, 0.388875077f, 0.388963403f, 0.389051725f, 0.389140044f, + 0.389228359f, 0.389316670f, 0.389404978f, 0.389493282f, 0.389581583f, + 0.389669880f, 0.389758174f, 0.389846464f, 0.389934751f, 0.390023033f, + 0.390111313f, 0.390199588f, 0.390287861f, 0.390376129f, 0.390464394f, + 0.390552655f, 0.390640913f, 0.390729167f, 0.390817418f, 0.390905665f, + 0.390993908f, 0.391082148f, 0.391170384f, 0.391258617f, 0.391346846f, + 0.391435071f, 0.391523293f, 0.391611511f, 0.391699726f, 0.391787937f, + 0.391876144f, 0.391964348f, 0.392052548f, 0.392140745f, 0.392228938f, + 0.392317128f, 0.392405313f, 0.392493495f, 0.392581674f, 0.392669849f, + 0.392758020f, 0.392846188f, 0.392934352f, 0.393022513f, 0.393110670f, + 0.393198823f, 0.393286973f, 0.393375119f, 0.393463261f, 0.393551400f, + 0.393639535f, 0.393727667f, 0.393815795f, 0.393903919f, 0.393992040f, + 0.394080157f, 0.394168271f, 0.394256381f, 0.394344487f, 0.394432589f, + 0.394520688f, 0.394608784f, 0.394696876f, 0.394784964f, 0.394873048f, + 0.394961129f, 0.395049206f, 0.395137280f, 0.395225350f, 0.395313416f, + 0.395401479f, 0.395489538f, 0.395577593f, 0.395665645f, 0.395753693f, + 0.395841738f, 0.395929779f, 0.396017816f, 0.396105850f, 0.396193880f, + 0.396281906f, 0.396369929f, 0.396457948f, 0.396545963f, 0.396633975f, + 0.396721983f, 0.396809987f, 0.396897988f, 0.396985985f, 0.397073979f, + 0.397161969f, 0.397249955f, 0.397337938f, 0.397425916f, 0.397513892f, + 0.397601863f, 0.397689831f, 0.397777796f, 0.397865756f, 0.397953713f, + 0.398041666f, 0.398129616f, 0.398217562f, 0.398305504f, 0.398393443f, + 0.398481378f, 0.398569310f, 0.398657237f, 0.398745161f, 0.398833082f, + 0.398920998f, 0.399008911f, 0.399096821f, 0.399184726f, 0.399272628f, + 0.399360527f, 0.399448421f, 0.399536313f, 0.399624200f, 0.399712084f, + 0.399799964f, 0.399887840f, 0.399975712f, 0.400063581f, 0.400151447f, + 0.400239308f, 0.400327166f, 0.400415021f, 0.400502871f, 0.400590718f, + 0.400678561f, 0.400766401f, 0.400854237f, 0.400942069f, 0.401029897f, + 0.401117722f, 0.401205543f, 0.401293360f, 0.401381174f, 0.401468984f, + 0.401556791f, 0.401644593f, 0.401732392f, 0.401820187f, 0.401907979f, + 0.401995767f, 0.402083551f, 0.402171332f, 0.402259108f, 0.402346881f, + 0.402434651f, 0.402522417f, 0.402610179f, 0.402697937f, 0.402785691f, + 0.402873442f, 0.402961190f, 0.403048933f, 0.403136673f, 0.403224409f, + 0.403312141f, 0.403399870f, 0.403487595f, 0.403575316f, 0.403663034f, + 0.403750747f, 0.403838458f, 0.403926164f, 0.404013867f, 0.404101566f, + 0.404189261f, 0.404276952f, 0.404364640f, 0.404452324f, 0.404540005f, + 0.404627681f, 0.404715354f, 0.404803024f, 0.404890689f, 0.404978351f, + 0.405066009f, 0.405153663f, 0.405241314f, 0.405328961f, 0.405416604f, + 0.405504244f, 0.405591879f, 0.405679511f, 0.405767140f, 0.405854764f, + 0.405942385f, 0.406030002f, 0.406117615f, 0.406205225f, 0.406292831f, + 0.406380433f, 0.406468031f, 0.406555626f, 0.406643217f, 0.406730804f, + 0.406818388f, 0.406905967f, 0.406993543f, 0.407081115f, 0.407168684f, + 0.407256249f, 0.407343810f, 0.407431367f, 0.407518920f, 0.407606470f, + 0.407694016f, 0.407781559f, 0.407869097f, 0.407956632f, 0.408044163f, + 0.408131690f, 0.408219214f, 0.408306733f, 0.408394249f, 0.408481762f, + 0.408569270f, 0.408656775f, 0.408744276f, 0.408831773f, 0.408919267f, + 0.409006756f, 0.409094242f, 0.409181725f, 0.409269203f, 0.409356678f, + 0.409444149f, 0.409531616f, 0.409619079f, 0.409706539f, 0.409793995f, + 0.409881447f, 0.409968895f, 0.410056340f, 0.410143781f, 0.410231218f, + 0.410318651f, 0.410406080f, 0.410493506f, 0.410580928f, 0.410668346f, + 0.410755760f, 0.410843171f, 0.410930578f, 0.411017981f, 0.411105380f, + 0.411192776f, 0.411280167f, 0.411367555f, 0.411454940f, 0.411542320f, + 0.411629697f, 0.411717069f, 0.411804438f, 0.411891804f, 0.411979165f, + 0.412066523f, 0.412153877f, 0.412241227f, 0.412328573f, 0.412415915f, + 0.412503254f, 0.412590589f, 0.412677920f, 0.412765248f, 0.412852571f, + 0.412939891f, 0.413027207f, 0.413114519f, 0.413201827f, 0.413289132f, + 0.413376433f, 0.413463730f, 0.413551023f, 0.413638312f, 0.413725598f, + 0.413812880f, 0.413900158f, 0.413987432f, 0.414074702f, 0.414161969f, + 0.414249231f, 0.414336490f, 0.414423745f, 0.414510997f, 0.414598244f, + 0.414685488f, 0.414772728f, 0.414859964f, 0.414947196f, 0.415034424f, + 0.415121649f, 0.415208870f, 0.415296087f, 0.415383300f, 0.415470509f, + 0.415557715f, 0.415644917f, 0.415732115f, 0.415819309f, 0.415906499f, + 0.415993685f, 0.416080868f, 0.416168047f, 0.416255222f, 0.416342393f, + 0.416429560f, 0.416516724f, 0.416603883f, 0.416691039f, 0.416778191f, + 0.416865339f, 0.416952484f, 0.417039624f, 0.417126761f, 0.417213893f, + 0.417301022f, 0.417388148f, 0.417475269f, 0.417562386f, 0.417649500f, + 0.417736610f, 0.417823716f, 0.417910818f, 0.417997916f, 0.418085011f, + 0.418172101f, 0.418259188f, 0.418346271f, 0.418433350f, 0.418520425f, + 0.418607497f, 0.418694564f, 0.418781628f, 0.418868688f, 0.418955744f, + 0.419042796f, 0.419129844f, 0.419216888f, 0.419303929f, 0.419390966f, + 0.419477998f, 0.419565027f, 0.419652053f, 0.419739074f, 0.419826091f, + 0.419913105f, 0.420000115f, 0.420087120f, 0.420174122f, 0.420261121f, + 0.420348115f, 0.420435105f, 0.420522092f, 0.420609074f, 0.420696053f, + 0.420783028f, 0.420869999f, 0.420956966f, 0.421043930f, 0.421130889f, + 0.421217845f, 0.421304797f, 0.421391744f, 0.421478688f, 0.421565628f, + 0.421652565f, 0.421739497f, 0.421826425f, 0.421913350f, 0.422000271f, + 0.422087188f, 0.422174101f, 0.422261010f, 0.422347915f, 0.422434816f, + 0.422521714f, 0.422608607f, 0.422695497f, 0.422782383f, 0.422869264f, + 0.422956142f, 0.423043017f, 0.423129887f, 0.423216753f, 0.423303616f, + 0.423390474f, 0.423477329f, 0.423564180f, 0.423651026f, 0.423737869f, + 0.423824709f, 0.423911544f, 0.423998375f, 0.424085202f, 0.424172026f, + 0.424258846f, 0.424345661f, 0.424432473f, 0.424519281f, 0.424606085f, + 0.424692885f, 0.424779681f, 0.424866473f, 0.424953262f, 0.425040046f, + 0.425126827f, 0.425213604f, 0.425300376f, 0.425387145f, 0.425473910f, + 0.425560671f, 0.425647428f, 0.425734181f, 0.425820931f, 0.425907676f, + 0.425994418f, 0.426081155f, 0.426167889f, 0.426254618f, 0.426341344f, + 0.426428066f, 0.426514784f, 0.426601498f, 0.426688208f, 0.426774914f, + 0.426861617f, 0.426948315f, 0.427035009f, 0.427121700f, 0.427208386f, + 0.427295069f, 0.427381748f, 0.427468423f, 0.427555093f, 0.427641760f, + 0.427728423f, 0.427815082f, 0.427901738f, 0.427988389f, 0.428075036f, + 0.428161679f, 0.428248319f, 0.428334954f, 0.428421586f, 0.428508213f, + 0.428594837f, 0.428681457f, 0.428768072f, 0.428854684f, 0.428941292f, + 0.429027896f, 0.429114496f, 0.429201092f, 0.429287684f, 0.429374272f, + 0.429460856f, 0.429547437f, 0.429634013f, 0.429720585f, 0.429807154f, + 0.429893718f, 0.429980279f, 0.430066835f, 0.430153388f, 0.430239937f, + 0.430326481f, 0.430413022f, 0.430499559f, 0.430586092f, 0.430672621f, + 0.430759145f, 0.430845666f, 0.430932183f, 0.431018696f, 0.431105206f, + 0.431191711f, 0.431278212f, 0.431364709f, 0.431451202f, 0.431537691f, + 0.431624177f, 0.431710658f, 0.431797135f, 0.431883609f, 0.431970078f, + 0.432056544f, 0.432143005f, 0.432229463f, 0.432315916f, 0.432402366f, + 0.432488811f, 0.432575253f, 0.432661690f, 0.432748124f, 0.432834554f, + 0.432920979f, 0.433007401f, 0.433093819f, 0.433180233f, 0.433266642f, + 0.433353048f, 0.433439450f, 0.433525848f, 0.433612242f, 0.433698631f, + 0.433785017f, 0.433871399f, 0.433957777f, 0.434044151f, 0.434130521f, + 0.434216887f, 0.434303249f, 0.434389607f, 0.434475961f, 0.434562311f, + 0.434648656f, 0.434734998f, 0.434821336f, 0.434907670f, 0.434994000f, + 0.435080326f, 0.435166648f, 0.435252966f, 0.435339280f, 0.435425590f, + 0.435511896f, 0.435598198f, 0.435684496f, 0.435770790f, 0.435857080f, + 0.435943366f, 0.436029648f, 0.436115926f, 0.436202200f, 0.436288470f, + 0.436374735f, 0.436460997f, 0.436547255f, 0.436633509f, 0.436719759f, + 0.436806005f, 0.436892247f, 0.436978484f, 0.437064718f, 0.437150948f, + 0.437237174f, 0.437323395f, 0.437409613f, 0.437495827f, 0.437582036f, + 0.437668242f, 0.437754444f, 0.437840641f, 0.437926835f, 0.438013024f, + 0.438099210f, 0.438185391f, 0.438271569f, 0.438357742f, 0.438443912f, + 0.438530077f, 0.438616239f, 0.438702396f, 0.438788549f, 0.438874698f, + 0.438960844f, 0.439046985f, 0.439133122f, 0.439219255f, 0.439305384f, + 0.439391509f, 0.439477630f, 0.439563747f, 0.439649860f, 0.439735969f, + 0.439822074f, 0.439908175f, 0.439994271f, 0.440080364f, 0.440166453f, + 0.440252537f, 0.440338618f, 0.440424694f, 0.440510767f, 0.440596835f, + 0.440682900f, 0.440768960f, 0.440855016f, 0.440941068f, 0.441027117f, + 0.441113161f, 0.441199201f, 0.441285237f, 0.441371269f, 0.441457297f, + 0.441543320f, 0.441629340f, 0.441715356f, 0.441801368f, 0.441887375f, + 0.441973379f, 0.442059378f, 0.442145374f, 0.442231365f, 0.442317352f, + 0.442403335f, 0.442489315f, 0.442575290f, 0.442661261f, 0.442747228f, + 0.442833190f, 0.442919149f, 0.443005104f, 0.443091055f, 0.443177001f, + 0.443262944f, 0.443348882f, 0.443434816f, 0.443520747f, 0.443606673f, + 0.443692595f, 0.443778513f, 0.443864427f, 0.443950337f, 0.444036243f, + 0.444122145f, 0.444208042f, 0.444293936f, 0.444379825f, 0.444465711f, + 0.444551592f, 0.444637469f, 0.444723342f, 0.444809211f, 0.444895076f, + 0.444980937f, 0.445066794f, 0.445152647f, 0.445238495f, 0.445324340f, + 0.445410180f, 0.445496017f, 0.445581849f, 0.445667677f, 0.445753501f, + 0.445839321f, 0.445925137f, 0.446010948f, 0.446096756f, 0.446182560f, + 0.446268359f, 0.446354154f, 0.446439946f, 0.446525733f, 0.446611516f, + 0.446697295f, 0.446783069f, 0.446868840f, 0.446954607f, 0.447040369f, + 0.447126128f, 0.447211882f, 0.447297632f, 0.447383378f, 0.447469120f, + 0.447554858f, 0.447640592f, 0.447726321f, 0.447812047f, 0.447897768f, + 0.447983485f, 0.448069198f, 0.448154907f, 0.448240612f, 0.448326313f, + 0.448412010f, 0.448497702f, 0.448583391f, 0.448669075f, 0.448754755f, + 0.448840431f, 0.448926103f, 0.449011771f, 0.449097434f, 0.449183094f, + 0.449268749f, 0.449354401f, 0.449440048f, 0.449525691f, 0.449611330f, + 0.449696964f, 0.449782595f, 0.449868221f, 0.449953844f, 0.450039462f, + 0.450125076f, 0.450210686f, 0.450296292f, 0.450381893f, 0.450467491f, + 0.450553084f, 0.450638674f, 0.450724259f, 0.450809840f, 0.450895416f, + 0.450980989f, 0.451066558f, 0.451152122f, 0.451237682f, 0.451323238f, + 0.451408790f, 0.451494338f, 0.451579882f, 0.451665421f, 0.451750956f, + 0.451836487f, 0.451922014f, 0.452007537f, 0.452093056f, 0.452178571f, + 0.452264081f, 0.452349587f, 0.452435089f, 0.452520587f, 0.452606081f, + 0.452691571f, 0.452777056f, 0.452862537f, 0.452948014f, 0.453033487f, + 0.453118956f, 0.453204421f, 0.453289881f, 0.453375338f, 0.453460790f, + 0.453546238f, 0.453631681f, 0.453717121f, 0.453802556f, 0.453887988f, + 0.453973415f, 0.454058838f, 0.454144257f, 0.454229671f, 0.454315081f, + 0.454400488f, 0.454485890f, 0.454571288f, 0.454656681f, 0.454742071f, + 0.454827456f, 0.454912837f, 0.454998214f, 0.455083587f, 0.455168956f, + 0.455254320f, 0.455339680f, 0.455425036f, 0.455510388f, 0.455595736f, + 0.455681080f, 0.455766419f, 0.455851754f, 0.455937085f, 0.456022412f, + 0.456107734f, 0.456193053f, 0.456278367f, 0.456363677f, 0.456448982f, + 0.456534284f, 0.456619581f, 0.456704875f, 0.456790164f, 0.456875448f, + 0.456960729f, 0.457046005f, 0.457131277f, 0.457216545f, 0.457301809f, + 0.457387069f, 0.457472324f, 0.457557575f, 0.457642822f, 0.457728065f, + 0.457813304f, 0.457898538f, 0.457983768f, 0.458068994f, 0.458154216f, + 0.458239433f, 0.458324646f, 0.458409856f, 0.458495060f, 0.458580261f, + 0.458665457f, 0.458750650f, 0.458835838f, 0.458921021f, 0.459006201f, + 0.459091376f, 0.459176548f, 0.459261714f, 0.459346877f, 0.459432036f, + 0.459517190f, 0.459602340f, 0.459687486f, 0.459772627f, 0.459857765f, + 0.459942898f, 0.460028026f, 0.460113151f, 0.460198272f, 0.460283388f, + 0.460368500f, 0.460453607f, 0.460538711f, 0.460623810f, 0.460708905f, + 0.460793996f, 0.460879083f, 0.460964165f, 0.461049243f, 0.461134317f, + 0.461219386f, 0.461304452f, 0.461389513f, 0.461474570f, 0.461559623f, + 0.461644671f, 0.461729715f, 0.461814755f, 0.461899791f, 0.461984822f, + 0.462069849f, 0.462154872f, 0.462239891f, 0.462324905f, 0.462409916f, + 0.462494922f, 0.462579923f, 0.462664921f, 0.462749914f, 0.462834903f, + 0.462919887f, 0.463004868f, 0.463089844f, 0.463174816f, 0.463259784f, + 0.463344747f, 0.463429706f, 0.463514661f, 0.463599612f, 0.463684558f, + 0.463769500f, 0.463854438f, 0.463939371f, 0.464024301f, 0.464109226f, + 0.464194146f, 0.464279063f, 0.464363975f, 0.464448883f, 0.464533787f, + 0.464618686f, 0.464703581f, 0.464788472f, 0.464873359f, 0.464958241f, + 0.465043119f, 0.465127993f, 0.465212863f, 0.465297728f, 0.465382589f, + 0.465467446f, 0.465552298f, 0.465637146f, 0.465721990f, 0.465806829f, + 0.465891665f, 0.465976496f, 0.466061322f, 0.466146145f, 0.466230963f, + 0.466315777f, 0.466400587f, 0.466485392f, 0.466570193f, 0.466654990f, + 0.466739782f, 0.466824570f, 0.466909354f, 0.466994133f, 0.467078909f, + 0.467163680f, 0.467248446f, 0.467333209f, 0.467417967f, 0.467502721f, + 0.467587470f, 0.467672215f, 0.467756956f, 0.467841693f, 0.467926425f, + 0.468011153f, 0.468095877f, 0.468180596f, 0.468265311f, 0.468350022f, + 0.468434728f, 0.468519431f, 0.468604128f, 0.468688822f, 0.468773511f, + 0.468858196f, 0.468942877f, 0.469027553f, 0.469112225f, 0.469196893f, + 0.469281556f, 0.469366215f, 0.469450870f, 0.469535520f, 0.469620167f, + 0.469704808f, 0.469789446f, 0.469874079f, 0.469958708f, 0.470043332f, + 0.470127953f, 0.470212569f, 0.470297180f, 0.470381787f, 0.470466390f, + 0.470550989f, 0.470635583f, 0.470720173f, 0.470804759f, 0.470889340f, + 0.470973917f, 0.471058490f, 0.471143058f, 0.471227622f, 0.471312182f, + 0.471396737f, 0.471481288f, 0.471565834f, 0.471650377f, 0.471734915f, + 0.471819448f, 0.471903978f, 0.471988503f, 0.472073023f, 0.472157540f, + 0.472242051f, 0.472326559f, 0.472411062f, 0.472495561f, 0.472580056f, + 0.472664546f, 0.472749032f, 0.472833513f, 0.472917991f, 0.473002464f, + 0.473086932f, 0.473171396f, 0.473255856f, 0.473340311f, 0.473424763f, + 0.473509209f, 0.473593652f, 0.473678090f, 0.473762523f, 0.473846953f, + 0.473931378f, 0.474015798f, 0.474100215f, 0.474184627f, 0.474269034f, + 0.474353437f, 0.474437836f, 0.474522231f, 0.474606621f, 0.474691006f, + 0.474775388f, 0.474859765f, 0.474944138f, 0.475028506f, 0.475112870f, + 0.475197229f, 0.475281584f, 0.475365935f, 0.475450282f, 0.475534624f, + 0.475618962f, 0.475703295f, 0.475787624f, 0.475871948f, 0.475956269f, + 0.476040584f, 0.476124896f, 0.476209203f, 0.476293506f, 0.476377804f, + 0.476462098f, 0.476546388f, 0.476630673f, 0.476714954f, 0.476799230f, + 0.476883502f, 0.476967770f, 0.477052033f, 0.477136292f, 0.477220546f, + 0.477304797f, 0.477389042f, 0.477473284f, 0.477557521f, 0.477641753f, + 0.477725981f, 0.477810205f, 0.477894425f, 0.477978640f, 0.478062850f, + 0.478147056f, 0.478231258f, 0.478315456f, 0.478399649f, 0.478483837f, + 0.478568022f, 0.478652201f, 0.478736377f, 0.478820548f, 0.478904715f, + 0.478988877f, 0.479073035f, 0.479157188f, 0.479241337f, 0.479325482f, + 0.479409622f, 0.479493758f, 0.479577889f, 0.479662016f, 0.479746139f, + 0.479830257f, 0.479914371f, 0.479998480f, 0.480082585f, 0.480166685f, + 0.480250781f, 0.480334873f, 0.480418960f, 0.480503043f, 0.480587122f, + 0.480671196f, 0.480755265f, 0.480839331f, 0.480923391f, 0.481007448f, + 0.481091500f, 0.481175547f, 0.481259590f, 0.481343629f, 0.481427663f, + 0.481511693f, 0.481595718f, 0.481679739f, 0.481763756f, 0.481847768f, + 0.481931776f, 0.482015779f, 0.482099778f, 0.482183772f, 0.482267762f, + 0.482351748f, 0.482435729f, 0.482519705f, 0.482603678f, 0.482687645f, + 0.482771609f, 0.482855568f, 0.482939522f, 0.483023472f, 0.483107418f, + 0.483191359f, 0.483275295f, 0.483359228f, 0.483443156f, 0.483527079f, + 0.483610998f, 0.483694912f, 0.483778822f, 0.483862728f, 0.483946629f, + 0.484030526f, 0.484114418f, 0.484198306f, 0.484282189f, 0.484366068f, + 0.484449943f, 0.484533813f, 0.484617678f, 0.484701539f, 0.484785396f, + 0.484869248f, 0.484953096f, 0.485036939f, 0.485120778f, 0.485204612f, + 0.485288442f, 0.485372267f, 0.485456088f, 0.485539905f, 0.485623717f, + 0.485707524f, 0.485791328f, 0.485875126f, 0.485958920f, 0.486042710f, + 0.486126495f, 0.486210276f, 0.486294052f, 0.486377824f, 0.486461592f, + 0.486545355f, 0.486629113f, 0.486712867f, 0.486796616f, 0.486880361f, + 0.486964102f, 0.487047838f, 0.487131569f, 0.487215297f, 0.487299019f, + 0.487382737f, 0.487466451f, 0.487550160f, 0.487633865f, 0.487717565f, + 0.487801261f, 0.487884952f, 0.487968639f, 0.488052321f, 0.488135999f, + 0.488219672f, 0.488303341f, 0.488387005f, 0.488470665f, 0.488554320f, + 0.488637971f, 0.488721618f, 0.488805260f, 0.488888897f, 0.488972530f, + 0.489056158f, 0.489139782f, 0.489223401f, 0.489307016f, 0.489390627f, + 0.489474233f, 0.489557834f, 0.489641431f, 0.489725023f, 0.489808611f, + 0.489892195f, 0.489975774f, 0.490059348f, 0.490142918f, 0.490226483f, + 0.490310044f, 0.490393601f, 0.490477152f, 0.490560700f, 0.490644243f, + 0.490727781f, 0.490811315f, 0.490894844f, 0.490978369f, 0.491061889f, + 0.491145405f, 0.491228916f, 0.491312423f, 0.491395925f, 0.491479423f, + 0.491562916f, 0.491646405f, 0.491729889f, 0.491813369f, 0.491896844f, + 0.491980314f, 0.492063780f, 0.492147242f, 0.492230699f, 0.492314151f, + 0.492397599f, 0.492481043f, 0.492564482f, 0.492647916f, 0.492731346f, + 0.492814771f, 0.492898192f, 0.492981609f, 0.493065020f, 0.493148427f, + 0.493231830f, 0.493315228f, 0.493398622f, 0.493482011f, 0.493565396f, + 0.493648776f, 0.493732151f, 0.493815522f, 0.493898888f, 0.493982250f, + 0.494065608f, 0.494148960f, 0.494232309f, 0.494315652f, 0.494398991f, + 0.494482326f, 0.494565656f, 0.494648982f, 0.494732302f, 0.494815619f, + 0.494898931f, 0.494982238f, 0.495065541f, 0.495148839f, 0.495232133f, + 0.495315422f, 0.495398706f, 0.495481986f, 0.495565262f, 0.495648533f, + 0.495731799f, 0.495815061f, 0.495898318f, 0.495981571f, 0.496064819f, + 0.496148062f, 0.496231301f, 0.496314536f, 0.496397766f, 0.496480991f, + 0.496564212f, 0.496647428f, 0.496730640f, 0.496813847f, 0.496897049f, + 0.496980247f, 0.497063440f, 0.497146629f, 0.497229813f, 0.497312993f, + 0.497396168f, 0.497479338f, 0.497562504f, 0.497645666f, 0.497728822f, + 0.497811975f, 0.497895122f, 0.497978265f, 0.498061404f, 0.498144538f, + 0.498227667f, 0.498310792f, 0.498393912f, 0.498477027f, 0.498560138f, + 0.498643245f, 0.498726347f, 0.498809444f, 0.498892537f, 0.498975625f, + 0.499058708f, 0.499141787f, 0.499224861f, 0.499307931f, 0.499390996f, + 0.499474057f, 0.499557113f, 0.499640164f, 0.499723211f, 0.499806253f, + 0.499889290f, 0.499972323f, 0.500055352f, 0.500138376f, 0.500221395f, + 0.500304409f, 0.500387419f, 0.500470425f, 0.500553425f, 0.500636422f, + 0.500719413f, 0.500802400f, 0.500885383f, 0.500968360f, 0.501051334f, + 0.501134302f, 0.501217266f, 0.501300225f, 0.501383180f, 0.501466130f, + 0.501549076f, 0.501632017f, 0.501714953f, 0.501797885f, 0.501880812f, + 0.501963734f, 0.502046652f, 0.502129565f, 0.502212474f, 0.502295378f, + 0.502378277f, 0.502461172f, 0.502544062f, 0.502626948f, 0.502709829f, + 0.502792705f, 0.502875577f, 0.502958444f, 0.503041306f, 0.503124164f, + 0.503207017f, 0.503289866f, 0.503372710f, 0.503455549f, 0.503538384f, + 0.503621214f, 0.503704039f, 0.503786860f, 0.503869676f, 0.503952488f, + 0.504035295f, 0.504118097f, 0.504200894f, 0.504283687f, 0.504366476f, + 0.504449259f, 0.504532039f, 0.504614813f, 0.504697583f, 0.504780348f, + 0.504863109f, 0.504945864f, 0.505028616f, 0.505111362f, 0.505194104f, + 0.505276842f, 0.505359574f, 0.505442302f, 0.505525026f, 0.505607744f, + 0.505690458f, 0.505773168f, 0.505855873f, 0.505938573f, 0.506021268f, + 0.506103959f, 0.506186645f, 0.506269327f, 0.506352004f, 0.506434676f, + 0.506517344f, 0.506600006f, 0.506682665f, 0.506765318f, 0.506847967f, + 0.506930612f, 0.507013251f, 0.507095886f, 0.507178516f, 0.507261142f, + 0.507343763f, 0.507426379f, 0.507508991f, 0.507591598f, 0.507674200f, + 0.507756798f, 0.507839391f, 0.507921979f, 0.508004563f, 0.508087142f, + 0.508169716f, 0.508252286f, 0.508334851f, 0.508417411f, 0.508499967f, + 0.508582518f, 0.508665064f, 0.508747606f, 0.508830143f, 0.508912675f, + 0.508995202f, 0.509077725f, 0.509160243f, 0.509242757f, 0.509325266f, + 0.509407770f, 0.509490269f, 0.509572764f, 0.509655254f, 0.509737740f, + 0.509820221f, 0.509902697f, 0.509985168f, 0.510067635f, 0.510150097f, + 0.510232554f, 0.510315007f, 0.510397455f, 0.510479898f, 0.510562336f, + 0.510644770f, 0.510727199f, 0.510809624f, 0.510892044f, 0.510974459f, + 0.511056869f, 0.511139275f, 0.511221676f, 0.511304072f, 0.511386464f, + 0.511468850f, 0.511551233f, 0.511633610f, 0.511715983f, 0.511798351f, + 0.511880714f, 0.511963073f, 0.512045427f, 0.512127776f, 0.512210121f, + 0.512292461f, 0.512374796f, 0.512457126f, 0.512539452f, 0.512621773f, + 0.512704089f, 0.512786401f, 0.512868707f, 0.512951010f, 0.513033307f, + 0.513115600f, 0.513197888f, 0.513280171f, 0.513362450f, 0.513444723f, + 0.513526993f, 0.513609257f, 0.513691517f, 0.513773772f, 0.513856022f, + 0.513938267f, 0.514020508f, 0.514102744f, 0.514184976f, 0.514267202f, + 0.514349424f, 0.514431641f, 0.514513854f, 0.514596061f, 0.514678264f, + 0.514760463f, 0.514842656f, 0.514924845f, 0.515007029f, 0.515089208f, + 0.515171383f, 0.515253553f, 0.515335718f, 0.515417878f, 0.515500034f, + 0.515582185f, 0.515664331f, 0.515746472f, 0.515828609f, 0.515910741f, + 0.515992868f, 0.516074990f, 0.516157108f, 0.516239221f, 0.516321329f, + 0.516403433f, 0.516485531f, 0.516567625f, 0.516649715f, 0.516731799f, + 0.516813879f, 0.516895954f, 0.516978024f, 0.517060089f, 0.517142150f, + 0.517224206f, 0.517306257f, 0.517388304f, 0.517470345f, 0.517552382f, + 0.517634415f, 0.517716442f, 0.517798465f, 0.517880483f, 0.517962496f, + 0.518044504f, 0.518126508f, 0.518208507f, 0.518290501f, 0.518372490f, + 0.518454475f, 0.518536454f, 0.518618429f, 0.518700400f, 0.518782365f, + 0.518864326f, 0.518946282f, 0.519028233f, 0.519110180f, 0.519192121f, + 0.519274058f, 0.519355990f, 0.519437917f, 0.519519840f, 0.519601758f, + 0.519683671f, 0.519765579f, 0.519847483f, 0.519929381f, 0.520011275f, + 0.520093164f, 0.520175049f, 0.520256928f, 0.520338803f, 0.520420673f, + 0.520502538f, 0.520584399f, 0.520666254f, 0.520748105f, 0.520829951f, + 0.520911792f, 0.520993629f, 0.521075461f, 0.521157287f, 0.521239110f, + 0.521320927f, 0.521402739f, 0.521484547f, 0.521566350f, 0.521648148f, + 0.521729942f, 0.521811730f, 0.521893514f, 0.521975293f, 0.522057067f, + 0.522138836f, 0.522220601f, 0.522302361f, 0.522384116f, 0.522465866f, + 0.522547611f, 0.522629352f, 0.522711088f, 0.522792819f, 0.522874545f, + 0.522956266f, 0.523037983f, 0.523119694f, 0.523201401f, 0.523283103f, + 0.523364801f, 0.523446493f, 0.523528181f, 0.523609864f, 0.523691542f, + 0.523773215f, 0.523854884f, 0.523936547f, 0.524018206f, 0.524099860f, + 0.524181509f, 0.524263153f, 0.524344793f, 0.524426428f, 0.524508058f, + 0.524589683f, 0.524671303f, 0.524752918f, 0.524834529f, 0.524916135f, + 0.524997736f, 0.525079332f, 0.525160923f, 0.525242510f, 0.525324091f, + 0.525405668f, 0.525487240f, 0.525568807f, 0.525650369f, 0.525731927f, + 0.525813480f, 0.525895027f, 0.525976570f, 0.526058109f, 0.526139642f, + 0.526221170f, 0.526302694f, 0.526384213f, 0.526465727f, 0.526547236f, + 0.526628740f, 0.526710240f, 0.526791734f, 0.526873224f, 0.526954709f, + 0.527036189f, 0.527117664f, 0.527199135f, 0.527280600f, 0.527362061f, + 0.527443517f, 0.527524968f, 0.527606414f, 0.527687855f, 0.527769292f, + 0.527850723f, 0.527932150f, 0.528013572f, 0.528094989f, 0.528176401f, + 0.528257809f, 0.528339211f, 0.528420609f, 0.528502002f, 0.528583389f, + 0.528664773f, 0.528746151f, 0.528827524f, 0.528908893f, 0.528990256f, + 0.529071615f, 0.529152969f, 0.529234318f, 0.529315662f, 0.529397001f, + 0.529478336f, 0.529559665f, 0.529640990f, 0.529722310f, 0.529803625f, + 0.529884935f, 0.529966240f, 0.530047540f, 0.530128836f, 0.530210126f, + 0.530291412f, 0.530372693f, 0.530453969f, 0.530535240f, 0.530616506f, + 0.530697768f, 0.530779024f, 0.530860276f, 0.530941522f, 0.531022764f, + 0.531104001f, 0.531185233f, 0.531266460f, 0.531347683f, 0.531428900f, + 0.531510113f, 0.531591320f, 0.531672523f, 0.531753721f, 0.531834914f, + 0.531916102f, 0.531997285f, 0.532078464f, 0.532159637f, 0.532240805f, + 0.532321969f, 0.532403128f, 0.532484282f, 0.532565431f, 0.532646575f, + 0.532727714f, 0.532808848f, 0.532889978f, 0.532971102f, 0.533052222f, + 0.533133336f, 0.533214446f, 0.533295551f, 0.533376651f, 0.533457746f, + 0.533538836f, 0.533619921f, 0.533701002f, 0.533782077f, 0.533863148f, + 0.533944213f, 0.534025274f, 0.534106330f, 0.534187381f, 0.534268427f, + 0.534349468f, 0.534430504f, 0.534511535f, 0.534592562f, 0.534673583f, + 0.534754600f, 0.534835611f, 0.534916618f, 0.534997620f, 0.535078617f, + 0.535159609f, 0.535240596f, 0.535321578f, 0.535402555f, 0.535483527f, + 0.535564495f, 0.535645457f, 0.535726415f, 0.535807367f, 0.535888315f, + 0.535969257f, 0.536050195f, 0.536131128f, 0.536212056f, 0.536292979f, + 0.536373897f, 0.536454810f, 0.536535719f, 0.536616622f, 0.536697520f, + 0.536778414f, 0.536859302f, 0.536940186f, 0.537021064f, 0.537101938f, + 0.537182807f, 0.537263670f, 0.537344529f, 0.537425383f, 0.537506232f, + 0.537587076f, 0.537667915f, 0.537748750f, 0.537829579f, 0.537910403f, + 0.537991222f, 0.538072037f, 0.538152846f, 0.538233651f, 0.538314450f, + 0.538395245f, 0.538476035f, 0.538556819f, 0.538637599f, 0.538718374f, + 0.538799144f, 0.538879909f, 0.538960668f, 0.539041423f, 0.539122173f, + 0.539202919f, 0.539283659f, 0.539364394f, 0.539445124f, 0.539525849f, + 0.539606570f, 0.539687285f, 0.539767995f, 0.539848701f, 0.539929401f, + 0.540010097f, 0.540090787f, 0.540171473f, 0.540252153f, 0.540332829f, + 0.540413500f, 0.540494165f, 0.540574826f, 0.540655482f, 0.540736133f, + 0.540816778f, 0.540897419f, 0.540978055f, 0.541058686f, 0.541139312f, + 0.541219933f, 0.541300549f, 0.541381160f, 0.541461766f, 0.541542367f, + 0.541622963f, 0.541703554f, 0.541784140f, 0.541864721f, 0.541945297f, + 0.542025869f, 0.542106435f, 0.542186996f, 0.542267552f, 0.542348103f, + 0.542428650f, 0.542509191f, 0.542589727f, 0.542670259f, 0.542750785f, + 0.542831306f, 0.542911823f, 0.542992334f, 0.543072840f, 0.543153342f, + 0.543233838f, 0.543314329f, 0.543394816f, 0.543475297f, 0.543555773f, + 0.543636245f, 0.543716711f, 0.543797173f, 0.543877629f, 0.543958080f, + 0.544038527f, 0.544118968f, 0.544199405f, 0.544279836f, 0.544360262f, + 0.544440684f, 0.544521100f, 0.544601511f, 0.544681918f, 0.544762319f, + 0.544842716f, 0.544923107f, 0.545003493f, 0.545083875f, 0.545164251f, + 0.545244622f, 0.545324988f, 0.545405350f, 0.545485706f, 0.545566057f, + 0.545646403f, 0.545726745f, 0.545807081f, 0.545887412f, 0.545967738f, + 0.546048059f, 0.546128376f, 0.546208687f, 0.546288993f, 0.546369294f, + 0.546449590f, 0.546529881f, 0.546610167f, 0.546690448f, 0.546770724f, + 0.546850995f, 0.546931261f, 0.547011522f, 0.547091777f, 0.547172028f, + 0.547252274f, 0.547332515f, 0.547412750f, 0.547492981f, 0.547573207f, + 0.547653427f, 0.547733643f, 0.547813854f, 0.547894059f, 0.547974260f, + 0.548054455f, 0.548134646f, 0.548214831f, 0.548295011f, 0.548375187f, + 0.548455357f, 0.548535522f, 0.548615682f, 0.548695837f, 0.548775987f, + 0.548856132f, 0.548936272f, 0.549016407f, 0.549096537f, 0.549176662f, + 0.549256782f, 0.549336897f, 0.549417006f, 0.549497111f, 0.549577211f, + 0.549657305f, 0.549737395f, 0.549817479f, 0.549897559f, 0.549977633f, + 0.550057702f, 0.550137767f, 0.550217826f, 0.550297880f, 0.550377929f, + 0.550457973f, 0.550538012f, 0.550618046f, 0.550698075f, 0.550778098f, + 0.550858117f, 0.550938131f, 0.551018139f, 0.551098143f, 0.551178141f, + 0.551258135f, 0.551338123f, 0.551418106f, 0.551498084f, 0.551578057f, + 0.551658025f, 0.551737988f, 0.551817946f, 0.551897899f, 0.551977847f, + 0.552057790f, 0.552137727f, 0.552217660f, 0.552297587f, 0.552377509f, + 0.552457427f, 0.552537339f, 0.552617246f, 0.552697148f, 0.552777045f, + 0.552856937f, 0.552936824f, 0.553016706f, 0.553096582f, 0.553176454f, + 0.553256320f, 0.553336182f, 0.553416038f, 0.553495889f, 0.553575735f, + 0.553655576f, 0.553735412f, 0.553815243f, 0.553895069f, 0.553974890f, + 0.554054705f, 0.554134516f, 0.554214321f, 0.554294121f, 0.554373917f, + 0.554453707f, 0.554533492f, 0.554613272f, 0.554693047f, 0.554772816f, + 0.554852581f, 0.554932340f, 0.555012095f, 0.555091844f, 0.555171588f, + 0.555251328f, 0.555331062f, 0.555410791f, 0.555490514f, 0.555570233f, + 0.555649947f, 0.555729655f, 0.555809358f, 0.555889057f, 0.555968750f, + 0.556048438f, 0.556128121f, 0.556207799f, 0.556287471f, 0.556367139f, + 0.556446802f, 0.556526459f, 0.556606111f, 0.556685758f, 0.556765400f, + 0.556845037f, 0.556924669f, 0.557004296f, 0.557083917f, 0.557163534f, + 0.557243145f, 0.557322751f, 0.557402352f, 0.557481948f, 0.557561539f, + 0.557641125f, 0.557720705f, 0.557800281f, 0.557879851f, 0.557959416f, + 0.558038976f, 0.558118531f, 0.558198081f, 0.558277626f, 0.558357165f, + 0.558436700f, 0.558516229f, 0.558595753f, 0.558675272f, 0.558754786f, + 0.558834295f, 0.558913798f, 0.558993297f, 0.559072790f, 0.559152278f, + 0.559231761f, 0.559311239f, 0.559390712f, 0.559470179f, 0.559549642f, + 0.559629099f, 0.559708551f, 0.559787999f, 0.559867440f, 0.559946877f, + 0.560026309f, 0.560105735f, 0.560185157f, 0.560264573f, 0.560343984f, + 0.560423390f, 0.560502790f, 0.560582186f, 0.560661576f, 0.560740961f, + 0.560820342f, 0.560899716f, 0.560979086f, 0.561058451f, 0.561137810f, + 0.561217165f, 0.561296514f, 0.561375858f, 0.561455197f, 0.561534530f, + 0.561613859f, 0.561693182f, 0.561772500f, 0.561851813f, 0.561931121f, + 0.562010424f, 0.562089721f, 0.562169014f, 0.562248301f, 0.562327583f, + 0.562406860f, 0.562486132f, 0.562565398f, 0.562644659f, 0.562723916f, + 0.562803167f, 0.562882412f, 0.562961653f, 0.563040889f, 0.563120119f, + 0.563199344f, 0.563278564f, 0.563357779f, 0.563436988f, 0.563516193f, + 0.563595392f, 0.563674586f, 0.563753775f, 0.563832959f, 0.563912137f, + 0.563991310f, 0.564070479f, 0.564149642f, 0.564228799f, 0.564307952f, + 0.564387099f, 0.564466242f, 0.564545379f, 0.564624510f, 0.564703637f, + 0.564782758f, 0.564861875f, 0.564940986f, 0.565020092f, 0.565099192f, + 0.565178288f, 0.565257378f, 0.565336463f, 0.565415543f, 0.565494618f, + 0.565573687f, 0.565652752f, 0.565731811f, 0.565810865f, 0.565889913f, + 0.565968957f, 0.566047995f, 0.566127028f, 0.566206056f, 0.566285079f, + 0.566364096f, 0.566443109f, 0.566522116f, 0.566601118f, 0.566680114f, + 0.566759106f, 0.566838092f, 0.566917073f, 0.566996049f, 0.567075019f, + 0.567153985f, 0.567232945f, 0.567311900f, 0.567390850f, 0.567469794f, + 0.567548734f, 0.567627668f, 0.567706597f, 0.567785520f, 0.567864439f, + 0.567943352f, 0.568022260f, 0.568101163f, 0.568180060f, 0.568258953f, + 0.568337840f, 0.568416722f, 0.568495598f, 0.568574470f, 0.568653336f, + 0.568732197f, 0.568811053f, 0.568889903f, 0.568968749f, 0.569047589f, + 0.569126424f, 0.569205253f, 0.569284078f, 0.569362897f, 0.569441711f, + 0.569520519f, 0.569599323f, 0.569678121f, 0.569756914f, 0.569835702f, + 0.569914484f, 0.569993262f, 0.570072034f, 0.570150800f, 0.570229562f, + 0.570308318f, 0.570387069f, 0.570465815f, 0.570544556f, 0.570623291f, + 0.570702021f, 0.570780746f, 0.570859465f, 0.570938180f, 0.571016889f, + 0.571095593f, 0.571174291f, 0.571252985f, 0.571331673f, 0.571410356f, + 0.571489033f, 0.571567706f, 0.571646373f, 0.571725035f, 0.571803691f, + 0.571882342f, 0.571960989f, 0.572039629f, 0.572118265f, 0.572196895f, + 0.572275520f, 0.572354140f, 0.572432754f, 0.572511364f, 0.572589968f, + 0.572668566f, 0.572747160f, 0.572825748f, 0.572904331f, 0.572982909f, + 0.573061481f, 0.573140048f, 0.573218610f, 0.573297167f, 0.573375718f, + 0.573454264f, 0.573532805f, 0.573611340f, 0.573689871f, 0.573768396f, + 0.573846915f, 0.573925430f, 0.574003939f, 0.574082443f, 0.574160941f, + 0.574239435f, 0.574317923f, 0.574396405f, 0.574474883f, 0.574553355f, + 0.574631822f, 0.574710284f, 0.574788740f, 0.574867191f, 0.574945637f, + 0.575024077f, 0.575102512f, 0.575180942f, 0.575259367f, 0.575337786f, + 0.575416200f, 0.575494609f, 0.575573013f, 0.575651411f, 0.575729804f, + 0.575808191f, 0.575886574f, 0.575964951f, 0.576043322f, 0.576121689f, + 0.576200050f, 0.576278406f, 0.576356756f, 0.576435102f, 0.576513442f, + 0.576591776f, 0.576670106f, 0.576748430f, 0.576826748f, 0.576905062f, + 0.576983370f, 0.577061673f, 0.577139970f, 0.577218263f, 0.577296550f, + 0.577374831f, 0.577453107f, 0.577531378f, 0.577609644f, 0.577687905f, + 0.577766160f, 0.577844409f, 0.577922654f, 0.578000893f, 0.578079127f, + 0.578157355f, 0.578235579f, 0.578313796f, 0.578392009f, 0.578470216f, + 0.578548418f, 0.578626615f, 0.578704806f, 0.578782992f, 0.578861173f, + 0.578939348f, 0.579017518f, 0.579095683f, 0.579173842f, 0.579251996f, + 0.579330145f, 0.579408288f, 0.579486426f, 0.579564559f, 0.579642687f, + 0.579720809f, 0.579798925f, 0.579877037f, 0.579955143f, 0.580033244f, + 0.580111339f, 0.580189429f, 0.580267514f, 0.580345593f, 0.580423668f, + 0.580501736f, 0.580579800f, 0.580657858f, 0.580735911f, 0.580813958f, + 0.580892000f, 0.580970037f, 0.581048068f, 0.581126094f, 0.581204115f, + 0.581282131f, 0.581360141f, 0.581438145f, 0.581516145f, 0.581594139f, + 0.581672127f, 0.581750111f, 0.581828089f, 0.581906061f, 0.581984028f, + 0.582061990f, 0.582139947f, 0.582217898f, 0.582295844f, 0.582373785f, + 0.582451720f, 0.582529649f, 0.582607574f, 0.582685493f, 0.582763407f, + 0.582841315f, 0.582919218f, 0.582997116f, 0.583075008f, 0.583152895f, + 0.583230777f, 0.583308653f, 0.583386524f, 0.583464389f, 0.583542249f, + 0.583620104f, 0.583697954f, 0.583775798f, 0.583853636f, 0.583931470f, + 0.584009298f, 0.584087120f, 0.584164937f, 0.584242749f, 0.584320556f, + 0.584398357f, 0.584476153f, 0.584553943f, 0.584631728f, 0.584709508f, + 0.584787282f, 0.584865051f, 0.584942814f, 0.585020572f, 0.585098325f, + 0.585176072f, 0.585253814f, 0.585331551f, 0.585409282f, 0.585487008f, + 0.585564728f, 0.585642443f, 0.585720153f, 0.585797857f, 0.585875556f, + 0.585953250f, 0.586030938f, 0.586108621f, 0.586186298f, 0.586263970f, + 0.586341637f, 0.586419298f, 0.586496954f, 0.586574604f, 0.586652249f, + 0.586729889f, 0.586807523f, 0.586885152f, 0.586962775f, 0.587040394f, + 0.587118006f, 0.587195613f, 0.587273215f, 0.587350812f, 0.587428403f, + 0.587505989f, 0.587583569f, 0.587661144f, 0.587738713f, 0.587816277f, + 0.587893836f, 0.587971389f, 0.588048937f, 0.588126480f, 0.588204017f, + 0.588281548f, 0.588359074f, 0.588436595f, 0.588514111f, 0.588591621f, + 0.588669125f, 0.588746625f, 0.588824118f, 0.588901607f, 0.588979090f, + 0.589056567f, 0.589134039f, 0.589211506f, 0.589288967f, 0.589366423f, + 0.589443874f, 0.589521319f, 0.589598758f, 0.589676192f, 0.589753621f, + 0.589831045f, 0.589908463f, 0.589985875f, 0.590063282f, 0.590140684f, + 0.590218080f, 0.590295471f, 0.590372856f, 0.590450236f, 0.590527611f, + 0.590604980f, 0.590682344f, 0.590759702f, 0.590837055f, 0.590914402f, + 0.590991744f, 0.591069081f, 0.591146412f, 0.591223737f, 0.591301058f, + 0.591378372f, 0.591455682f, 0.591532986f, 0.591610284f, 0.591687577f, + 0.591764865f, 0.591842147f, 0.591919424f, 0.591996695f, 0.592073961f, + 0.592151221f, 0.592228476f, 0.592305726f, 0.592382970f, 0.592460208f, + 0.592537442f, 0.592614669f, 0.592691892f, 0.592769108f, 0.592846320f, + 0.592923526f, 0.593000726f, 0.593077921f, 0.593155111f, 0.593232295f, + 0.593309474f, 0.593386647f, 0.593463815f, 0.593540977f, 0.593618134f, + 0.593695285f, 0.593772431f, 0.593849572f, 0.593926707f, 0.594003836f, + 0.594080961f, 0.594158079f, 0.594235192f, 0.594312300f, 0.594389402f, + 0.594466499f, 0.594543591f, 0.594620676f, 0.594697757f, 0.594774832f, + 0.594851901f, 0.594928965f, 0.595006024f, 0.595083077f, 0.595160124f, + 0.595237167f, 0.595314203f, 0.595391234f, 0.595468260f, 0.595545280f, + 0.595622295f, 0.595699304f, 0.595776308f, 0.595853307f, 0.595930300f, + 0.596007287f, 0.596084269f, 0.596161245f, 0.596238216f, 0.596315182f, + 0.596392142f, 0.596469096f, 0.596546045f, 0.596622989f, 0.596699927f, + 0.596776859f, 0.596853786f, 0.596930708f, 0.597007624f, 0.597084535f, + 0.597161440f, 0.597238340f, 0.597315234f, 0.597392122f, 0.597469006f, + 0.597545883f, 0.597622755f, 0.597699622f, 0.597776483f, 0.597853339f, + 0.597930189f, 0.598007034f, 0.598083873f, 0.598160707f, 0.598237535f, + 0.598314358f, 0.598391175f, 0.598467987f, 0.598544793f, 0.598621594f, + 0.598698389f, 0.598775179f, 0.598851963f, 0.598928742f, 0.599005515f, + 0.599082283f, 0.599159045f, 0.599235802f, 0.599312553f, 0.599389298f, + 0.599466039f, 0.599542773f, 0.599619502f, 0.599696226f, 0.599772944f, + 0.599849657f, 0.599926364f, 0.600003065f, 0.600079761f, 0.600156452f, + 0.600233137f, 0.600309817f, 0.600386491f, 0.600463159f, 0.600539822f, + 0.600616479f, 0.600693131f, 0.600769778f, 0.600846419f, 0.600923054f, + 0.600999684f, 0.601076308f, 0.601152927f, 0.601229540f, 0.601306148f, + 0.601382750f, 0.601459347f, 0.601535938f, 0.601612523f, 0.601689103f, + 0.601765678f, 0.601842247f, 0.601918811f, 0.601995369f, 0.602071921f, + 0.602148468f, 0.602225009f, 0.602301545f, 0.602378075f, 0.602454600f, + 0.602531119f, 0.602607633f, 0.602684141f, 0.602760644f, 0.602837141f, + 0.602913632f, 0.602990118f, 0.603066599f, 0.603143073f, 0.603219543f, + 0.603296007f, 0.603372465f, 0.603448917f, 0.603525365f, 0.603601806f, + 0.603678242f, 0.603754673f, 0.603831098f, 0.603907517f, 0.603983931f, + 0.604060339f, 0.604136742f, 0.604213139f, 0.604289531f, 0.604365917f, + 0.604442298f, 0.604518673f, 0.604595042f, 0.604671406f, 0.604747764f, + 0.604824117f, 0.604900464f, 0.604976806f, 0.605053142f, 0.605129472f, + 0.605205797f, 0.605282117f, 0.605358430f, 0.605434739f, 0.605511041f, + 0.605587339f, 0.605663630f, 0.605739916f, 0.605816197f, 0.605892471f, + 0.605968741f, 0.606045004f, 0.606121263f, 0.606197515f, 0.606273762f, + 0.606350004f, 0.606426239f, 0.606502470f, 0.606578694f, 0.606654913f, + 0.606731127f, 0.606807335f, 0.606883537f, 0.606959734f, 0.607035925f, + 0.607112111f, 0.607188291f, 0.607264466f, 0.607340635f, 0.607416798f, + 0.607492956f, 0.607569108f, 0.607645254f, 0.607721395f, 0.607797531f, + 0.607873661f, 0.607949785f, 0.608025904f, 0.608102017f, 0.608178124f, + 0.608254226f, 0.608330322f, 0.608406413f, 0.608482498f, 0.608558578f, + 0.608634652f, 0.608710720f, 0.608786783f, 0.608862840f, 0.608938891f, + 0.609014937f, 0.609090978f, 0.609167012f, 0.609243041f, 0.609319065f, + 0.609395083f, 0.609471095f, 0.609547102f, 0.609623103f, 0.609699099f, + 0.609775089f, 0.609851073f, 0.609927052f, 0.610003025f, 0.610078992f, + 0.610154954f, 0.610230911f, 0.610306861f, 0.610382806f, 0.610458746f, + 0.610534680f, 0.610610608f, 0.610686530f, 0.610762447f, 0.610838359f, + 0.610914265f, 0.610990165f, 0.611066059f, 0.611141948f, 0.611217832f, + 0.611293709f, 0.611369581f, 0.611445448f, 0.611521309f, 0.611597164f, + 0.611673014f, 0.611748858f, 0.611824696f, 0.611900529f, 0.611976356f, + 0.612052177f, 0.612127993f, 0.612203803f, 0.612279608f, 0.612355407f, + 0.612431200f, 0.612506988f, 0.612582770f, 0.612658546f, 0.612734317f, + 0.612810082f, 0.612885842f, 0.612961596f, 0.613037344f, 0.613113087f, + 0.613188824f, 0.613264555f, 0.613340281f, 0.613416001f, 0.613491716f, + 0.613567424f, 0.613643128f, 0.613718825f, 0.613794517f, 0.613870203f, + 0.613945884f, 0.614021559f, 0.614097228f, 0.614172892f, 0.614248550f, + 0.614324202f, 0.614399849f, 0.614475490f, 0.614551126f, 0.614626756f, + 0.614702380f, 0.614777998f, 0.614853611f, 0.614929218f, 0.615004820f, + 0.615080416f, 0.615156006f, 0.615231591f, 0.615307170f, 0.615382743f, + 0.615458310f, 0.615533872f, 0.615609429f, 0.615684979f, 0.615760524f, + 0.615836064f, 0.615911597f, 0.615987125f, 0.616062648f, 0.616138164f, + 0.616213675f, 0.616289181f, 0.616364681f, 0.616440175f, 0.616515663f, + 0.616591146f, 0.616666623f, 0.616742094f, 0.616817560f, 0.616893020f, + 0.616968474f, 0.617043923f, 0.617119366f, 0.617194803f, 0.617270235f, + 0.617345661f, 0.617421081f, 0.617496496f, 0.617571905f, 0.617647308f, + 0.617722706f, 0.617798097f, 0.617873484f, 0.617948864f, 0.618024239f, + 0.618099608f, 0.618174972f, 0.618250330f, 0.618325682f, 0.618401028f, + 0.618476369f, 0.618551704f, 0.618627034f, 0.618702358f, 0.618777676f, + 0.618852988f, 0.618928295f, 0.619003596f, 0.619078891f, 0.619154181f, + 0.619229464f, 0.619304743f, 0.619380015f, 0.619455282f, 0.619530543f, + 0.619605799f, 0.619681048f, 0.619756292f, 0.619831531f, 0.619906764f, + 0.619981990f, 0.620057212f, 0.620132427f, 0.620207637f, 0.620282841f, + 0.620358040f, 0.620433233f, 0.620508420f, 0.620583601f, 0.620658777f, + 0.620733947f, 0.620809111f, 0.620884269f, 0.620959422f, 0.621034569f, + 0.621109711f, 0.621184847f, 0.621259977f, 0.621335101f, 0.621410219f, + 0.621485332f, 0.621560439f, 0.621635541f, 0.621710637f, 0.621785727f, + 0.621860811f, 0.621935889f, 0.622010962f, 0.622086029f, 0.622161091f, + 0.622236147f, 0.622311197f, 0.622386241f, 0.622461279f, 0.622536312f, + 0.622611339f, 0.622686361f, 0.622761376f, 0.622836386f, 0.622911390f, + 0.622986389f, 0.623061382f, 0.623136369f, 0.623211350f, 0.623286326f, + 0.623361295f, 0.623436260f, 0.623511218f, 0.623586171f, 0.623661118f, + 0.623736059f, 0.623810994f, 0.623885924f, 0.623960848f, 0.624035766f, + 0.624110679f, 0.624185585f, 0.624260486f, 0.624335382f, 0.624410271f, + 0.624485155f, 0.624560033f, 0.624634906f, 0.624709772f, 0.624784633f, + 0.624859488f, 0.624934338f, 0.625009181f, 0.625084019f, 0.625158851f, + 0.625233678f, 0.625308498f, 0.625383313f, 0.625458122f, 0.625532926f, + 0.625607723f, 0.625682515f, 0.625757301f, 0.625832082f, 0.625906856f, + 0.625981625f, 0.626056388f, 0.626131146f, 0.626205897f, 0.626280643f, + 0.626355383f, 0.626430118f, 0.626504846f, 0.626579569f, 0.626654286f, + 0.626728998f, 0.626803703f, 0.626878403f, 0.626953097f, 0.627027785f, + 0.627102468f, 0.627177145f, 0.627251815f, 0.627326481f, 0.627401140f, + 0.627475794f, 0.627550442f, 0.627625084f, 0.627699720f, 0.627774351f, + 0.627848976f, 0.627923595f, 0.627998208f, 0.628072816f, 0.628147417f, + 0.628222013f, 0.628296604f, 0.628371188f, 0.628445767f, 0.628520339f, + 0.628594907f, 0.628669468f, 0.628744023f, 0.628818573f, 0.628893117f, + 0.628967655f, 0.629042188f, 0.629116714f, 0.629191235f, 0.629265750f, + 0.629340260f, 0.629414763f, 0.629489261f, 0.629563753f, 0.629638239f, + 0.629712719f, 0.629787194f, 0.629861663f, 0.629936126f, 0.630010583f, + 0.630085034f, 0.630159480f, 0.630233920f, 0.630308354f, 0.630382782f, + 0.630457204f, 0.630531621f, 0.630606032f, 0.630680437f, 0.630754836f, + 0.630829230f, 0.630903617f, 0.630977999f, 0.631052375f, 0.631126745f, + 0.631201110f, 0.631275469f, 0.631349821f, 0.631424169f, 0.631498510f, + 0.631572845f, 0.631647175f, 0.631721499f, 0.631795817f, 0.631870129f, + 0.631944435f, 0.632018736f, 0.632093031f, 0.632167320f, 0.632241603f, + 0.632315880f, 0.632390152f, 0.632464418f, 0.632538677f, 0.632612932f, + 0.632687180f, 0.632761422f, 0.632835659f, 0.632909890f, 0.632984115f, + 0.633058334f, 0.633132547f, 0.633206755f, 0.633280957f, 0.633355153f, + 0.633429343f, 0.633503527f, 0.633577706f, 0.633651878f, 0.633726045f, + 0.633800206f, 0.633874361f, 0.633948511f, 0.634022654f, 0.634096792f, + 0.634170924f, 0.634245050f, 0.634319170f, 0.634393284f, 0.634467393f, + 0.634541495f, 0.634615592f, 0.634689683f, 0.634763769f, 0.634837848f, + 0.634911921f, 0.634985989f, 0.635060051f, 0.635134107f, 0.635208157f, + 0.635282202f, 0.635356240f, 0.635430273f, 0.635504300f, 0.635578320f, + 0.635652336f, 0.635726345f, 0.635800348f, 0.635874346f, 0.635948338f, + 0.636022324f, 0.636096304f, 0.636170278f, 0.636244246f, 0.636318209f, + 0.636392166f, 0.636466116f, 0.636540061f, 0.636614001f, 0.636687934f, + 0.636761861f, 0.636835783f, 0.636909699f, 0.636983608f, 0.637057512f, + 0.637131411f, 0.637205303f, 0.637279189f, 0.637353070f, 0.637426945f, + 0.637500813f, 0.637574677f, 0.637648534f, 0.637722385f, 0.637796230f, + 0.637870070f, 0.637943904f, 0.638017731f, 0.638091553f, 0.638165370f, + 0.638239180f, 0.638312984f, 0.638386783f, 0.638460575f, 0.638534362f, + 0.638608143f, 0.638681918f, 0.638755687f, 0.638829450f, 0.638903208f, + 0.638976959f, 0.639050705f, 0.639124445f, 0.639198179f, 0.639271907f, + 0.639345629f, 0.639419345f, 0.639493056f, 0.639566760f, 0.639640459f, + 0.639714152f, 0.639787839f, 0.639861520f, 0.639935195f, 0.640008864f, + 0.640082527f, 0.640156185f, 0.640229836f, 0.640303482f, 0.640377122f, + 0.640450756f, 0.640524384f, 0.640598006f, 0.640671622f, 0.640745233f, + 0.640818837f, 0.640892436f, 0.640966029f, 0.641039616f, 0.641113197f, + 0.641186772f, 0.641260341f, 0.641333904f, 0.641407461f, 0.641481013f, + 0.641554558f, 0.641628098f, 0.641701632f, 0.641775160f, 0.641848682f, + 0.641922198f, 0.641995708f, 0.642069212f, 0.642142711f, 0.642216203f, + 0.642289690f, 0.642363170f, 0.642436645f, 0.642510114f, 0.642583577f, + 0.642657034f, 0.642730485f, 0.642803930f, 0.642877370f, 0.642950803f, + 0.643024231f, 0.643097652f, 0.643171068f, 0.643244478f, 0.643317881f, + 0.643391279f, 0.643464671f, 0.643538058f, 0.643611438f, 0.643684812f, + 0.643758180f, 0.643831543f, 0.643904899f, 0.643978250f, 0.644051595f, + 0.644124934f, 0.644198266f, 0.644271593f, 0.644344914f, 0.644418229f, + 0.644491539f, 0.644564842f, 0.644638139f, 0.644711431f, 0.644784716f, + 0.644857996f, 0.644931269f, 0.645004537f, 0.645077799f, 0.645151054f, + 0.645224304f, 0.645297548f, 0.645370786f, 0.645444018f, 0.645517245f, + 0.645590465f, 0.645663679f, 0.645736887f, 0.645810090f, 0.645883286f, + 0.645956477f, 0.646029662f, 0.646102840f, 0.646176013f, 0.646249180f, + 0.646322341f, 0.646395496f, 0.646468645f, 0.646541788f, 0.646614925f, + 0.646688056f, 0.646761181f, 0.646834300f, 0.646907414f, 0.646980521f, + 0.647053622f, 0.647126718f, 0.647199807f, 0.647272891f, 0.647345969f, + 0.647419040f, 0.647492106f, 0.647565166f, 0.647638220f, 0.647711268f, + 0.647784309f, 0.647857345f, 0.647930375f, 0.648003399f, 0.648076418f, + 0.648149430f, 0.648222436f, 0.648295436f, 0.648368430f, 0.648441419f, + 0.648514401f, 0.648587377f, 0.648660348f, 0.648733312f, 0.648806271f, + 0.648879223f, 0.648952170f, 0.649025110f, 0.649098045f, 0.649170974f, + 0.649243897f, 0.649316813f, 0.649389724f, 0.649462629f, 0.649535528f, + 0.649608421f, 0.649681307f, 0.649754188f, 0.649827063f, 0.649899932f, + 0.649972795f, 0.650045652f, 0.650118503f, 0.650191348f, 0.650264187f, + 0.650337021f, 0.650409848f, 0.650482669f, 0.650555484f, 0.650628293f, + 0.650701096f, 0.650773894f, 0.650846685f, 0.650919470f, 0.650992250f, + 0.651065023f, 0.651137790f, 0.651210552f, 0.651283307f, 0.651356056f, + 0.651428800f, 0.651501537f, 0.651574268f, 0.651646994f, 0.651719713f, + 0.651792427f, 0.651865134f, 0.651937836f, 0.652010531f, 0.652083221f, + 0.652155904f, 0.652228582f, 0.652301253f, 0.652373918f, 0.652446578f, + 0.652519231f, 0.652591879f, 0.652664520f, 0.652737156f, 0.652809785f, + 0.652882409f, 0.652955026f, 0.653027638f, 0.653100243f, 0.653172843f, + 0.653245436f, 0.653318024f, 0.653390605f, 0.653463181f, 0.653535750f, + 0.653608314f, 0.653680871f, 0.653753423f, 0.653825968f, 0.653898508f, + 0.653971041f, 0.654043568f, 0.654116090f, 0.654188605f, 0.654261114f, + 0.654333618f, 0.654406115f, 0.654478606f, 0.654551092f, 0.654623571f, + 0.654696044f, 0.654768512f, 0.654840973f, 0.654913428f, 0.654985877f, + 0.655058320f, 0.655130758f, 0.655203189f, 0.655275614f, 0.655348033f, + 0.655420446f, 0.655492853f, 0.655565254f, 0.655637649f, 0.655710038f, + 0.655782421f, 0.655854798f, 0.655927169f, 0.655999534f, 0.656071892f, + 0.656144245f, 0.656216592f, 0.656288933f, 0.656361267f, 0.656433596f, + 0.656505919f, 0.656578235f, 0.656650546f, 0.656722850f, 0.656795149f, + 0.656867441f, 0.656939728f, 0.657012008f, 0.657084282f, 0.657156551f, + 0.657228813f, 0.657301069f, 0.657373319f, 0.657445563f, 0.657517801f, + 0.657590033f, 0.657662259f, 0.657734479f, 0.657806693f, 0.657878901f, + 0.657951103f, 0.658023299f, 0.658095488f, 0.658167672f, 0.658239850f, + 0.658312021f, 0.658384187f, 0.658456346f, 0.658528500f, 0.658600647f, + 0.658672788f, 0.658744924f, 0.658817053f, 0.658889176f, 0.658961293f, + 0.659033404f, 0.659105509f, 0.659177608f, 0.659249701f, 0.659321788f, + 0.659393868f, 0.659465943f, 0.659538012f, 0.659610074f, 0.659682131f, + 0.659754181f, 0.659826225f, 0.659898264f, 0.659970296f, 0.660042322f, + 0.660114342f, 0.660186356f, 0.660258364f, 0.660330366f, 0.660402362f, + 0.660474351f, 0.660546335f, 0.660618313f, 0.660690284f, 0.660762250f, + 0.660834209f, 0.660906162f, 0.660978110f, 0.661050051f, 0.661121986f, + 0.661193915f, 0.661265838f, 0.661337755f, 0.661409665f, 0.661481570f, + 0.661553469f, 0.661625361f, 0.661697248f, 0.661769128f, 0.661841002f, + 0.661912871f, 0.661984733f, 0.662056589f, 0.662128439f, 0.662200283f, + 0.662272120f, 0.662343952f, 0.662415778f, 0.662487597f, 0.662559411f, + 0.662631218f, 0.662703019f, 0.662774814f, 0.662846603f, 0.662918386f, + 0.662990163f, 0.663061934f, 0.663133699f, 0.663205457f, 0.663277210f, + 0.663348956f, 0.663420696f, 0.663492431f, 0.663564159f, 0.663635881f, + 0.663707597f, 0.663779306f, 0.663851010f, 0.663922708f, 0.663994399f, + 0.664066084f, 0.664137764f, 0.664209437f, 0.664281104f, 0.664352765f, + 0.664424420f, 0.664496069f, 0.664567711f, 0.664639348f, 0.664710978f, + 0.664782603f, 0.664854221f, 0.664925833f, 0.664997439f, 0.665069039f, + 0.665140632f, 0.665212220f, 0.665283802f, 0.665355377f, 0.665426946f, + 0.665498510f, 0.665570067f, 0.665641618f, 0.665713162f, 0.665784701f, + 0.665856234f, 0.665927760f, 0.665999280f, 0.666070795f, 0.666142303f, + 0.666213805f, 0.666285301f, 0.666356790f, 0.666428274f, 0.666499751f, + 0.666571223f, 0.666642688f, 0.666714147f, 0.666785600f, 0.666857047f, + 0.666928488f, 0.666999922f, 0.667071351f, 0.667142773f, 0.667214189f, + 0.667285599f, 0.667357003f, 0.667428401f, 0.667499793f, 0.667571178f, + 0.667642558f, 0.667713931f, 0.667785298f, 0.667856659f, 0.667928014f, + 0.667999362f, 0.668070705f, 0.668142041f, 0.668213372f, 0.668284696f, + 0.668356014f, 0.668427326f, 0.668498631f, 0.668569931f, 0.668641224f, + 0.668712512f, 0.668783793f, 0.668855068f, 0.668926336f, 0.668997599f, + 0.669068856f, 0.669140106f, 0.669211350f, 0.669282588f, 0.669353820f, + 0.669425046f, 0.669496266f, 0.669567479f, 0.669638686f, 0.669709888f, + 0.669781083f, 0.669852271f, 0.669923454f, 0.669994631f, 0.670065801f, + 0.670136965f, 0.670208123f, 0.670279275f, 0.670350421f, 0.670421560f, + 0.670492694f, 0.670563821f, 0.670634942f, 0.670706057f, 0.670777166f, + 0.670848268f, 0.670919365f, 0.670990455f, 0.671061539f, 0.671132617f, + 0.671203689f, 0.671274754f, 0.671345814f, 0.671416867f, 0.671487914f, + 0.671558955f, 0.671629990f, 0.671701018f, 0.671772040f, 0.671843057f, + 0.671914067f, 0.671985071f, 0.672056068f, 0.672127060f, 0.672198045f, + 0.672269024f, 0.672339997f, 0.672410964f, 0.672481924f, 0.672552879f, + 0.672623827f, 0.672694769f, 0.672765705f, 0.672836635f, 0.672907558f, + 0.672978475f, 0.673049387f, 0.673120291f, 0.673191190f, 0.673262083f, + 0.673332969f, 0.673403849f, 0.673474723f, 0.673545591f, 0.673616453f, + 0.673687308f, 0.673758157f, 0.673829000f, 0.673899837f, 0.673970668f, + 0.674041492f, 0.674112311f, 0.674183123f, 0.674253928f, 0.674324728f, + 0.674395522f, 0.674466309f, 0.674537090f, 0.674607865f, 0.674678633f, + 0.674749396f, 0.674820152f, 0.674890902f, 0.674961646f, 0.675032384f, + 0.675103115f, 0.675173840f, 0.675244559f, 0.675315272f, 0.675385979f, + 0.675456679f, 0.675527374f, 0.675598062f, 0.675668743f, 0.675739419f, + 0.675810088f, 0.675880751f, 0.675951408f, 0.676022059f, 0.676092704f, + 0.676163342f, 0.676233974f, 0.676304600f, 0.676375219f, 0.676445833f, + 0.676516440f, 0.676587041f, 0.676657636f, 0.676728224f, 0.676798807f, + 0.676869383f, 0.676939953f, 0.677010516f, 0.677081074f, 0.677151625f, + 0.677222170f, 0.677292709f, 0.677363241f, 0.677433768f, 0.677504288f, + 0.677574802f, 0.677645309f, 0.677715811f, 0.677786306f, 0.677856795f, + 0.677927278f, 0.677997754f, 0.678068224f, 0.678138688f, 0.678209146f, + 0.678279598f, 0.678350043f, 0.678420482f, 0.678490915f, 0.678561342f, + 0.678631762f, 0.678702176f, 0.678772584f, 0.678842986f, 0.678913381f, + 0.678983770f, 0.679054153f, 0.679124530f, 0.679194900f, 0.679265265f, + 0.679335623f, 0.679405974f, 0.679476320f, 0.679546659f, 0.679616992f, + 0.679687319f, 0.679757639f, 0.679827954f, 0.679898262f, 0.679968563f, + 0.680038859f, 0.680109148f, 0.680179431f, 0.680249708f, 0.680319978f, + 0.680390243f, 0.680460501f, 0.680530752f, 0.680600998f, 0.680671237f, + 0.680741470f, 0.680811697f, 0.680881917f, 0.680952131f, 0.681022339f, + 0.681092541f, 0.681162736f, 0.681232925f, 0.681303108f, 0.681373285f, + 0.681443455f, 0.681513619f, 0.681583777f, 0.681653929f, 0.681724074f, + 0.681794213f, 0.681864346f, 0.681934472f, 0.682004593f, 0.682074707f, + 0.682144814f, 0.682214916f, 0.682285011f, 0.682355100f, 0.682425182f, + 0.682495259f, 0.682565329f, 0.682635393f, 0.682705450f, 0.682775501f, + 0.682845546f, 0.682915585f, 0.682985617f, 0.683055644f, 0.683125663f, + 0.683195677f, 0.683265684f, 0.683335685f, 0.683405680f, 0.683475669f, + 0.683545651f, 0.683615627f, 0.683685596f, 0.683755560f, 0.683825517f, + 0.683895467f, 0.683965412f, 0.684035350f, 0.684105282f, 0.684175207f, + 0.684245127f, 0.684315040f, 0.684384947f, 0.684454847f, 0.684524741f, + 0.684594629f, 0.684664511f, 0.684734386f, 0.684804255f, 0.684874117f, + 0.684943974f, 0.685013824f, 0.685083668f, 0.685153505f, 0.685223336f, + 0.685293161f, 0.685362980f, 0.685432792f, 0.685502598f, 0.685572398f, + 0.685642191f, 0.685711978f, 0.685781759f, 0.685851534f, 0.685921302f, + 0.685991064f, 0.686060819f, 0.686130569f, 0.686200312f, 0.686270048f, + 0.686339779f, 0.686409503f, 0.686479220f, 0.686548932f, 0.686618637f, + 0.686688336f, 0.686758028f, 0.686827714f, 0.686897394f, 0.686967068f, + 0.687036735f, 0.687106396f, 0.687176051f, 0.687245699f, 0.687315341f, + 0.687384977f, 0.687454606f, 0.687524229f, 0.687593846f, 0.687663456f, + 0.687733060f, 0.687802658f, 0.687872249f, 0.687941834f, 0.688011413f, + 0.688080985f, 0.688150552f, 0.688220111f, 0.688289665f, 0.688359212f, + 0.688428753f, 0.688498287f, 0.688567815f, 0.688637337f, 0.688706853f, + 0.688776362f, 0.688845865f, 0.688915361f, 0.688984851f, 0.689054335f, + 0.689123813f, 0.689193284f, 0.689262749f, 0.689332207f, 0.689401659f, + 0.689471105f, 0.689540545f, 0.689609978f, 0.689679405f, 0.689748825f, + 0.689818239f, 0.689887647f, 0.689957049f, 0.690026444f, 0.690095832f, + 0.690165215f, 0.690234591f, 0.690303961f, 0.690373324f, 0.690442681f, + 0.690512032f, 0.690581376f, 0.690650714f, 0.690720046f, 0.690789371f, + 0.690858690f, 0.690928003f, 0.690997309f, 0.691066609f, 0.691135902f, + 0.691205190f, 0.691274470f, 0.691343745f, 0.691413013f, 0.691482275f, + 0.691551530f, 0.691620779f, 0.691690022f, 0.691759258f, 0.691828488f, + 0.691897712f, 0.691966929f, 0.692036140f, 0.692105345f, 0.692174543f, + 0.692243735f, 0.692312920f, 0.692382099f, 0.692451272f, 0.692520438f, + 0.692589598f, 0.692658752f, 0.692727899f, 0.692797040f, 0.692866175f, + 0.692935303f, 0.693004425f, 0.693073540f, 0.693142649f, 0.693211752f, + 0.693280848f, 0.693349938f, 0.693419022f, 0.693488099f, 0.693557170f, + 0.693626234f, 0.693695292f, 0.693764344f, 0.693833389f, 0.693902428f, + 0.693971461f, 0.694040487f, 0.694109507f, 0.694178520f, 0.694247527f, + 0.694316528f, 0.694385522f, 0.694454510f, 0.694523492f, 0.694592467f, + 0.694661436f, 0.694730398f, 0.694799354f, 0.694868304f, 0.694937247f, + 0.695006184f, 0.695075114f, 0.695144038f, 0.695212956f, 0.695281867f, + 0.695350772f, 0.695419670f, 0.695488562f, 0.695557448f, 0.695626327f, + 0.695695200f, 0.695764067f, 0.695832927f, 0.695901781f, 0.695970628f, + 0.696039469f, 0.696108303f, 0.696177131f, 0.696245953f, 0.696314769f, + 0.696383577f, 0.696452380f, 0.696521176f, 0.696589966f, 0.696658749f, + 0.696727526f, 0.696796297f, 0.696865061f, 0.696933818f, 0.697002570f, + 0.697071315f, 0.697140053f, 0.697208785f, 0.697277511f, 0.697346230f, + 0.697414943f, 0.697483649f, 0.697552349f, 0.697621043f, 0.697689730f, + 0.697758411f, 0.697827085f, 0.697895753f, 0.697964415f, 0.698033070f, + 0.698101719f, 0.698170361f, 0.698238997f, 0.698307626f, 0.698376249f, + 0.698444866f, 0.698513476f, 0.698582080f, 0.698650677f, 0.698719268f, + 0.698787853f, 0.698856431f, 0.698925003f, 0.698993568f, 0.699062127f, + 0.699130679f, 0.699199225f, 0.699267765f, 0.699336298f, 0.699404824f, + 0.699473345f, 0.699541858f, 0.699610366f, 0.699678867f, 0.699747361f, + 0.699815849f, 0.699884331f, 0.699952806f, 0.700021275f, 0.700089738f, + 0.700158194f, 0.700226643f, 0.700295086f, 0.700363523f, 0.700431953f, + 0.700500377f, 0.700568794f, 0.700637205f, 0.700705609f, 0.700774007f, + 0.700842399f, 0.700910784f, 0.700979163f, 0.701047535f, 0.701115901f, + 0.701184260f, 0.701252613f, 0.701320959f, 0.701389299f, 0.701457633f, + 0.701525960f, 0.701594281f, 0.701662595f, 0.701730902f, 0.701799204f, + 0.701867499f, 0.701935787f, 0.702004069f, 0.702072345f, 0.702140614f, + 0.702208876f, 0.702277132f, 0.702345382f, 0.702413625f, 0.702481862f, + 0.702550092f, 0.702618316f, 0.702686534f, 0.702754744f, 0.702822949f, + 0.702891147f, 0.702959339f, 0.703027524f, 0.703095702f, 0.703163874f, + 0.703232040f, 0.703300199f, 0.703368352f, 0.703436498f, 0.703504638f, + 0.703572772f, 0.703640899f, 0.703709019f, 0.703777133f, 0.703845241f, + 0.703913342f, 0.703981436f, 0.704049524f, 0.704117606f, 0.704185681f, + 0.704253750f, 0.704321812f, 0.704389868f, 0.704457917f, 0.704525960f, + 0.704593996f, 0.704662026f, 0.704730049f, 0.704798066f, 0.704866076f, + 0.704934080f, 0.705002078f, 0.705070069f, 0.705138053f, 0.705206031f, + 0.705274003f, 0.705341968f, 0.705409926f, 0.705477878f, 0.705545824f, + 0.705613763f, 0.705681696f, 0.705749622f, 0.705817541f, 0.705885455f, + 0.705953361f, 0.706021261f, 0.706089155f, 0.706157042f, 0.706224923f, + 0.706292797f, 0.706360665f, 0.706428526f, 0.706496381f, 0.706564229f, + 0.706632071f, 0.706699906f, 0.706767735f, 0.706835557f, 0.706903373f, + 0.706971182f, 0.707038985f, 0.707106781f, 0.707174571f, 0.707242354f, + 0.707310131f, 0.707377901f, 0.707445665f, 0.707513422f, 0.707581173f, + 0.707648917f, 0.707716655f, 0.707784386f, 0.707852111f, 0.707919829f, + 0.707987541f, 0.708055246f, 0.708122945f, 0.708190637f, 0.708258323f, + 0.708326002f, 0.708393675f, 0.708461341f, 0.708529000f, 0.708596653f, + 0.708664300f, 0.708731940f, 0.708799574f, 0.708867201f, 0.708934821f, + 0.709002435f, 0.709070043f, 0.709137644f, 0.709205238f, 0.709272826f, + 0.709340408f, 0.709407983f, 0.709475551f, 0.709543113f, 0.709610668f, + 0.709678217f, 0.709745760f, 0.709813295f, 0.709880825f, 0.709948347f, + 0.710015864f, 0.710083373f, 0.710150877f, 0.710218373f, 0.710285863f, + 0.710353347f, 0.710420824f, 0.710488294f, 0.710555758f, 0.710623216f, + 0.710690667f, 0.710758111f, 0.710825549f, 0.710892980f, 0.710960405f, + 0.711027823f, 0.711095235f, 0.711162640f, 0.711230039f, 0.711297431f, + 0.711364817f, 0.711432196f, 0.711499568f, 0.711566934f, 0.711634294f, + 0.711701646f, 0.711768993f, 0.711836333f, 0.711903666f, 0.711970993f, + 0.712038313f, 0.712105626f, 0.712172933f, 0.712240234f, 0.712307528f, + 0.712374815f, 0.712442096f, 0.712509371f, 0.712576638f, 0.712643900f, + 0.712711154f, 0.712778402f, 0.712845644f, 0.712912879f, 0.712980107f, + 0.713047329f, 0.713114545f, 0.713181754f, 0.713248956f, 0.713316152f, + 0.713383341f, 0.713450523f, 0.713517699f, 0.713584869f, 0.713652032f, + 0.713719188f, 0.713786338f, 0.713853481f, 0.713920618f, 0.713987748f, + 0.714054871f, 0.714121988f, 0.714189099f, 0.714256203f, 0.714323300f, + 0.714390391f, 0.714457475f, 0.714524552f, 0.714591623f, 0.714658688f, + 0.714725746f, 0.714792797f, 0.714859842f, 0.714926880f, 0.714993912f, + 0.715060937f, 0.715127955f, 0.715194967f, 0.715261972f, 0.715328971f, + 0.715395963f, 0.715462949f, 0.715529928f, 0.715596900f, 0.715663866f, + 0.715730825f, 0.715797778f, 0.715864724f, 0.715931664f, 0.715998597f, + 0.716065523f, 0.716132443f, 0.716199356f, 0.716266263f, 0.716333163f, + 0.716400056f, 0.716466943f, 0.716533823f, 0.716600697f, 0.716667564f, + 0.716734425f, 0.716801279f, 0.716868126f, 0.716934967f, 0.717001801f, + 0.717068628f, 0.717135449f, 0.717202264f, 0.717269072f, 0.717335873f, + 0.717402667f, 0.717469455f, 0.717536237f, 0.717603012f, 0.717669780f, + 0.717736542f, 0.717803297f, 0.717870045f, 0.717936787f, 0.718003522f, + 0.718070251f, 0.718136973f, 0.718203688f, 0.718270397f, 0.718337099f, + 0.718403795f, 0.718470484f, 0.718537166f, 0.718603842f, 0.718670512f, + 0.718737174f, 0.718803830f, 0.718870480f, 0.718937122f, 0.719003759f, + 0.719070388f, 0.719137011f, 0.719203627f, 0.719270237f, 0.719336840f, + 0.719403437f, 0.719470027f, 0.719536610f, 0.719603187f, 0.719669757f, + 0.719736320f, 0.719802877f, 0.719869427f, 0.719935971f, 0.720002508f, + 0.720069038f, 0.720135562f, 0.720202079f, 0.720268590f, 0.720335094f, + 0.720401591f, 0.720468082f, 0.720534566f, 0.720601043f, 0.720667514f, + 0.720733978f, 0.720800435f, 0.720866886f, 0.720933331f, 0.720999768f, + 0.721066199f, 0.721132624f, 0.721199041f, 0.721265453f, 0.721331857f, + 0.721398255f, 0.721464646f, 0.721531031f, 0.721597409f, 0.721663780f, + 0.721730145f, 0.721796503f, 0.721862854f, 0.721929199f, 0.721995537f, + 0.722061869f, 0.722128194f, 0.722194512f, 0.722260824f, 0.722327129f, + 0.722393427f, 0.722459719f, 0.722526004f, 0.722592282f, 0.722658554f, + 0.722724819f, 0.722791078f, 0.722857330f, 0.722923575f, 0.722989813f, + 0.723056045f, 0.723122271f, 0.723188489f, 0.723254701f, 0.723320907f, + 0.723387105f, 0.723453297f, 0.723519483f, 0.723585661f, 0.723651834f, + 0.723717999f, 0.723784158f, 0.723850310f, 0.723916455f, 0.723982594f, + 0.724048726f, 0.724114852f, 0.724180971f, 0.724247083f, 0.724313188f, + 0.724379287f, 0.724445380f, 0.724511465f, 0.724577544f, 0.724643616f, + 0.724709682f, 0.724775741f, 0.724841793f, 0.724907839f, 0.724973878f, + 0.725039910f, 0.725105936f, 0.725171954f, 0.725237967f, 0.725303972f, + 0.725369971f, 0.725435964f, 0.725501949f, 0.725567928f, 0.725633900f, + 0.725699866f, 0.725765825f, 0.725831777f, 0.725897723f, 0.725963662f, + 0.726029594f, 0.726095520f, 0.726161438f, 0.726227351f, 0.726293256f, + 0.726359155f, 0.726425047f, 0.726490933f, 0.726556812f, 0.726622684f, + 0.726688549f, 0.726754408f, 0.726820260f, 0.726886106f, 0.726951944f, + 0.727017776f, 0.727083602f, 0.727149421f, 0.727215233f, 0.727281038f, + 0.727346837f, 0.727412629f, 0.727478414f, 0.727544192f, 0.727609964f, + 0.727675730f, 0.727741488f, 0.727807240f, 0.727872985f, 0.727938724f, + 0.728004455f, 0.728070180f, 0.728135899f, 0.728201611f, 0.728267316f, + 0.728333014f, 0.728398706f, 0.728464390f, 0.728530069f, 0.728595740f, + 0.728661405f, 0.728727063f, 0.728792715f, 0.728858359f, 0.728923997f, + 0.728989629f, 0.729055253f, 0.729120871f, 0.729186483f, 0.729252087f, + 0.729317685f, 0.729383276f, 0.729448860f, 0.729514438f, 0.729580009f, + 0.729645573f, 0.729711131f, 0.729776682f, 0.729842226f, 0.729907764f, + 0.729973294f, 0.730038818f, 0.730104336f, 0.730169846f, 0.730235350f, + 0.730300848f, 0.730366338f, 0.730431822f, 0.730497299f, 0.730562769f, + 0.730628233f, 0.730693690f, 0.730759140f, 0.730824583f, 0.730890020f, + 0.730955450f, 0.731020874f, 0.731086290f, 0.731151700f, 0.731217103f, + 0.731282500f, 0.731347890f, 0.731413273f, 0.731478649f, 0.731544018f, + 0.731609381f, 0.731674737f, 0.731740087f, 0.731805429f, 0.731870765f, + 0.731936095f, 0.732001417f, 0.732066733f, 0.732132042f, 0.732197344f, + 0.732262640f, 0.732327928f, 0.732393211f, 0.732458486f, 0.732523755f, + 0.732589017f, 0.732654272f, 0.732719520f, 0.732784762f, 0.732849997f, + 0.732915225f, 0.732980446f, 0.733045661f, 0.733110869f, 0.733176071f, + 0.733241265f, 0.733306453f, 0.733371634f, 0.733436808f, 0.733501976f, + 0.733567137f, 0.733632291f, 0.733697438f, 0.733762579f, 0.733827713f, + 0.733892840f, 0.733957960f, 0.734023074f, 0.734088181f, 0.734153281f, + 0.734218374f, 0.734283461f, 0.734348541f, 0.734413614f, 0.734478680f, + 0.734543740f, 0.734608793f, 0.734673839f, 0.734738878f, 0.734803911f, + 0.734868937f, 0.734933956f, 0.734998968f, 0.735063974f, 0.735128972f, + 0.735193965f, 0.735258950f, 0.735323928f, 0.735388900f, 0.735453865f, + 0.735518824f, 0.735583775f, 0.735648720f, 0.735713658f, 0.735778589f, + 0.735843514f, 0.735908431f, 0.735973342f, 0.736038247f, 0.736103144f, + 0.736168035f, 0.736232918f, 0.736297796f, 0.736362666f, 0.736427530f, + 0.736492386f, 0.736557236f, 0.736622080f, 0.736686916f, 0.736751746f, + 0.736816569f, 0.736881385f, 0.736946194f, 0.737010997f, 0.737075793f, + 0.737140582f, 0.737205364f, 0.737270140f, 0.737334909f, 0.737399671f, + 0.737464426f, 0.737529174f, 0.737593916f, 0.737658651f, 0.737723379f, + 0.737788100f, 0.737852815f, 0.737917523f, 0.737982223f, 0.738046918f, + 0.738111605f, 0.738176286f, 0.738240960f, 0.738305627f, 0.738370287f, + 0.738434940f, 0.738499587f, 0.738564227f, 0.738628860f, 0.738693486f, + 0.738758106f, 0.738822719f, 0.738887324f, 0.738951924f, 0.739016516f, + 0.739081102f, 0.739145680f, 0.739210252f, 0.739274817f, 0.739339376f, + 0.739403927f, 0.739468472f, 0.739533010f, 0.739597541f, 0.739662066f, + 0.739726583f, 0.739791094f, 0.739855598f, 0.739920095f, 0.739984586f, + 0.740049069f, 0.740113546f, 0.740178016f, 0.740242479f, 0.740306936f, + 0.740371385f, 0.740435828f, 0.740500264f, 0.740564693f, 0.740629116f, + 0.740693531f, 0.740757940f, 0.740822342f, 0.740886737f, 0.740951125f, + 0.741015507f, 0.741079882f, 0.741144249f, 0.741208610f, 0.741272965f, + 0.741337312f, 0.741401653f, 0.741465987f, 0.741530314f, 0.741594634f, + 0.741658947f, 0.741723254f, 0.741787553f, 0.741851846f, 0.741916132f, + 0.741980412f, 0.742044684f, 0.742108950f, 0.742173209f, 0.742237461f, + 0.742301706f, 0.742365944f, 0.742430176f, 0.742494400f, 0.742558618f, + 0.742622829f, 0.742687033f, 0.742751231f, 0.742815421f, 0.742879605f, + 0.742943782f, 0.743007952f, 0.743072115f, 0.743136272f, 0.743200421f, + 0.743264564f, 0.743328700f, 0.743392829f, 0.743456951f, 0.743521067f, + 0.743585175f, 0.743649277f, 0.743713372f, 0.743777460f, 0.743841541f, + 0.743905616f, 0.743969683f, 0.744033744f, 0.744097798f, 0.744161845f, + 0.744225885f, 0.744289919f, 0.744353945f, 0.744417965f, 0.744481978f, + 0.744545984f, 0.744609983f, 0.744673975f, 0.744737961f, 0.744801939f, + 0.744865911f, 0.744929876f, 0.744993834f, 0.745057785f, 0.745121730f, + 0.745185667f, 0.745249598f, 0.745313522f, 0.745377439f, 0.745441349f, + 0.745505252f, 0.745569149f, 0.745633038f, 0.745696921f, 0.745760797f, + 0.745824666f, 0.745888528f, 0.745952383f, 0.746016232f, 0.746080074f, + 0.746143908f, 0.746207736f, 0.746271557f, 0.746335371f, 0.746399179f, + 0.746462979f, 0.746526773f, 0.746590559f, 0.746654339f, 0.746718112f, + 0.746781878f, 0.746845638f, 0.746909390f, 0.746973136f, 0.747036874f, + 0.747100606f, 0.747164331f, 0.747228049f, 0.747291760f, 0.747355465f, + 0.747419162f, 0.747482853f, 0.747546536f, 0.747610213f, 0.747673883f, + 0.747737546f, 0.747801202f, 0.747864852f, 0.747928494f, 0.747992130f, + 0.748055759f, 0.748119380f, 0.748182995f, 0.748246604f, 0.748310205f, + 0.748373799f, 0.748437387f, 0.748500967f, 0.748564541f, 0.748628108f, + 0.748691668f, 0.748755221f, 0.748818767f, 0.748882306f, 0.748945839f, + 0.749009364f, 0.749072883f, 0.749136395f, 0.749199899f, 0.749263397f, + 0.749326888f, 0.749390373f, 0.749453850f, 0.749517320f, 0.749580784f, + 0.749644241f, 0.749707690f, 0.749771133f, 0.749834569f, 0.749897998f, + 0.749961421f, 0.750024836f, 0.750088244f, 0.750151646f, 0.750215040f, + 0.750278428f, 0.750341809f, 0.750405183f, 0.750468550f, 0.750531910f, + 0.750595263f, 0.750658610f, 0.750721949f, 0.750785282f, 0.750848607f, + 0.750911926f, 0.750975238f, 0.751038543f, 0.751101841f, 0.751165132f, + 0.751228416f, 0.751291693f, 0.751354964f, 0.751418227f, 0.751481484f, + 0.751544734f, 0.751607976f, 0.751671212f, 0.751734441f, 0.751797663f, + 0.751860878f, 0.751924087f, 0.751987288f, 0.752050482f, 0.752113670f, + 0.752176850f, 0.752240024f, 0.752303191f, 0.752366351f, 0.752429504f, + 0.752492650f, 0.752555789f, 0.752618921f, 0.752682046f, 0.752745164f, + 0.752808276f, 0.752871380f, 0.752934478f, 0.752997569f, 0.753060652f, + 0.753123729f, 0.753186799f, 0.753249862f, 0.753312918f, 0.753375967f, + 0.753439009f, 0.753502045f, 0.753565073f, 0.753628094f, 0.753691109f, + 0.753754116f, 0.753817117f, 0.753880111f, 0.753943098f, 0.754006077f, + 0.754069050f, 0.754132016f, 0.754194975f, 0.754257927f, 0.754320873f, + 0.754383811f, 0.754446742f, 0.754509667f, 0.754572584f, 0.754635495f, + 0.754698398f, 0.754761295f, 0.754824184f, 0.754887067f, 0.754949943f, + 0.755012812f, 0.755075674f, 0.755138529f, 0.755201377f, 0.755264218f, + 0.755327052f, 0.755389879f, 0.755452700f, 0.755515513f, 0.755578319f, + 0.755641119f, 0.755703911f, 0.755766697f, 0.755829476f, 0.755892247f, + 0.755955012f, 0.756017770f, 0.756080521f, 0.756143264f, 0.756206001f, + 0.756268731f, 0.756331454f, 0.756394170f, 0.756456880f, 0.756519582f, + 0.756582277f, 0.756644965f, 0.756707647f, 0.756770321f, 0.756832988f, + 0.756895649f, 0.756958302f, 0.757020949f, 0.757083588f, 0.757146221f, + 0.757208847f, 0.757271465f, 0.757334077f, 0.757396682f, 0.757459279f, + 0.757521870f, 0.757584454f, 0.757647031f, 0.757709601f, 0.757772164f, + 0.757834720f, 0.757897269f, 0.757959811f, 0.758022346f, 0.758084874f, + 0.758147396f, 0.758209910f, 0.758272417f, 0.758334917f, 0.758397411f, + 0.758459897f, 0.758522376f, 0.758584849f, 0.758647314f, 0.758709773f, + 0.758772224f, 0.758834669f, 0.758897106f, 0.758959537f, 0.759021960f, + 0.759084377f, 0.759146786f, 0.759209189f, 0.759271585f, 0.759333973f, + 0.759396355f, 0.759458730f, 0.759521097f, 0.759583458f, 0.759645812f, + 0.759708159f, 0.759770499f, 0.759832831f, 0.759895157f, 0.759957476f, + 0.760019788f, 0.760082093f, 0.760144391f, 0.760206682f, 0.760268966f, + 0.760331243f, 0.760393512f, 0.760455775f, 0.760518031f, 0.760580280f, + 0.760642522f, 0.760704757f, 0.760766985f, 0.760829206f, 0.760891420f, + 0.760953627f, 0.761015827f, 0.761078020f, 0.761140206f, 0.761202385f, + 0.761264558f, 0.761326723f, 0.761388881f, 0.761451032f, 0.761513176f, + 0.761575313f, 0.761637443f, 0.761699566f, 0.761761682f, 0.761823791f, + 0.761885893f, 0.761947988f, 0.762010076f, 0.762072157f, 0.762134231f, + 0.762196298f, 0.762258358f, 0.762320411f, 0.762382457f, 0.762444496f, + 0.762506528f, 0.762568553f, 0.762630571f, 0.762692582f, 0.762754586f, + 0.762816583f, 0.762878573f, 0.762940556f, 0.763002532f, 0.763064501f, + 0.763126462f, 0.763188417f, 0.763250365f, 0.763312306f, 0.763374240f, + 0.763436167f, 0.763498086f, 0.763559999f, 0.763621905f, 0.763683804f, + 0.763745695f, 0.763807580f, 0.763869458f, 0.763931328f, 0.763993192f, + 0.764055048f, 0.764116898f, 0.764178741f, 0.764240576f, 0.764302405f, + 0.764364226f, 0.764426040f, 0.764487848f, 0.764549648f, 0.764611442f, + 0.764673228f, 0.764735007f, 0.764796780f, 0.764858545f, 0.764920303f, + 0.764982054f, 0.765043798f, 0.765105536f, 0.765167266f, 0.765228989f, + 0.765290705f, 0.765352414f, 0.765414116f, 0.765475811f, 0.765537498f, + 0.765599179f, 0.765660853f, 0.765722520f, 0.765784180f, 0.765845832f, + 0.765907478f, 0.765969117f, 0.766030748f, 0.766092373f, 0.766153990f, + 0.766215601f, 0.766277204f, 0.766338800f, 0.766400390f, 0.766461972f, + 0.766523547f, 0.766585115f, 0.766646677f, 0.766708231f, 0.766769778f, + 0.766831318f, 0.766892851f, 0.766954377f, 0.767015895f, 0.767077407f, + 0.767138912f, 0.767200410f, 0.767261900f, 0.767323384f, 0.767384860f, + 0.767446330f, 0.767507792f, 0.767569248f, 0.767630696f, 0.767692137f, + 0.767753571f, 0.767814999f, 0.767876419f, 0.767937832f, 0.767999238f, + 0.768060637f, 0.768122029f, 0.768183413f, 0.768244791f, 0.768306162f, + 0.768367525f, 0.768428882f, 0.768490231f, 0.768551574f, 0.768612909f, + 0.768674237f, 0.768735559f, 0.768796873f, 0.768858180f, 0.768919480f, + 0.768980773f, 0.769042059f, 0.769103338f, 0.769164609f, 0.769225874f, + 0.769287132f, 0.769348382f, 0.769409626f, 0.769470862f, 0.769532091f, + 0.769593314f, 0.769654529f, 0.769715737f, 0.769776938f, 0.769838132f, + 0.769899319f, 0.769960499f, 0.770021671f, 0.770082837f, 0.770143996f, + 0.770205147f, 0.770266291f, 0.770327429f, 0.770388559f, 0.770449682f, + 0.770510798f, 0.770571907f, 0.770633009f, 0.770694104f, 0.770755192f, + 0.770816272f, 0.770877346f, 0.770938413f, 0.770999472f, 0.771060524f, + 0.771121569f, 0.771182608f, 0.771243639f, 0.771304663f, 0.771365680f, + 0.771426689f, 0.771487692f, 0.771548688f, 0.771609676f, 0.771670658f, + 0.771731632f, 0.771792599f, 0.771853559f, 0.771914512f, 0.771975458f, + 0.772036397f, 0.772097329f, 0.772158254f, 0.772219171f, 0.772280082f, + 0.772340985f, 0.772401881f, 0.772462770f, 0.772523652f, 0.772584527f, + 0.772645395f, 0.772706256f, 0.772767110f, 0.772827956f, 0.772888796f, + 0.772949628f, 0.773010453f, 0.773071272f, 0.773132083f, 0.773192886f, + 0.773253683f, 0.773314473f, 0.773375256f, 0.773436031f, 0.773496799f, + 0.773557561f, 0.773618315f, 0.773679062f, 0.773739802f, 0.773800535f, + 0.773861261f, 0.773921979f, 0.773982691f, 0.774043395f, 0.774104092f, + 0.774164782f, 0.774225465f, 0.774286141f, 0.774346810f, 0.774407472f, + 0.774468126f, 0.774528774f, 0.774589414f, 0.774650047f, 0.774710673f, + 0.774771292f, 0.774831904f, 0.774892509f, 0.774953107f, 0.775013697f, + 0.775074280f, 0.775134857f, 0.775195426f, 0.775255988f, 0.775316543f, + 0.775377090f, 0.775437631f, 0.775498164f, 0.775558691f, 0.775619210f, + 0.775679722f, 0.775740227f, 0.775800725f, 0.775861215f, 0.775921699f, + 0.775982175f, 0.776042645f, 0.776103107f, 0.776163562f, 0.776224010f, + 0.776284451f, 0.776344884f, 0.776405311f, 0.776465730f, 0.776526142f, + 0.776586547f, 0.776646945f, 0.776707336f, 0.776767720f, 0.776828096f, + 0.776888466f, 0.776948828f, 0.777009183f, 0.777069531f, 0.777129872f, + 0.777190205f, 0.777250532f, 0.777310851f, 0.777371164f, 0.777431469f, + 0.777491767f, 0.777552057f, 0.777612341f, 0.777672618f, 0.777732887f, + 0.777793149f, 0.777853404f, 0.777913652f, 0.777973893f, 0.778034126f, + 0.778094353f, 0.778154572f, 0.778214784f, 0.778274989f, 0.778335187f, + 0.778395378f, 0.778455561f, 0.778515738f, 0.778575907f, 0.778636069f, + 0.778696224f, 0.778756372f, 0.778816512f, 0.778876646f, 0.778936772f, + 0.778996891f, 0.779057003f, 0.779117108f, 0.779177206f, 0.779237296f, + 0.779297379f, 0.779357456f, 0.779417524f, 0.779477586f, 0.779537641f, + 0.779597688f, 0.779657729f, 0.779717762f, 0.779777788f, 0.779837807f, + 0.779897818f, 0.779957823f, 0.780017820f, 0.780077810f, 0.780137793f, + 0.780197769f, 0.780257738f, 0.780317699f, 0.780377653f, 0.780437601f, + 0.780497541f, 0.780557473f, 0.780617399f, 0.780677317f, 0.780737229f, + 0.780797133f, 0.780857030f, 0.780916919f, 0.780976802f, 0.781036677f, + 0.781096545f, 0.781156406f, 0.781216260f, 0.781276107f, 0.781335946f, + 0.781395778f, 0.781455604f, 0.781515421f, 0.781575232f, 0.781635036f, + 0.781694832f, 0.781754621f, 0.781814403f, 0.781874178f, 0.781933946f, + 0.781993706f, 0.782053459f, 0.782113205f, 0.782172944f, 0.782232676f, + 0.782292400f, 0.782352118f, 0.782411828f, 0.782471531f, 0.782531226f, + 0.782590915f, 0.782650596f, 0.782710270f, 0.782769937f, 0.782829597f, + 0.782889250f, 0.782948895f, 0.783008533f, 0.783068164f, 0.783127788f, + 0.783187404f, 0.783247014f, 0.783306616f, 0.783366211f, 0.783425799f, + 0.783485379f, 0.783544952f, 0.783604519f, 0.783664078f, 0.783723629f, + 0.783783174f, 0.783842711f, 0.783902241f, 0.783961764f, 0.784021280f, + 0.784080789f, 0.784140290f, 0.784199784f, 0.784259271f, 0.784318751f, + 0.784378223f, 0.784437688f, 0.784497146f, 0.784556597f, 0.784616041f, + 0.784675477f, 0.784734906f, 0.784794328f, 0.784853743f, 0.784913151f, + 0.784972551f, 0.785031944f, 0.785091330f, 0.785150709f, 0.785210080f, + 0.785269445f, 0.785328802f, 0.785388152f, 0.785447494f, 0.785506830f, + 0.785566158f, 0.785625479f, 0.785684792f, 0.785744099f, 0.785803398f, + 0.785862690f, 0.785921975f, 0.785981253f, 0.786040523f, 0.786099786f, + 0.786159042f, 0.786218291f, 0.786277532f, 0.786336767f, 0.786395994f, + 0.786455214f, 0.786514426f, 0.786573632f, 0.786632830f, 0.786692021f, + 0.786751204f, 0.786810381f, 0.786869550f, 0.786928712f, 0.786987867f, + 0.787047014f, 0.787106154f, 0.787165287f, 0.787224413f, 0.787283532f, + 0.787342643f, 0.787401747f, 0.787460844f, 0.787519933f, 0.787579016f, + 0.787638091f, 0.787697159f, 0.787756220f, 0.787815273f, 0.787874319f, + 0.787933358f, 0.787992390f, 0.788051414f, 0.788110431f, 0.788169441f, + 0.788228444f, 0.788287439f, 0.788346428f, 0.788405409f, 0.788464382f, + 0.788523349f, 0.788582308f, 0.788641260f, 0.788700205f, 0.788759142f, + 0.788818072f, 0.788876995f, 0.788935911f, 0.788994820f, 0.789053721f, + 0.789112615f, 0.789171502f, 0.789230381f, 0.789289253f, 0.789348118f, + 0.789406976f, 0.789465826f, 0.789524669f, 0.789583505f, 0.789642334f, + 0.789701155f, 0.789759970f, 0.789818776f, 0.789877576f, 0.789936368f, + 0.789995154f, 0.790053931f, 0.790112702f, 0.790171465f, 0.790230221f, + 0.790288970f, 0.790347712f, 0.790406446f, 0.790465173f, 0.790523893f, + 0.790582605f, 0.790641310f, 0.790700008f, 0.790758699f, 0.790817382f, + 0.790876059f, 0.790934727f, 0.790993389f, 0.791052043f, 0.791110690f, + 0.791169330f, 0.791227963f, 0.791286588f, 0.791345206f, 0.791403817f, + 0.791462420f, 0.791521016f, 0.791579605f, 0.791638187f, 0.791696761f, + 0.791755328f, 0.791813888f, 0.791872440f, 0.791930985f, 0.791989523f, + 0.792048054f, 0.792106577f, 0.792165093f, 0.792223602f, 0.792282104f, + 0.792340598f, 0.792399085f, 0.792457565f, 0.792516037f, 0.792574502f, + 0.792632960f, 0.792691410f, 0.792749854f, 0.792808290f, 0.792866718f, + 0.792925140f, 0.792983554f, 0.793041960f, 0.793100360f, 0.793158752f, + 0.793217137f, 0.793275515f, 0.793333885f, 0.793392248f, 0.793450604f, + 0.793508952f, 0.793567294f, 0.793625627f, 0.793683954f, 0.793742273f, + 0.793800585f, 0.793858890f, 0.793917187f, 0.793975478f, 0.794033760f, + 0.794092036f, 0.794150304f, 0.794208565f, 0.794266819f, 0.794325065f, + 0.794383304f, 0.794441536f, 0.794499760f, 0.794557977f, 0.794616187f, + 0.794674389f, 0.794732585f, 0.794790772f, 0.794848953f, 0.794907126f, + 0.794965292f, 0.795023451f, 0.795081602f, 0.795139746f, 0.795197883f, + 0.795256012f, 0.795314135f, 0.795372249f, 0.795430357f, 0.795488457f, + 0.795546550f, 0.795604636f, 0.795662714f, 0.795720785f, 0.795778848f, + 0.795836905f, 0.795894954f, 0.795952995f, 0.796011030f, 0.796069057f, + 0.796127076f, 0.796185089f, 0.796243094f, 0.796301092f, 0.796359082f, + 0.796417065f, 0.796475041f, 0.796533009f, 0.796590971f, 0.796648924f, + 0.796706871f, 0.796764810f, 0.796822742f, 0.796880667f, 0.796938584f, + 0.796996494f, 0.797054396f, 0.797112292f, 0.797170179f, 0.797228060f, + 0.797285933f, 0.797343799f, 0.797401658f, 0.797459509f, 0.797517353f, + 0.797575190f, 0.797633019f, 0.797690841f, 0.797748656f, 0.797806463f, + 0.797864263f, 0.797922055f, 0.797979841f, 0.798037619f, 0.798095389f, + 0.798153153f, 0.798210908f, 0.798268657f, 0.798326398f, 0.798384132f, + 0.798441859f, 0.798499578f, 0.798557290f, 0.798614995f, 0.798672692f, + 0.798730382f, 0.798788064f, 0.798845740f, 0.798903407f, 0.798961068f, + 0.799018721f, 0.799076367f, 0.799134005f, 0.799191637f, 0.799249260f, + 0.799306877f, 0.799364486f, 0.799422088f, 0.799479682f, 0.799537269f, + 0.799594849f, 0.799652421f, 0.799709986f, 0.799767544f, 0.799825094f, + 0.799882637f, 0.799940173f, 0.799997701f, 0.800055222f, 0.800112735f, + 0.800170242f, 0.800227740f, 0.800285232f, 0.800342716f, 0.800400193f, + 0.800457662f, 0.800515124f, 0.800572579f, 0.800630026f, 0.800687466f, + 0.800744899f, 0.800802324f, 0.800859742f, 0.800917153f, 0.800974556f, + 0.801031952f, 0.801089340f, 0.801146721f, 0.801204095f, 0.801261461f, + 0.801318820f, 0.801376172f, 0.801433516f, 0.801490853f, 0.801548182f, + 0.801605505f, 0.801662819f, 0.801720127f, 0.801777427f, 0.801834719f, + 0.801892005f, 0.801949283f, 0.802006553f, 0.802063816f, 0.802121072f, + 0.802178321f, 0.802235562f, 0.802292796f, 0.802350022f, 0.802407241f, + 0.802464452f, 0.802521657f, 0.802578853f, 0.802636043f, 0.802693225f, + 0.802750400f, 0.802807567f, 0.802864727f, 0.802921879f, 0.802979025f, + 0.803036162f, 0.803093293f, 0.803150416f, 0.803207531f, 0.803264640f, + 0.803321741f, 0.803378834f, 0.803435920f, 0.803492999f, 0.803550070f, + 0.803607134f, 0.803664191f, 0.803721240f, 0.803778282f, 0.803835316f, + 0.803892343f, 0.803949363f, 0.804006375f, 0.804063380f, 0.804120377f, + 0.804177367f, 0.804234350f, 0.804291325f, 0.804348293f, 0.804405254f, + 0.804462207f, 0.804519153f, 0.804576091f, 0.804633022f, 0.804689945f, + 0.804746861f, 0.804803770f, 0.804860672f, 0.804917565f, 0.804974452f, + 0.805031331f, 0.805088203f, 0.805145067f, 0.805201924f, 0.805258774f, + 0.805315616f, 0.805372451f, 0.805429278f, 0.805486098f, 0.805542910f, + 0.805599715f, 0.805656513f, 0.805713303f, 0.805770086f, 0.805826862f, + 0.805883630f, 0.805940391f, 0.805997144f, 0.806053890f, 0.806110628f, + 0.806167359f, 0.806224083f, 0.806280799f, 0.806337508f, 0.806394209f, + 0.806450903f, 0.806507590f, 0.806564269f, 0.806620941f, 0.806677605f, + 0.806734262f, 0.806790911f, 0.806847554f, 0.806904188f, 0.806960815f, + 0.807017435f, 0.807074048f, 0.807130653f, 0.807187250f, 0.807243840f, + 0.807300423f, 0.807356999f, 0.807413566f, 0.807470127f, 0.807526680f, + 0.807583226f, 0.807639764f, 0.807696295f, 0.807752818f, 0.807809334f, + 0.807865842f, 0.807922343f, 0.807978837f, 0.808035323f, 0.808091802f, + 0.808148274f, 0.808204737f, 0.808261194f, 0.808317643f, 0.808374085f, + 0.808430519f, 0.808486946f, 0.808543365f, 0.808599777f, 0.808656182f, + 0.808712579f, 0.808768968f, 0.808825350f, 0.808881725f, 0.808938093f, + 0.808994452f, 0.809050805f, 0.809107150f, 0.809163488f, 0.809219818f, + 0.809276140f, 0.809332456f, 0.809388764f, 0.809445064f, 0.809501357f, + 0.809557642f, 0.809613920f, 0.809670191f, 0.809726454f, 0.809782710f, + 0.809838958f, 0.809895199f, 0.809951433f, 0.810007659f, 0.810063877f, + 0.810120088f, 0.810176292f, 0.810232488f, 0.810288677f, 0.810344858f, + 0.810401032f, 0.810457198f, 0.810513357f, 0.810569509f, 0.810625653f, + 0.810681789f, 0.810737918f, 0.810794040f, 0.810850154f, 0.810906261f, + 0.810962360f, 0.811018452f, 0.811074537f, 0.811130614f, 0.811186683f, + 0.811242745f, 0.811298800f, 0.811354847f, 0.811410887f, 0.811466919f, + 0.811522944f, 0.811578961f, 0.811634971f, 0.811690973f, 0.811746968f, + 0.811802956f, 0.811858936f, 0.811914908f, 0.811970873f, 0.812026831f, + 0.812082781f, 0.812138724f, 0.812194659f, 0.812250587f, 0.812306507f, + 0.812362420f, 0.812418325f, 0.812474223f, 0.812530113f, 0.812585996f, + 0.812641872f, 0.812697740f, 0.812753600f, 0.812809453f, 0.812865299f, + 0.812921137f, 0.812976968f, 0.813032791f, 0.813088607f, 0.813144415f, + 0.813200216f, 0.813256009f, 0.813311795f, 0.813367573f, 0.813423344f, + 0.813479107f, 0.813534863f, 0.813590612f, 0.813646353f, 0.813702086f, + 0.813757812f, 0.813813530f, 0.813869242f, 0.813924945f, 0.813980641f, + 0.814036330f, 0.814092011f, 0.814147684f, 0.814203351f, 0.814259009f, + 0.814314660f, 0.814370304f, 0.814425940f, 0.814481569f, 0.814537190f, + 0.814592804f, 0.814648410f, 0.814704009f, 0.814759600f, 0.814815184f, + 0.814870760f, 0.814926329f, 0.814981890f, 0.815037444f, 0.815092991f, + 0.815148529f, 0.815204061f, 0.815259585f, 0.815315101f, 0.815370610f, + 0.815426111f, 0.815481605f, 0.815537091f, 0.815592570f, 0.815648042f, + 0.815703506f, 0.815758962f, 0.815814411f, 0.815869852f, 0.815925286f, + 0.815980712f, 0.816036131f, 0.816091543f, 0.816146947f, 0.816202343f, + 0.816257732f, 0.816313113f, 0.816368487f, 0.816423854f, 0.816479212f, + 0.816534564f, 0.816589908f, 0.816645244f, 0.816700573f, 0.816755894f, + 0.816811208f, 0.816866514f, 0.816921813f, 0.816977104f, 0.817032388f, + 0.817087665f, 0.817142933f, 0.817198195f, 0.817253448f, 0.817308695f, + 0.817363933f, 0.817419165f, 0.817474388f, 0.817529604f, 0.817584813f, + 0.817640014f, 0.817695208f, 0.817750394f, 0.817805573f, 0.817860744f, + 0.817915907f, 0.817971063f, 0.818026212f, 0.818081353f, 0.818136487f, + 0.818191612f, 0.818246731f, 0.818301842f, 0.818356945f, 0.818412041f, + 0.818467130f, 0.818522210f, 0.818577284f, 0.818632350f, 0.818687408f, + 0.818742459f, 0.818797502f, 0.818852538f, 0.818907566f, 0.818962586f, + 0.819017599f, 0.819072605f, 0.819127603f, 0.819182594f, 0.819237577f, + 0.819292552f, 0.819347520f, 0.819402480f, 0.819457433f, 0.819512379f, + 0.819567317f, 0.819622247f, 0.819677170f, 0.819732085f, 0.819786992f, + 0.819841893f, 0.819896785f, 0.819951670f, 0.820006548f, 0.820061418f, + 0.820116280f, 0.820171135f, 0.820225983f, 0.820280822f, 0.820335655f, + 0.820390479f, 0.820445297f, 0.820500106f, 0.820554909f, 0.820609703f, + 0.820664490f, 0.820719270f, 0.820774042f, 0.820828806f, 0.820883563f, + 0.820938312f, 0.820993054f, 0.821047788f, 0.821102515f, 0.821157234f, + 0.821211946f, 0.821266650f, 0.821321346f, 0.821376035f, 0.821430717f, + 0.821485390f, 0.821540057f, 0.821594716f, 0.821649367f, 0.821704010f, + 0.821758646f, 0.821813275f, 0.821867896f, 0.821922509f, 0.821977115f, + 0.822031714f, 0.822086304f, 0.822140888f, 0.822195463f, 0.822250031f, + 0.822304592f, 0.822359145f, 0.822413690f, 0.822468228f, 0.822522758f, + 0.822577281f, 0.822631796f, 0.822686304f, 0.822740804f, 0.822795296f, + 0.822849781f, 0.822904259f, 0.822958729f, 0.823013191f, 0.823067645f, + 0.823122093f, 0.823176532f, 0.823230964f, 0.823285388f, 0.823339805f, + 0.823394215f, 0.823448616f, 0.823503010f, 0.823557397f, 0.823611776f, + 0.823666147f, 0.823720511f, 0.823774868f, 0.823829216f, 0.823883557f, + 0.823937891f, 0.823992217f, 0.824046535f, 0.824100846f, 0.824155149f, + 0.824209445f, 0.824263733f, 0.824318014f, 0.824372287f, 0.824426552f, + 0.824480810f, 0.824535060f, 0.824589303f, 0.824643538f, 0.824697765f, + 0.824751985f, 0.824806198f, 0.824860402f, 0.824914599f, 0.824968789f, + 0.825022971f, 0.825077145f, 0.825131312f, 0.825185472f, 0.825239623f, + 0.825293767f, 0.825347904f, 0.825402033f, 0.825456154f, 0.825510268f, + 0.825564374f, 0.825618472f, 0.825672563f, 0.825726647f, 0.825780723f, + 0.825834791f, 0.825888851f, 0.825942904f, 0.825996950f, 0.826050988f, + 0.826105018f, 0.826159040f, 0.826213056f, 0.826267063f, 0.826321063f, + 0.826375055f, 0.826429040f, 0.826483017f, 0.826536986f, 0.826590948f, + 0.826644902f, 0.826698849f, 0.826752788f, 0.826806720f, 0.826860644f, + 0.826914560f, 0.826968469f, 0.827022370f, 0.827076263f, 0.827130149f, + 0.827184027f, 0.827237898f, 0.827291761f, 0.827345616f, 0.827399464f, + 0.827453305f, 0.827507137f, 0.827560962f, 0.827614780f, 0.827668590f, + 0.827722392f, 0.827776186f, 0.827829973f, 0.827883753f, 0.827937525f, + 0.827991289f, 0.828045045f, 0.828098794f, 0.828152536f, 0.828206269f, + 0.828259995f, 0.828313714f, 0.828367425f, 0.828421128f, 0.828474824f, + 0.828528512f, 0.828582192f, 0.828635865f, 0.828689530f, 0.828743188f, + 0.828796838f, 0.828850480f, 0.828904115f, 0.828957742f, 0.829011361f, + 0.829064973f, 0.829118577f, 0.829172174f, 0.829225763f, 0.829279344f, + 0.829332918f, 0.829386484f, 0.829440043f, 0.829493594f, 0.829547137f, + 0.829600673f, 0.829654201f, 0.829707721f, 0.829761234f, 0.829814739f, + 0.829868236f, 0.829921726f, 0.829975209f, 0.830028683f, 0.830082150f, + 0.830135610f, 0.830189061f, 0.830242505f, 0.830295942f, 0.830349371f, + 0.830402792f, 0.830456205f, 0.830509611f, 0.830563010f, 0.830616400f, + 0.830669783f, 0.830723159f, 0.830776526f, 0.830829887f, 0.830883239f, + 0.830936584f, 0.830989921f, 0.831043251f, 0.831096573f, 0.831149887f, + 0.831203194f, 0.831256493f, 0.831309784f, 0.831363068f, 0.831416344f, + 0.831469612f, 0.831522873f, 0.831576126f, 0.831629372f, 0.831682610f, + 0.831735840f, 0.831789062f, 0.831842277f, 0.831895485f, 0.831948684f, + 0.832001876f, 0.832055061f, 0.832108237f, 0.832161406f, 0.832214568f, + 0.832267722f, 0.832320868f, 0.832374006f, 0.832427137f, 0.832480260f, + 0.832533376f, 0.832586484f, 0.832639584f, 0.832692676f, 0.832745761f, + 0.832798838f, 0.832851908f, 0.832904970f, 0.832958024f, 0.833011071f, + 0.833064110f, 0.833117141f, 0.833170165f, 0.833223181f, 0.833276189f, + 0.833329190f, 0.833382183f, 0.833435168f, 0.833488146f, 0.833541116f, + 0.833594078f, 0.833647033f, 0.833699980f, 0.833752919f, 0.833805851f, + 0.833858775f, 0.833911691f, 0.833964600f, 0.834017501f, 0.834070394f, + 0.834123280f, 0.834176158f, 0.834229029f, 0.834281891f, 0.834334746f, + 0.834387594f, 0.834440433f, 0.834493266f, 0.834546090f, 0.834598907f, + 0.834651716f, 0.834704517f, 0.834757311f, 0.834810097f, 0.834862875f, + 0.834915646f, 0.834968409f, 0.835021164f, 0.835073912f, 0.835126652f, + 0.835179384f, 0.835232108f, 0.835284825f, 0.835337535f, 0.835390236f, + 0.835442930f, 0.835495616f, 0.835548295f, 0.835600966f, 0.835653629f, + 0.835706284f, 0.835758932f, 0.835811572f, 0.835864205f, 0.835916830f, + 0.835969447f, 0.836022056f, 0.836074658f, 0.836127252f, 0.836179838f, + 0.836232417f, 0.836284988f, 0.836337551f, 0.836390107f, 0.836442654f, + 0.836495195f, 0.836547727f, 0.836600252f, 0.836652769f, 0.836705279f, + 0.836757780f, 0.836810275f, 0.836862761f, 0.836915240f, 0.836967711f, + 0.837020174f, 0.837072630f, 0.837125077f, 0.837177518f, 0.837229950f, + 0.837282375f, 0.837334792f, 0.837387202f, 0.837439603f, 0.837491997f, + 0.837544384f, 0.837596762f, 0.837649133f, 0.837701497f, 0.837753852f, + 0.837806200f, 0.837858540f, 0.837910873f, 0.837963197f, 0.838015514f, + 0.838067824f, 0.838120125f, 0.838172419f, 0.838224706f, 0.838276984f, + 0.838329255f, 0.838381518f, 0.838433773f, 0.838486021f, 0.838538261f, + 0.838590493f, 0.838642718f, 0.838694935f, 0.838747144f, 0.838799345f, + 0.838851539f, 0.838903725f, 0.838955904f, 0.839008074f, 0.839060237f, + 0.839112392f, 0.839164540f, 0.839216679f, 0.839268812f, 0.839320936f, + 0.839373052f, 0.839425161f, 0.839477263f, 0.839529356f, 0.839581442f, + 0.839633520f, 0.839685590f, 0.839737653f, 0.839789708f, 0.839841755f, + 0.839893794f, 0.839945826f, 0.839997850f, 0.840049866f, 0.840101875f, + 0.840153876f, 0.840205869f, 0.840257854f, 0.840309832f, 0.840361802f, + 0.840413764f, 0.840465718f, 0.840517665f, 0.840569604f, 0.840621536f, + 0.840673459f, 0.840725375f, 0.840777283f, 0.840829184f, 0.840881076f, + 0.840932961f, 0.840984838f, 0.841036708f, 0.841088570f, 0.841140424f, + 0.841192270f, 0.841244108f, 0.841295939f, 0.841347762f, 0.841399578f, + 0.841451385f, 0.841503185f, 0.841554977f, 0.841606762f, 0.841658539f, + 0.841710307f, 0.841762069f, 0.841813822f, 0.841865568f, 0.841917306f, + 0.841969036f, 0.842020759f, 0.842072474f, 0.842124181f, 0.842175880f, + 0.842227571f, 0.842279255f, 0.842330931f, 0.842382600f, 0.842434260f, + 0.842485913f, 0.842537558f, 0.842589196f, 0.842640825f, 0.842692447f, + 0.842744061f, 0.842795668f, 0.842847266f, 0.842898857f, 0.842950440f, + 0.843002016f, 0.843053583f, 0.843105143f, 0.843156695f, 0.843208240f, + 0.843259776f, 0.843311305f, 0.843362826f, 0.843414340f, 0.843465845f, + 0.843517343f, 0.843568833f, 0.843620316f, 0.843671790f, 0.843723257f, + 0.843774716f, 0.843826168f, 0.843877611f, 0.843929047f, 0.843980475f, + 0.844031895f, 0.844083308f, 0.844134713f, 0.844186110f, 0.844237499f, + 0.844288881f, 0.844340254f, 0.844391621f, 0.844442979f, 0.844494329f, + 0.844545672f, 0.844597007f, 0.844648334f, 0.844699654f, 0.844750965f, + 0.844802269f, 0.844853565f, 0.844904854f, 0.844956134f, 0.845007407f, + 0.845058672f, 0.845109929f, 0.845161179f, 0.845212421f, 0.845263655f, + 0.845314881f, 0.845366099f, 0.845417310f, 0.845468513f, 0.845519708f, + 0.845570896f, 0.845622075f, 0.845673247f, 0.845724411f, 0.845775567f, + 0.845826716f, 0.845877857f, 0.845928990f, 0.845980115f, 0.846031232f, + 0.846082342f, 0.846133444f, 0.846184538f, 0.846235624f, 0.846286702f, + 0.846337773f, 0.846388836f, 0.846439891f, 0.846490939f, 0.846541978f, + 0.846593010f, 0.846644034f, 0.846695051f, 0.846746059f, 0.846797060f, + 0.846848053f, 0.846899038f, 0.846950015f, 0.847000985f, 0.847051947f, + 0.847102901f, 0.847153847f, 0.847204785f, 0.847255716f, 0.847306639f, + 0.847357554f, 0.847408461f, 0.847459361f, 0.847510252f, 0.847561136f, + 0.847612012f, 0.847662881f, 0.847713741f, 0.847764594f, 0.847815439f, + 0.847866276f, 0.847917105f, 0.847967927f, 0.848018741f, 0.848069547f, + 0.848120345f, 0.848171135f, 0.848221918f, 0.848272693f, 0.848323460f, + 0.848374219f, 0.848424970f, 0.848475714f, 0.848526450f, 0.848577178f, + 0.848627898f, 0.848678610f, 0.848729315f, 0.848780012f, 0.848830701f, + 0.848881382f, 0.848932055f, 0.848982721f, 0.849033379f, 0.849084029f, + 0.849134671f, 0.849185305f, 0.849235932f, 0.849286550f, 0.849337161f, + 0.849387765f, 0.849438360f, 0.849488947f, 0.849539527f, 0.849590099f, + 0.849640663f, 0.849691220f, 0.849741768f, 0.849792309f, 0.849842842f, + 0.849893367f, 0.849943884f, 0.849994393f, 0.850044895f, 0.850095389f, + 0.850145875f, 0.850196353f, 0.850246823f, 0.850297286f, 0.850347741f, + 0.850398187f, 0.850448627f, 0.850499058f, 0.850549481f, 0.850599897f, + 0.850650305f, 0.850700705f, 0.850751097f, 0.850801481f, 0.850851858f, + 0.850902227f, 0.850952587f, 0.851002941f, 0.851053286f, 0.851103623f, + 0.851153953f, 0.851204275f, 0.851254589f, 0.851304895f, 0.851355193f, + 0.851405484f, 0.851455766f, 0.851506041f, 0.851556308f, 0.851606567f, + 0.851656819f, 0.851707062f, 0.851757298f, 0.851807526f, 0.851857746f, + 0.851907958f, 0.851958162f, 0.852008359f, 0.852058548f, 0.852108729f, + 0.852158902f, 0.852209067f, 0.852259224f, 0.852309374f, 0.852359516f, + 0.852409649f, 0.852459775f, 0.852509894f, 0.852560004f, 0.852610107f, + 0.852660201f, 0.852710288f, 0.852760367f, 0.852810438f, 0.852860502f, + 0.852910557f, 0.852960605f, 0.853010645f, 0.853060677f, 0.853110701f, + 0.853160717f, 0.853210726f, 0.853260726f, 0.853310719f, 0.853360704f, + 0.853410681f, 0.853460650f, 0.853510612f, 0.853560565f, 0.853610511f, + 0.853660449f, 0.853710379f, 0.853760301f, 0.853810215f, 0.853860122f, + 0.853910021f, 0.853959911f, 0.854009794f, 0.854059669f, 0.854109537f, + 0.854159396f, 0.854209248f, 0.854259091f, 0.854308927f, 0.854358755f, + 0.854408575f, 0.854458387f, 0.854508192f, 0.854557988f, 0.854607777f, + 0.854657558f, 0.854707331f, 0.854757096f, 0.854806853f, 0.854856603f, + 0.854906344f, 0.854956078f, 0.855005804f, 0.855055522f, 0.855105232f, + 0.855154934f, 0.855204629f, 0.855254315f, 0.855303994f, 0.855353665f, + 0.855403328f, 0.855452983f, 0.855502630f, 0.855552269f, 0.855601901f, + 0.855651525f, 0.855701140f, 0.855750748f, 0.855800348f, 0.855849940f, + 0.855899525f, 0.855949101f, 0.855998670f, 0.856048231f, 0.856097783f, + 0.856147328f, 0.856196865f, 0.856246395f, 0.856295916f, 0.856345430f, + 0.856394935f, 0.856444433f, 0.856493923f, 0.856543405f, 0.856592879f, + 0.856642345f, 0.856691804f, 0.856741254f, 0.856790697f, 0.856840132f, + 0.856889558f, 0.856938977f, 0.856988389f, 0.857037792f, 0.857087187f, + 0.857136575f, 0.857185954f, 0.857235326f, 0.857284690f, 0.857334046f, + 0.857383394f, 0.857432734f, 0.857482067f, 0.857531391f, 0.857580708f, + 0.857630016f, 0.857679317f, 0.857728610f, 0.857777895f, 0.857827172f, + 0.857876441f, 0.857925703f, 0.857974956f, 0.858024202f, 0.858073440f, + 0.858122670f, 0.858171891f, 0.858221106f, 0.858270312f, 0.858319510f, + 0.858368700f, 0.858417883f, 0.858467058f, 0.858516224f, 0.858565383f, + 0.858614534f, 0.858663677f, 0.858712812f, 0.858761940f, 0.858811059f, + 0.858860170f, 0.858909274f, 0.858958370f, 0.859007457f, 0.859056537f, + 0.859105609f, 0.859154673f, 0.859203730f, 0.859252778f, 0.859301818f, + 0.859350851f, 0.859399875f, 0.859448892f, 0.859497901f, 0.859546902f, + 0.859595895f, 0.859644880f, 0.859693857f, 0.859742827f, 0.859791788f, + 0.859840741f, 0.859889687f, 0.859938625f, 0.859987555f, 0.860036476f, + 0.860085390f, 0.860134297f, 0.860183195f, 0.860232085f, 0.860280967f, + 0.860329842f, 0.860378708f, 0.860427567f, 0.860476418f, 0.860525260f, + 0.860574095f, 0.860622922f, 0.860671741f, 0.860720553f, 0.860769356f, + 0.860818151f, 0.860866939f, 0.860915718f, 0.860964490f, 0.861013253f, + 0.861062009f, 0.861110757f, 0.861159497f, 0.861208229f, 0.861256953f, + 0.861305669f, 0.861354378f, 0.861403078f, 0.861451771f, 0.861500455f, + 0.861549132f, 0.861597800f, 0.861646461f, 0.861695114f, 0.861743759f, + 0.861792396f, 0.861841025f, 0.861889646f, 0.861938259f, 0.861986865f, + 0.862035462f, 0.862084052f, 0.862132633f, 0.862181207f, 0.862229773f, + 0.862278330f, 0.862326880f, 0.862375422f, 0.862423956f, 0.862472482f, + 0.862521000f, 0.862569511f, 0.862618013f, 0.862666507f, 0.862714994f, + 0.862763472f, 0.862811943f, 0.862860405f, 0.862908860f, 0.862957307f, + 0.863005746f, 0.863054177f, 0.863102600f, 0.863151015f, 0.863199422f, + 0.863247821f, 0.863296212f, 0.863344595f, 0.863392971f, 0.863441338f, + 0.863489698f, 0.863538049f, 0.863586393f, 0.863634729f, 0.863683056f, + 0.863731376f, 0.863779688f, 0.863827992f, 0.863876288f, 0.863924576f, + 0.863972856f, 0.864021128f, 0.864069393f, 0.864117649f, 0.864165897f, + 0.864214138f, 0.864262370f, 0.864310594f, 0.864358811f, 0.864407020f, + 0.864455220f, 0.864503413f, 0.864551598f, 0.864599775f, 0.864647944f, + 0.864696105f, 0.864744258f, 0.864792403f, 0.864840540f, 0.864888669f, + 0.864936790f, 0.864984903f, 0.865033009f, 0.865081106f, 0.865129195f, + 0.865177277f, 0.865225350f, 0.865273416f, 0.865321473f, 0.865369523f, + 0.865417565f, 0.865465598f, 0.865513624f, 0.865561642f, 0.865609652f, + 0.865657654f, 0.865705648f, 0.865753634f, 0.865801612f, 0.865849582f, + 0.865897544f, 0.865945498f, 0.865993444f, 0.866041382f, 0.866089313f, + 0.866137235f, 0.866185149f, 0.866233056f, 0.866280954f, 0.866328844f, + 0.866376727f, 0.866424602f, 0.866472468f, 0.866520327f, 0.866568177f, + 0.866616020f, 0.866663855f, 0.866711681f, 0.866759500f, 0.866807311f, + 0.866855114f, 0.866902909f, 0.866950696f, 0.866998475f, 0.867046246f, + 0.867094009f, 0.867141764f, 0.867189511f, 0.867237250f, 0.867284981f, + 0.867332704f, 0.867380419f, 0.867428126f, 0.867475826f, 0.867523517f, + 0.867571200f, 0.867618875f, 0.867666543f, 0.867714202f, 0.867761853f, + 0.867809497f, 0.867857132f, 0.867904760f, 0.867952379f, 0.867999991f, + 0.868047594f, 0.868095190f, 0.868142777f, 0.868190357f, 0.868237928f, + 0.868285492f, 0.868333048f, 0.868380595f, 0.868428135f, 0.868475667f, + 0.868523190f, 0.868570706f, 0.868618214f, 0.868665713f, 0.868713205f, + 0.868760689f, 0.868808165f, 0.868855633f, 0.868903092f, 0.868950544f, + 0.868997988f, 0.869045424f, 0.869092852f, 0.869140272f, 0.869187684f, + 0.869235088f, 0.869282483f, 0.869329871f, 0.869377251f, 0.869424623f, + 0.869471987f, 0.869519343f, 0.869566691f, 0.869614031f, 0.869661363f, + 0.869708687f, 0.869756003f, 0.869803311f, 0.869850611f, 0.869897903f, + 0.869945187f, 0.869992463f, 0.870039731f, 0.870086991f, 0.870134243f, + 0.870181487f, 0.870228723f, 0.870275951f, 0.870323171f, 0.870370383f, + 0.870417587f, 0.870464783f, 0.870511971f, 0.870559151f, 0.870606323f, + 0.870653487f, 0.870700643f, 0.870747791f, 0.870794931f, 0.870842063f, + 0.870889187f, 0.870936303f, 0.870983411f, 0.871030511f, 0.871077603f, + 0.871124687f, 0.871171763f, 0.871218831f, 0.871265891f, 0.871312943f, + 0.871359987f, 0.871407023f, 0.871454051f, 0.871501071f, 0.871548083f, + 0.871595087f, 0.871642083f, 0.871689070f, 0.871736050f, 0.871783022f, + 0.871829986f, 0.871876942f, 0.871923889f, 0.871970829f, 0.872017761f, + 0.872064685f, 0.872111600f, 0.872158508f, 0.872205408f, 0.872252300f, + 0.872299183f, 0.872346059f, 0.872392927f, 0.872439786f, 0.872486638f, + 0.872533481f, 0.872580317f, 0.872627144f, 0.872673964f, 0.872720775f, + 0.872767579f, 0.872814374f, 0.872861162f, 0.872907941f, 0.872954712f, + 0.873001476f, 0.873048231f, 0.873094978f, 0.873141718f, 0.873188449f, + 0.873235172f, 0.873281887f, 0.873328595f, 0.873375294f, 0.873421985f, + 0.873468668f, 0.873515343f, 0.873562010f, 0.873608669f, 0.873655320f, + 0.873701963f, 0.873748598f, 0.873795225f, 0.873841843f, 0.873888454f, + 0.873935057f, 0.873981652f, 0.874028239f, 0.874074817f, 0.874121388f, + 0.874167950f, 0.874214505f, 0.874261052f, 0.874307590f, 0.874354121f, + 0.874400643f, 0.874447157f, 0.874493664f, 0.874540162f, 0.874586652f, + 0.874633135f, 0.874679609f, 0.874726075f, 0.874772533f, 0.874818983f, + 0.874865425f, 0.874911859f, 0.874958285f, 0.875004703f, 0.875051113f, + 0.875097515f, 0.875143908f, 0.875190294f, 0.875236672f, 0.875283042f, + 0.875329403f, 0.875375757f, 0.875422102f, 0.875468440f, 0.875514769f, + 0.875561090f, 0.875607404f, 0.875653709f, 0.875700006f, 0.875746295f, + 0.875792577f, 0.875838850f, 0.875885115f, 0.875931372f, 0.875977621f, + 0.876023861f, 0.876070094f, 0.876116319f, 0.876162536f, 0.876208744f, + 0.876254945f, 0.876301137f, 0.876347322f, 0.876393498f, 0.876439667f, + 0.876485827f, 0.876531979f, 0.876578124f, 0.876624260f, 0.876670388f, + 0.876716508f, 0.876762620f, 0.876808724f, 0.876854820f, 0.876900907f, + 0.876946987f, 0.876993059f, 0.877039123f, 0.877085178f, 0.877131226f, + 0.877177265f, 0.877223296f, 0.877269320f, 0.877315335f, 0.877361342f, + 0.877407341f, 0.877453332f, 0.877499315f, 0.877545290f, 0.877591257f, + 0.877637216f, 0.877683167f, 0.877729109f, 0.877775044f, 0.877820970f, + 0.877866889f, 0.877912799f, 0.877958701f, 0.878004596f, 0.878050482f, + 0.878096360f, 0.878142230f, 0.878188092f, 0.878233946f, 0.878279792f, + 0.878325629f, 0.878371459f, 0.878417281f, 0.878463094f, 0.878508900f, + 0.878554697f, 0.878600486f, 0.878646267f, 0.878692041f, 0.878737806f, + 0.878783563f, 0.878829312f, 0.878875052f, 0.878920785f, 0.878966510f, + 0.879012226f, 0.879057935f, 0.879103635f, 0.879149328f, 0.879195012f, + 0.879240688f, 0.879286356f, 0.879332016f, 0.879377668f, 0.879423312f, + 0.879468948f, 0.879514576f, 0.879560195f, 0.879605807f, 0.879651410f, + 0.879697006f, 0.879742593f, 0.879788172f, 0.879833743f, 0.879879306f, + 0.879924861f, 0.879970408f, 0.880015947f, 0.880061477f, 0.880107000f, + 0.880152514f, 0.880198021f, 0.880243519f, 0.880289009f, 0.880334491f, + 0.880379965f, 0.880425431f, 0.880470889f, 0.880516339f, 0.880561780f, + 0.880607214f, 0.880652639f, 0.880698057f, 0.880743466f, 0.880788867f, + 0.880834260f, 0.880879645f, 0.880925022f, 0.880970391f, 0.881015752f, + 0.881061104f, 0.881106449f, 0.881151785f, 0.881197113f, 0.881242434f, + 0.881287746f, 0.881333050f, 0.881378346f, 0.881423633f, 0.881468913f, + 0.881514185f, 0.881559448f, 0.881604704f, 0.881649951f, 0.881695190f, + 0.881740421f, 0.881785644f, 0.881830859f, 0.881876066f, 0.881921264f, + 0.881966455f, 0.882011637f, 0.882056812f, 0.882101978f, 0.882147136f, + 0.882192286f, 0.882237428f, 0.882282562f, 0.882327687f, 0.882372805f, + 0.882417914f, 0.882463016f, 0.882508109f, 0.882553194f, 0.882598271f, + 0.882643340f, 0.882688401f, 0.882733453f, 0.882778498f, 0.882823534f, + 0.882868563f, 0.882913583f, 0.882958595f, 0.883003599f, 0.883048595f, + 0.883093583f, 0.883138562f, 0.883183534f, 0.883228497f, 0.883273452f, + 0.883318400f, 0.883363339f, 0.883408270f, 0.883453192f, 0.883498107f, + 0.883543014f, 0.883587912f, 0.883632802f, 0.883677685f, 0.883722559f, + 0.883767425f, 0.883812282f, 0.883857132f, 0.883901974f, 0.883946807f, + 0.883991632f, 0.884036450f, 0.884081259f, 0.884126060f, 0.884170852f, + 0.884215637f, 0.884260414f, 0.884305182f, 0.884349942f, 0.884394695f, + 0.884439439f, 0.884484175f, 0.884528902f, 0.884573622f, 0.884618334f, + 0.884663037f, 0.884707732f, 0.884752419f, 0.884797098f, 0.884841769f, + 0.884886432f, 0.884931087f, 0.884975733f, 0.885020371f, 0.885065002f, + 0.885109624f, 0.885154238f, 0.885198843f, 0.885243441f, 0.885288031f, + 0.885332612f, 0.885377185f, 0.885421750f, 0.885466307f, 0.885510856f, + 0.885555397f, 0.885599929f, 0.885644454f, 0.885688970f, 0.885733478f, + 0.885777978f, 0.885822470f, 0.885866954f, 0.885911429f, 0.885955897f, + 0.886000356f, 0.886044807f, 0.886089250f, 0.886133685f, 0.886178112f, + 0.886222530f, 0.886266941f, 0.886311343f, 0.886355737f, 0.886400123f, + 0.886444501f, 0.886488870f, 0.886533232f, 0.886577585f, 0.886621930f, + 0.886666268f, 0.886710596f, 0.886754917f, 0.886799230f, 0.886843534f, + 0.886887831f, 0.886932119f, 0.886976399f, 0.887020671f, 0.887064934f, + 0.887109190f, 0.887153437f, 0.887197677f, 0.887241908f, 0.887286131f, + 0.887330345f, 0.887374552f, 0.887418750f, 0.887462941f, 0.887507123f, + 0.887551297f, 0.887595463f, 0.887639620f, 0.887683770f, 0.887727911f, + 0.887772044f, 0.887816170f, 0.887860286f, 0.887904395f, 0.887948496f, + 0.887992588f, 0.888036672f, 0.888080748f, 0.888124816f, 0.888168876f, + 0.888212928f, 0.888256971f, 0.888301006f, 0.888345033f, 0.888389052f, + 0.888433063f, 0.888477066f, 0.888521060f, 0.888565046f, 0.888609024f, + 0.888652994f, 0.888696956f, 0.888740910f, 0.888784855f, 0.888828792f, + 0.888872721f, 0.888916642f, 0.888960555f, 0.889004459f, 0.889048356f, + 0.889092244f, 0.889136124f, 0.889179996f, 0.889223860f, 0.889267715f, + 0.889311563f, 0.889355402f, 0.889399233f, 0.889443056f, 0.889486870f, + 0.889530677f, 0.889574475f, 0.889618265f, 0.889662047f, 0.889705821f, + 0.889749586f, 0.889793344f, 0.889837093f, 0.889880834f, 0.889924567f, + 0.889968292f, 0.890012008f, 0.890055716f, 0.890099417f, 0.890143109f, + 0.890186792f, 0.890230468f, 0.890274135f, 0.890317795f, 0.890361446f, + 0.890405089f, 0.890448723f, 0.890492350f, 0.890535968f, 0.890579578f, + 0.890623180f, 0.890666774f, 0.890710359f, 0.890753937f, 0.890797506f, + 0.890841067f, 0.890884620f, 0.890928164f, 0.890971701f, 0.891015229f, + 0.891058749f, 0.891102261f, 0.891145765f, 0.891189260f, 0.891232748f, + 0.891276227f, 0.891319698f, 0.891363160f, 0.891406615f, 0.891450061f, + 0.891493499f, 0.891536929f, 0.891580351f, 0.891623765f, 0.891667170f, + 0.891710567f, 0.891753956f, 0.891797337f, 0.891840709f, 0.891884074f, + 0.891927430f, 0.891970778f, 0.892014118f, 0.892057449f, 0.892100773f, + 0.892144088f, 0.892187395f, 0.892230694f, 0.892273984f, 0.892317267f, + 0.892360541f, 0.892403807f, 0.892447064f, 0.892490314f, 0.892533555f, + 0.892576789f, 0.892620014f, 0.892663230f, 0.892706439f, 0.892749639f, + 0.892792831f, 0.892836015f, 0.892879191f, 0.892922358f, 0.892965518f, + 0.893008669f, 0.893051812f, 0.893094946f, 0.893138073f, 0.893181191f, + 0.893224301f, 0.893267403f, 0.893310497f, 0.893353582f, 0.893396659f, + 0.893439728f, 0.893482789f, 0.893525842f, 0.893568886f, 0.893611922f, + 0.893654950f, 0.893697970f, 0.893740981f, 0.893783985f, 0.893826980f, + 0.893869967f, 0.893912945f, 0.893955916f, 0.893998878f, 0.894041832f, + 0.894084778f, 0.894127715f, 0.894170644f, 0.894213566f, 0.894256478f, + 0.894299383f, 0.894342280f, 0.894385168f, 0.894428048f, 0.894470920f, + 0.894513783f, 0.894556639f, 0.894599486f, 0.894642325f, 0.894685155f, + 0.894727978f, 0.894770792f, 0.894813598f, 0.894856396f, 0.894899185f, + 0.894941967f, 0.894984740f, 0.895027505f, 0.895070261f, 0.895113010f, + 0.895155750f, 0.895198482f, 0.895241206f, 0.895283921f, 0.895326628f, + 0.895369327f, 0.895412018f, 0.895454701f, 0.895497375f, 0.895540041f, + 0.895582699f, 0.895625349f, 0.895667990f, 0.895710623f, 0.895753248f, + 0.895795865f, 0.895838474f, 0.895881074f, 0.895923666f, 0.895966250f, + 0.896008825f, 0.896051393f, 0.896093952f, 0.896136503f, 0.896179045f, + 0.896221580f, 0.896264106f, 0.896306624f, 0.896349133f, 0.896391635f, + 0.896434128f, 0.896476613f, 0.896519090f, 0.896561558f, 0.896604018f, + 0.896646470f, 0.896688914f, 0.896731349f, 0.896773777f, 0.896816196f, + 0.896858606f, 0.896901009f, 0.896943403f, 0.896985789f, 0.897028167f, + 0.897070537f, 0.897112898f, 0.897155251f, 0.897197596f, 0.897239932f, + 0.897282261f, 0.897324581f, 0.897366893f, 0.897409196f, 0.897451491f, + 0.897493778f, 0.897536057f, 0.897578328f, 0.897620590f, 0.897662844f, + 0.897705090f, 0.897747328f, 0.897789557f, 0.897831778f, 0.897873991f, + 0.897916195f, 0.897958392f, 0.898000580f, 0.898042760f, 0.898084931f, + 0.898127094f, 0.898169249f, 0.898211396f, 0.898253535f, 0.898295665f, + 0.898337787f, 0.898379901f, 0.898422006f, 0.898464103f, 0.898506192f, + 0.898548273f, 0.898590346f, 0.898632410f, 0.898674466f, 0.898716513f, + 0.898758553f, 0.898800584f, 0.898842607f, 0.898884621f, 0.898926628f, + 0.898968626f, 0.899010616f, 0.899052597f, 0.899094571f, 0.899136536f, + 0.899178492f, 0.899220441f, 0.899262381f, 0.899304313f, 0.899346237f, + 0.899388152f, 0.899430060f, 0.899471959f, 0.899513849f, 0.899555732f, + 0.899597606f, 0.899639472f, 0.899681329f, 0.899723178f, 0.899765019f, + 0.899806852f, 0.899848677f, 0.899890493f, 0.899932301f, 0.899974101f, + 0.900015892f, 0.900057675f, 0.900099450f, 0.900141217f, 0.900182975f, + 0.900224725f, 0.900266467f, 0.900308200f, 0.900349925f, 0.900391642f, + 0.900433351f, 0.900475051f, 0.900516744f, 0.900558427f, 0.900600103f, + 0.900641770f, 0.900683429f, 0.900725080f, 0.900766722f, 0.900808357f, + 0.900849982f, 0.900891600f, 0.900933209f, 0.900974810f, 0.901016403f, + 0.901057988f, 0.901099564f, 0.901141132f, 0.901182691f, 0.901224243f, + 0.901265786f, 0.901307321f, 0.901348847f, 0.901390365f, 0.901431875f, + 0.901473377f, 0.901514870f, 0.901556355f, 0.901597832f, 0.901639300f, + 0.901680761f, 0.901722213f, 0.901763656f, 0.901805092f, 0.901846519f, + 0.901887937f, 0.901929348f, 0.901970750f, 0.902012144f, 0.902053529f, + 0.902094907f, 0.902136276f, 0.902177637f, 0.902218989f, 0.902260333f, + 0.902301669f, 0.902342996f, 0.902384316f, 0.902425627f, 0.902466929f, + 0.902508224f, 0.902549510f, 0.902590788f, 0.902632057f, 0.902673318f, + 0.902714571f, 0.902755816f, 0.902797052f, 0.902838280f, 0.902879500f, + 0.902920711f, 0.902961914f, 0.903003109f, 0.903044295f, 0.903085474f, + 0.903126644f, 0.903167805f, 0.903208958f, 0.903250103f, 0.903291240f, + 0.903332368f, 0.903373489f, 0.903414600f, 0.903455704f, 0.903496799f, + 0.903537886f, 0.903578964f, 0.903620035f, 0.903661097f, 0.903702150f, + 0.903743196f, 0.903784233f, 0.903825261f, 0.903866282f, 0.903907294f, + 0.903948298f, 0.903989293f, 0.904030280f, 0.904071259f, 0.904112230f, + 0.904153192f, 0.904194146f, 0.904235092f, 0.904276029f, 0.904316958f, + 0.904357879f, 0.904398791f, 0.904439695f, 0.904480591f, 0.904521478f, + 0.904562357f, 0.904603228f, 0.904644091f, 0.904684945f, 0.904725791f, + 0.904766628f, 0.904807457f, 0.904848278f, 0.904889091f, 0.904929895f, + 0.904970691f, 0.905011479f, 0.905052258f, 0.905093029f, 0.905133792f, + 0.905174546f, 0.905215292f, 0.905256030f, 0.905296759f, 0.905337480f, + 0.905378193f, 0.905418898f, 0.905459594f, 0.905500282f, 0.905540961f, + 0.905581632f, 0.905622295f, 0.905662949f, 0.905703596f, 0.905744233f, + 0.905784863f, 0.905825484f, 0.905866097f, 0.905906702f, 0.905947298f, + 0.905987886f, 0.906028465f, 0.906069036f, 0.906109599f, 0.906150154f, + 0.906190700f, 0.906231238f, 0.906271768f, 0.906312289f, 0.906352802f, + 0.906393307f, 0.906433803f, 0.906474291f, 0.906514770f, 0.906555242f, + 0.906595705f, 0.906636159f, 0.906676605f, 0.906717043f, 0.906757473f, + 0.906797894f, 0.906838307f, 0.906878712f, 0.906919108f, 0.906959496f, + 0.906999875f, 0.907040247f, 0.907080610f, 0.907120964f, 0.907161310f, + 0.907201648f, 0.907241978f, 0.907282299f, 0.907322612f, 0.907362917f, + 0.907403213f, 0.907443501f, 0.907483780f, 0.907524051f, 0.907564314f, + 0.907604569f, 0.907644815f, 0.907685053f, 0.907725282f, 0.907765503f, + 0.907805716f, 0.907845920f, 0.907886116f, 0.907926304f, 0.907966484f, + 0.908006655f, 0.908046817f, 0.908086972f, 0.908127118f, 0.908167255f, + 0.908207385f, 0.908247506f, 0.908287618f, 0.908327723f, 0.908367819f, + 0.908407906f, 0.908447985f, 0.908488056f, 0.908528119f, 0.908568173f, + 0.908608219f, 0.908648256f, 0.908688285f, 0.908728306f, 0.908768318f, + 0.908808323f, 0.908848318f, 0.908888306f, 0.908928285f, 0.908968255f, + 0.909008218f, 0.909048171f, 0.909088117f, 0.909128054f, 0.909167983f, + 0.909207904f, 0.909247816f, 0.909287720f, 0.909327615f, 0.909367502f, + 0.909407381f, 0.909447251f, 0.909487113f, 0.909526967f, 0.909566812f, + 0.909606649f, 0.909646477f, 0.909686298f, 0.909726110f, 0.909765913f, + 0.909805708f, 0.909845495f, 0.909885273f, 0.909925043f, 0.909964805f, + 0.910004558f, 0.910044303f, 0.910084040f, 0.910123768f, 0.910163488f, + 0.910203199f, 0.910242902f, 0.910282597f, 0.910322283f, 0.910361961f, + 0.910401631f, 0.910441292f, 0.910480945f, 0.910520590f, 0.910560226f, + 0.910599854f, 0.910639473f, 0.910679084f, 0.910718687f, 0.910758281f, + 0.910797867f, 0.910837445f, 0.910877014f, 0.910916575f, 0.910956127f, + 0.910995671f, 0.911035207f, 0.911074734f, 0.911114253f, 0.911153764f, + 0.911193266f, 0.911232760f, 0.911272245f, 0.911311722f, 0.911351191f, + 0.911390651f, 0.911430103f, 0.911469547f, 0.911508982f, 0.911548409f, + 0.911587827f, 0.911627237f, 0.911666639f, 0.911706032f, 0.911745417f, + 0.911784793f, 0.911824162f, 0.911863521f, 0.911902873f, 0.911942216f, + 0.911981550f, 0.912020877f, 0.912060194f, 0.912099504f, 0.912138805f, + 0.912178098f, 0.912217382f, 0.912256658f, 0.912295925f, 0.912335185f, + 0.912374435f, 0.912413678f, 0.912452912f, 0.912492137f, 0.912531355f, + 0.912570563f, 0.912609764f, 0.912648956f, 0.912688140f, 0.912727315f, + 0.912766482f, 0.912805640f, 0.912844790f, 0.912883932f, 0.912923065f, + 0.912962190f, 0.913001307f, 0.913040415f, 0.913079515f, 0.913118606f, + 0.913157689f, 0.913196764f, 0.913235830f, 0.913274888f, 0.913313937f, + 0.913352978f, 0.913392011f, 0.913431035f, 0.913470051f, 0.913509058f, + 0.913548057f, 0.913587048f, 0.913626030f, 0.913665004f, 0.913703969f, + 0.913742926f, 0.913781875f, 0.913820815f, 0.913859747f, 0.913898671f, + 0.913937586f, 0.913976492f, 0.914015391f, 0.914054280f, 0.914093162f, + 0.914132035f, 0.914170899f, 0.914209756f, 0.914248604f, 0.914287443f, + 0.914326274f, 0.914365097f, 0.914403911f, 0.914442717f, 0.914481514f, + 0.914520303f, 0.914559084f, 0.914597856f, 0.914636619f, 0.914675375f, + 0.914714122f, 0.914752860f, 0.914791591f, 0.914830312f, 0.914869026f, + 0.914907730f, 0.914946427f, 0.914985115f, 0.915023795f, 0.915062466f, + 0.915101129f, 0.915139783f, 0.915178429f, 0.915217067f, 0.915255696f, + 0.915294317f, 0.915332929f, 0.915371533f, 0.915410129f, 0.915448716f, + 0.915487295f, 0.915525865f, 0.915564427f, 0.915602981f, 0.915641526f, + 0.915680062f, 0.915718590f, 0.915757110f, 0.915795622f, 0.915834125f, + 0.915872619f, 0.915911105f, 0.915949583f, 0.915988052f, 0.916026513f, + 0.916064966f, 0.916103410f, 0.916141845f, 0.916180273f, 0.916218691f, + 0.916257102f, 0.916295504f, 0.916333897f, 0.916372282f, 0.916410659f, + 0.916449027f, 0.916487387f, 0.916525739f, 0.916564082f, 0.916602416f, + 0.916640742f, 0.916679060f, 0.916717369f, 0.916755670f, 0.916793962f, + 0.916832246f, 0.916870522f, 0.916908789f, 0.916947048f, 0.916985298f, + 0.917023540f, 0.917061773f, 0.917099998f, 0.917138215f, 0.917176423f, + 0.917214623f, 0.917252814f, 0.917290997f, 0.917329171f, 0.917367337f, + 0.917405495f, 0.917443644f, 0.917481785f, 0.917519917f, 0.917558041f, + 0.917596156f, 0.917634263f, 0.917672362f, 0.917710452f, 0.917748533f, + 0.917786607f, 0.917824671f, 0.917862728f, 0.917900776f, 0.917938815f, + 0.917976846f, 0.918014869f, 0.918052883f, 0.918090889f, 0.918128886f, + 0.918166875f, 0.918204855f, 0.918242827f, 0.918280791f, 0.918318746f, + 0.918356692f, 0.918394630f, 0.918432560f, 0.918470481f, 0.918508394f, + 0.918546299f, 0.918584195f, 0.918622082f, 0.918659961f, 0.918697832f, + 0.918735694f, 0.918773548f, 0.918811393f, 0.918849230f, 0.918887059f, + 0.918924879f, 0.918962690f, 0.919000493f, 0.919038288f, 0.919076074f, + 0.919113852f, 0.919151621f, 0.919189382f, 0.919227134f, 0.919264878f, + 0.919302614f, 0.919340341f, 0.919378059f, 0.919415769f, 0.919453471f, + 0.919491164f, 0.919528849f, 0.919566525f, 0.919604193f, 0.919641853f, + 0.919679504f, 0.919717146f, 0.919754780f, 0.919792406f, 0.919830023f, + 0.919867632f, 0.919905232f, 0.919942824f, 0.919980407f, 0.920017982f, + 0.920055549f, 0.920093107f, 0.920130656f, 0.920168197f, 0.920205730f, + 0.920243254f, 0.920280769f, 0.920318277f, 0.920355775f, 0.920393266f, + 0.920430748f, 0.920468221f, 0.920505686f, 0.920543142f, 0.920580590f, + 0.920618030f, 0.920655461f, 0.920692884f, 0.920730298f, 0.920767703f, + 0.920805101f, 0.920842489f, 0.920879870f, 0.920917242f, 0.920954605f, + 0.920991960f, 0.921029306f, 0.921066644f, 0.921103974f, 0.921141295f, + 0.921178607f, 0.921215911f, 0.921253207f, 0.921290494f, 0.921327773f, + 0.921365043f, 0.921402305f, 0.921439558f, 0.921476803f, 0.921514039f, + 0.921551267f, 0.921588487f, 0.921625698f, 0.921662900f, 0.921700094f, + 0.921737280f, 0.921774457f, 0.921811625f, 0.921848785f, 0.921885937f, + 0.921923080f, 0.921960215f, 0.921997341f, 0.922034459f, 0.922071568f, + 0.922108669f, 0.922145761f, 0.922182845f, 0.922219920f, 0.922256987f, + 0.922294046f, 0.922331095f, 0.922368137f, 0.922405170f, 0.922442194f, + 0.922479210f, 0.922516218f, 0.922553217f, 0.922590208f, 0.922627190f, + 0.922664163f, 0.922701128f, 0.922738085f, 0.922775033f, 0.922811973f, + 0.922848904f, 0.922885827f, 0.922922741f, 0.922959647f, 0.922996544f, + 0.923033433f, 0.923070313f, 0.923107185f, 0.923144048f, 0.923180903f, + 0.923217749f, 0.923254587f, 0.923291417f, 0.923328238f, 0.923365050f, + 0.923401854f, 0.923438649f, 0.923475436f, 0.923512215f, 0.923548985f, + 0.923585746f, 0.923622499f, 0.923659244f, 0.923695980f, 0.923732707f, + 0.923769426f, 0.923806137f, 0.923842839f, 0.923879533f, 0.923916218f, + 0.923952894f, 0.923989562f, 0.924026222f, 0.924062873f, 0.924099516f, + 0.924136150f, 0.924172775f, 0.924209392f, 0.924246001f, 0.924282601f, + 0.924319193f, 0.924355776f, 0.924392351f, 0.924428917f, 0.924465474f, + 0.924502023f, 0.924538564f, 0.924575096f, 0.924611620f, 0.924648135f, + 0.924684642f, 0.924721140f, 0.924757630f, 0.924794111f, 0.924830583f, + 0.924867048f, 0.924903503f, 0.924939950f, 0.924976389f, 0.925012819f, + 0.925049241f, 0.925085654f, 0.925122059f, 0.925158455f, 0.925194842f, + 0.925231221f, 0.925267592f, 0.925303954f, 0.925340308f, 0.925376653f, + 0.925412990f, 0.925449318f, 0.925485637f, 0.925521948f, 0.925558251f, + 0.925594545f, 0.925630831f, 0.925667108f, 0.925703376f, 0.925739636f, + 0.925775888f, 0.925812131f, 0.925848365f, 0.925884591f, 0.925920809f, + 0.925957018f, 0.925993218f, 0.926029410f, 0.926065594f, 0.926101768f, + 0.926137935f, 0.926174093f, 0.926210242f, 0.926246383f, 0.926282515f, + 0.926318639f, 0.926354755f, 0.926390861f, 0.926426960f, 0.926463049f, + 0.926499131f, 0.926535203f, 0.926571268f, 0.926607323f, 0.926643371f, + 0.926679409f, 0.926715440f, 0.926751461f, 0.926787474f, 0.926823479f, + 0.926859475f, 0.926895463f, 0.926931442f, 0.926967412f, 0.927003374f, + 0.927039328f, 0.927075273f, 0.927111209f, 0.927147137f, 0.927183056f, + 0.927218967f, 0.927254870f, 0.927290764f, 0.927326649f, 0.927362526f, + 0.927398394f, 0.927434254f, 0.927470105f, 0.927505948f, 0.927541782f, + 0.927577607f, 0.927613425f, 0.927649233f, 0.927685033f, 0.927720825f, + 0.927756608f, 0.927792382f, 0.927828148f, 0.927863906f, 0.927899654f, + 0.927935395f, 0.927971127f, 0.928006850f, 0.928042565f, 0.928078271f, + 0.928113969f, 0.928149658f, 0.928185339f, 0.928221011f, 0.928256674f, + 0.928292329f, 0.928327976f, 0.928363614f, 0.928399243f, 0.928434864f, + 0.928470477f, 0.928506080f, 0.928541676f, 0.928577263f, 0.928612841f, + 0.928648411f, 0.928683972f, 0.928719524f, 0.928755068f, 0.928790604f, + 0.928826131f, 0.928861650f, 0.928897160f, 0.928932661f, 0.928968154f, + 0.929003638f, 0.929039114f, 0.929074581f, 0.929110040f, 0.929145490f, + 0.929180932f, 0.929216365f, 0.929251789f, 0.929287205f, 0.929322613f, + 0.929358012f, 0.929393402f, 0.929428784f, 0.929464157f, 0.929499522f, + 0.929534878f, 0.929570226f, 0.929605565f, 0.929640896f, 0.929676218f, + 0.929711531f, 0.929746836f, 0.929782133f, 0.929817421f, 0.929852700f, + 0.929887971f, 0.929923233f, 0.929958487f, 0.929993732f, 0.930028968f, + 0.930064196f, 0.930099416f, 0.930134627f, 0.930169829f, 0.930205023f, + 0.930240208f, 0.930275385f, 0.930310553f, 0.930345713f, 0.930380864f, + 0.930416006f, 0.930451140f, 0.930486266f, 0.930521383f, 0.930556491f, + 0.930591591f, 0.930626682f, 0.930661764f, 0.930696839f, 0.930731904f, + 0.930766961f, 0.930802010f, 0.930837049f, 0.930872081f, 0.930907103f, + 0.930942118f, 0.930977123f, 0.931012120f, 0.931047109f, 0.931082089f, + 0.931117060f, 0.931152023f, 0.931186977f, 0.931221923f, 0.931256860f, + 0.931291789f, 0.931326709f, 0.931361621f, 0.931396524f, 0.931431418f, + 0.931466304f, 0.931501181f, 0.931536050f, 0.931570910f, 0.931605761f, + 0.931640604f, 0.931675439f, 0.931710265f, 0.931745082f, 0.931779891f, + 0.931814691f, 0.931849483f, 0.931884266f, 0.931919040f, 0.931953806f, + 0.931988563f, 0.932023312f, 0.932058052f, 0.932092784f, 0.932127507f, + 0.932162222f, 0.932196928f, 0.932231625f, 0.932266314f, 0.932300994f, + 0.932335666f, 0.932370329f, 0.932404983f, 0.932439629f, 0.932474267f, + 0.932508895f, 0.932543516f, 0.932578127f, 0.932612731f, 0.932647325f, + 0.932681911f, 0.932716488f, 0.932751057f, 0.932785617f, 0.932820169f, + 0.932854712f, 0.932889247f, 0.932923773f, 0.932958290f, 0.932992799f, + 0.933027299f, 0.933061791f, 0.933096274f, 0.933130748f, 0.933165214f, + 0.933199671f, 0.933234120f, 0.933268560f, 0.933302992f, 0.933337415f, + 0.933371829f, 0.933406235f, 0.933440633f, 0.933475021f, 0.933509401f, + 0.933543773f, 0.933578136f, 0.933612490f, 0.933646836f, 0.933681173f, + 0.933715502f, 0.933749822f, 0.933784133f, 0.933818436f, 0.933852731f, + 0.933887016f, 0.933921294f, 0.933955562f, 0.933989822f, 0.934024073f, + 0.934058316f, 0.934092550f, 0.934126776f, 0.934160993f, 0.934195202f, + 0.934229401f, 0.934263593f, 0.934297775f, 0.934331949f, 0.934366115f, + 0.934400272f, 0.934434420f, 0.934468560f, 0.934502691f, 0.934536814f, + 0.934570928f, 0.934605033f, 0.934639130f, 0.934673218f, 0.934707298f, + 0.934741369f, 0.934775431f, 0.934809485f, 0.934843530f, 0.934877567f, + 0.934911595f, 0.934945614f, 0.934979625f, 0.935013627f, 0.935047621f, + 0.935081606f, 0.935115583f, 0.935149551f, 0.935183510f, 0.935217461f, + 0.935251403f, 0.935285336f, 0.935319261f, 0.935353177f, 0.935387085f, + 0.935420984f, 0.935454875f, 0.935488757f, 0.935522630f, 0.935556495f, + 0.935590351f, 0.935624198f, 0.935658037f, 0.935691868f, 0.935725689f, + 0.935759503f, 0.935793307f, 0.935827103f, 0.935860890f, 0.935894669f, + 0.935928439f, 0.935962201f, 0.935995954f, 0.936029698f, 0.936063434f, + 0.936097161f, 0.936130879f, 0.936164589f, 0.936198290f, 0.936231983f, + 0.936265667f, 0.936299343f, 0.936333010f, 0.936366668f, 0.936400317f, + 0.936433958f, 0.936467591f, 0.936501215f, 0.936534830f, 0.936568437f, + 0.936602035f, 0.936635624f, 0.936669205f, 0.936702777f, 0.936736340f, + 0.936769895f, 0.936803442f, 0.936836979f, 0.936870509f, 0.936904029f, + 0.936937541f, 0.936971044f, 0.937004539f, 0.937038025f, 0.937071502f, + 0.937104971f, 0.937138432f, 0.937171883f, 0.937205326f, 0.937238760f, + 0.937272186f, 0.937305603f, 0.937339012f, 0.937372412f, 0.937405803f, + 0.937439186f, 0.937472560f, 0.937505925f, 0.937539282f, 0.937572630f, + 0.937605970f, 0.937639301f, 0.937672623f, 0.937705937f, 0.937739242f, + 0.937772539f, 0.937805827f, 0.937839106f, 0.937872376f, 0.937905638f, + 0.937938892f, 0.937972137f, 0.938005373f, 0.938038600f, 0.938071819f, + 0.938105030f, 0.938138231f, 0.938171424f, 0.938204609f, 0.938237784f, + 0.938270952f, 0.938304110f, 0.938337260f, 0.938370401f, 0.938403534f, + 0.938436658f, 0.938469774f, 0.938502880f, 0.938535978f, 0.938569068f, + 0.938602149f, 0.938635221f, 0.938668285f, 0.938701340f, 0.938734386f, + 0.938767424f, 0.938800453f, 0.938833474f, 0.938866486f, 0.938899489f, + 0.938932484f, 0.938965470f, 0.938998447f, 0.939031416f, 0.939064376f, + 0.939097327f, 0.939130270f, 0.939163204f, 0.939196130f, 0.939229047f, + 0.939261955f, 0.939294855f, 0.939327746f, 0.939360628f, 0.939393502f, + 0.939426367f, 0.939459224f, 0.939492071f, 0.939524911f, 0.939557741f, + 0.939590563f, 0.939623377f, 0.939656181f, 0.939688977f, 0.939721765f, + 0.939754543f, 0.939787314f, 0.939820075f, 0.939852828f, 0.939885572f, + 0.939918308f, 0.939951035f, 0.939983753f, 0.940016463f, 0.940049164f, + 0.940081856f, 0.940114540f, 0.940147215f, 0.940179881f, 0.940212539f, + 0.940245188f, 0.940277829f, 0.940310461f, 0.940343084f, 0.940375699f, + 0.940408305f, 0.940440902f, 0.940473491f, 0.940506071f, 0.940538642f, + 0.940571205f, 0.940603759f, 0.940636304f, 0.940668841f, 0.940701369f, + 0.940733889f, 0.940766400f, 0.940798902f, 0.940831395f, 0.940863880f, + 0.940896356f, 0.940928824f, 0.940961283f, 0.940993733f, 0.941026175f, + 0.941058608f, 0.941091032f, 0.941123448f, 0.941155855f, 0.941188254f, + 0.941220643f, 0.941253025f, 0.941285397f, 0.941317761f, 0.941350116f, + 0.941382462f, 0.941414800f, 0.941447130f, 0.941479450f, 0.941511762f, + 0.941544065f, 0.941576360f, 0.941608646f, 0.941640923f, 0.941673192f, + 0.941705452f, 0.941737703f, 0.941769946f, 0.941802179f, 0.941834405f, + 0.941866622f, 0.941898830f, 0.941931029f, 0.941963220f, 0.941995402f, + 0.942027575f, 0.942059740f, 0.942091896f, 0.942124043f, 0.942156182f, + 0.942188312f, 0.942220434f, 0.942252546f, 0.942284650f, 0.942316746f, + 0.942348833f, 0.942380911f, 0.942412980f, 0.942445041f, 0.942477093f, + 0.942509137f, 0.942541171f, 0.942573198f, 0.942605215f, 0.942637224f, + 0.942669224f, 0.942701216f, 0.942733198f, 0.942765173f, 0.942797138f, + 0.942829095f, 0.942861043f, 0.942892983f, 0.942924913f, 0.942956836f, + 0.942988749f, 0.943020654f, 0.943052550f, 0.943084437f, 0.943116316f, + 0.943148186f, 0.943180048f, 0.943211901f, 0.943243745f, 0.943275580f, + 0.943307407f, 0.943339225f, 0.943371035f, 0.943402836f, 0.943434628f, + 0.943466411f, 0.943498186f, 0.943529952f, 0.943561709f, 0.943593458f, + 0.943625198f, 0.943656930f, 0.943688652f, 0.943720366f, 0.943752072f, + 0.943783769f, 0.943815457f, 0.943847136f, 0.943878807f, 0.943910469f, + 0.943942122f, 0.943973767f, 0.944005403f, 0.944037030f, 0.944068649f, + 0.944100258f, 0.944131860f, 0.944163452f, 0.944195036f, 0.944226612f, + 0.944258178f, 0.944289736f, 0.944321285f, 0.944352826f, 0.944384357f, + 0.944415881f, 0.944447395f, 0.944478901f, 0.944510398f, 0.944541886f, + 0.944573366f, 0.944604837f, 0.944636300f, 0.944667753f, 0.944699198f, + 0.944730635f, 0.944762062f, 0.944793481f, 0.944824892f, 0.944856293f, + 0.944887686f, 0.944919070f, 0.944950446f, 0.944981813f, 0.945013171f, + 0.945044520f, 0.945075861f, 0.945107193f, 0.945138517f, 0.945169831f, + 0.945201137f, 0.945232435f, 0.945263724f, 0.945295004f, 0.945326275f, + 0.945357537f, 0.945388791f, 0.945420037f, 0.945451273f, 0.945482501f, + 0.945513720f, 0.945544931f, 0.945576132f, 0.945607325f, 0.945638510f, + 0.945669685f, 0.945700852f, 0.945732011f, 0.945763160f, 0.945794301f, + 0.945825434f, 0.945856557f, 0.945887672f, 0.945918778f, 0.945949876f, + 0.945980964f, 0.946012044f, 0.946043116f, 0.946074178f, 0.946105232f, + 0.946136278f, 0.946167314f, 0.946198342f, 0.946229361f, 0.946260372f, + 0.946291374f, 0.946322367f, 0.946353351f, 0.946384327f, 0.946415294f, + 0.946446252f, 0.946477202f, 0.946508143f, 0.946539075f, 0.946569998f, + 0.946600913f, 0.946631819f, 0.946662717f, 0.946693605f, 0.946724485f, + 0.946755357f, 0.946786219f, 0.946817073f, 0.946847918f, 0.946878755f, + 0.946909582f, 0.946940402f, 0.946971212f, 0.947002014f, 0.947032807f, + 0.947063591f, 0.947094366f, 0.947125133f, 0.947155891f, 0.947186641f, + 0.947217381f, 0.947248114f, 0.947278837f, 0.947309551f, 0.947340257f, + 0.947370955f, 0.947401643f, 0.947432323f, 0.947462994f, 0.947493656f, + 0.947524310f, 0.947554955f, 0.947585591f, 0.947616219f, 0.947646837f, + 0.947677447f, 0.947708049f, 0.947738642f, 0.947769225f, 0.947799801f, + 0.947830367f, 0.947860925f, 0.947891474f, 0.947922015f, 0.947952546f, + 0.947983069f, 0.948013584f, 0.948044089f, 0.948074586f, 0.948105074f, + 0.948135553f, 0.948166024f, 0.948196486f, 0.948226939f, 0.948257384f, + 0.948287820f, 0.948318247f, 0.948348665f, 0.948379075f, 0.948409476f, + 0.948439868f, 0.948470252f, 0.948500626f, 0.948530993f, 0.948561350f, + 0.948591699f, 0.948622038f, 0.948652370f, 0.948682692f, 0.948713006f, + 0.948743311f, 0.948773607f, 0.948803895f, 0.948834174f, 0.948864444f, + 0.948894705f, 0.948924958f, 0.948955202f, 0.948985437f, 0.949015664f, + 0.949045882f, 0.949076091f, 0.949106291f, 0.949136483f, 0.949166666f, + 0.949196840f, 0.949227006f, 0.949257162f, 0.949287310f, 0.949317450f, + 0.949347580f, 0.949377702f, 0.949407815f, 0.949437920f, 0.949468015f, + 0.949498102f, 0.949528181f, 0.949558250f, 0.949588311f, 0.949618363f, + 0.949648406f, 0.949678441f, 0.949708467f, 0.949738484f, 0.949768492f, + 0.949798492f, 0.949828483f, 0.949858465f, 0.949888438f, 0.949918403f, + 0.949948359f, 0.949978306f, 0.950008245f, 0.950038175f, 0.950068096f, + 0.950098008f, 0.950127912f, 0.950157807f, 0.950187693f, 0.950217570f, + 0.950247439f, 0.950277299f, 0.950307150f, 0.950336993f, 0.950366826f, + 0.950396651f, 0.950426468f, 0.950456275f, 0.950486074f, 0.950515864f, + 0.950545645f, 0.950575418f, 0.950605182f, 0.950634937f, 0.950664683f, + 0.950694421f, 0.950724150f, 0.950753870f, 0.950783581f, 0.950813284f, + 0.950842978f, 0.950872663f, 0.950902340f, 0.950932007f, 0.950961666f, + 0.950991317f, 0.951020958f, 0.951050591f, 0.951080215f, 0.951109830f, + 0.951139437f, 0.951169034f, 0.951198623f, 0.951228204f, 0.951257775f, + 0.951287338f, 0.951316892f, 0.951346437f, 0.951375974f, 0.951405502f, + 0.951435021f, 0.951464531f, 0.951494033f, 0.951523526f, 0.951553010f, + 0.951582485f, 0.951611952f, 0.951641410f, 0.951670859f, 0.951700299f, + 0.951729731f, 0.951759154f, 0.951788568f, 0.951817973f, 0.951847370f, + 0.951876758f, 0.951906137f, 0.951935507f, 0.951964869f, 0.951994222f, + 0.952023566f, 0.952052901f, 0.952082228f, 0.952111546f, 0.952140855f, + 0.952170155f, 0.952199447f, 0.952228730f, 0.952258004f, 0.952287269f, + 0.952316526f, 0.952345774f, 0.952375013f, 0.952404243f, 0.952433465f, + 0.952462677f, 0.952491882f, 0.952521077f, 0.952550263f, 0.952579441f, + 0.952608610f, 0.952637771f, 0.952666922f, 0.952696065f, 0.952725199f, + 0.952754324f, 0.952783441f, 0.952812549f, 0.952841648f, 0.952870738f, + 0.952899819f, 0.952928892f, 0.952957956f, 0.952987011f, 0.953016058f, + 0.953045095f, 0.953074124f, 0.953103144f, 0.953132156f, 0.953161159f, + 0.953190152f, 0.953219138f, 0.953248114f, 0.953277082f, 0.953306040f, + 0.953334990f, 0.953363932f, 0.953392864f, 0.953421788f, 0.953450703f, + 0.953479609f, 0.953508507f, 0.953537396f, 0.953566276f, 0.953595147f, + 0.953624009f, 0.953652863f, 0.953681708f, 0.953710544f, 0.953739371f, + 0.953768190f, 0.953797000f, 0.953825801f, 0.953854593f, 0.953883377f, + 0.953912151f, 0.953940917f, 0.953969675f, 0.953998423f, 0.954027163f, + 0.954055894f, 0.954084616f, 0.954113329f, 0.954142034f, 0.954170730f, + 0.954199417f, 0.954228095f, 0.954256765f, 0.954285425f, 0.954314077f, + 0.954342721f, 0.954371355f, 0.954399981f, 0.954428598f, 0.954457206f, + 0.954485805f, 0.954514396f, 0.954542978f, 0.954571551f, 0.954600115f, + 0.954628670f, 0.954657217f, 0.954685755f, 0.954714284f, 0.954742804f, + 0.954771316f, 0.954799819f, 0.954828313f, 0.954856798f, 0.954885275f, + 0.954913742f, 0.954942201f, 0.954970652f, 0.954999093f, 0.955027526f, + 0.955055949f, 0.955084365f, 0.955112771f, 0.955141168f, 0.955169557f, + 0.955197937f, 0.955226308f, 0.955254671f, 0.955283024f, 0.955311369f, + 0.955339705f, 0.955368032f, 0.955396351f, 0.955424660f, 0.955452961f, + 0.955481253f, 0.955509537f, 0.955537811f, 0.955566077f, 0.955594334f, + 0.955622582f, 0.955650822f, 0.955679052f, 0.955707274f, 0.955735487f, + 0.955763692f, 0.955791887f, 0.955820074f, 0.955848252f, 0.955876421f, + 0.955904581f, 0.955932733f, 0.955960876f, 0.955989010f, 0.956017135f, + 0.956045251f, 0.956073359f, 0.956101458f, 0.956129548f, 0.956157629f, + 0.956185702f, 0.956213765f, 0.956241820f, 0.956269866f, 0.956297904f, + 0.956325932f, 0.956353952f, 0.956381963f, 0.956409965f, 0.956437959f, + 0.956465943f, 0.956493919f, 0.956521886f, 0.956549844f, 0.956577794f, + 0.956605734f, 0.956633666f, 0.956661589f, 0.956689503f, 0.956717409f, + 0.956745305f, 0.956773193f, 0.956801072f, 0.956828943f, 0.956856804f, + 0.956884657f, 0.956912501f, 0.956940336f, 0.956968162f, 0.956995980f, + 0.957023788f, 0.957051588f, 0.957079379f, 0.957107162f, 0.957134935f, + 0.957162700f, 0.957190456f, 0.957218203f, 0.957245941f, 0.957273671f, + 0.957301391f, 0.957329103f, 0.957356806f, 0.957384501f, 0.957412186f, + 0.957439863f, 0.957467531f, 0.957495190f, 0.957522840f, 0.957550482f, + 0.957578115f, 0.957605739f, 0.957633354f, 0.957660960f, 0.957688558f, + 0.957716146f, 0.957743726f, 0.957771297f, 0.957798860f, 0.957826413f, + 0.957853958f, 0.957881494f, 0.957909021f, 0.957936539f, 0.957964048f, + 0.957991549f, 0.958019041f, 0.958046524f, 0.958073998f, 0.958101464f, + 0.958128920f, 0.958156368f, 0.958183807f, 0.958211237f, 0.958238659f, + 0.958266071f, 0.958293475f, 0.958320870f, 0.958348256f, 0.958375634f, + 0.958403002f, 0.958430362f, 0.958457713f, 0.958485055f, 0.958512388f, + 0.958539713f, 0.958567029f, 0.958594335f, 0.958621634f, 0.958648923f, + 0.958676203f, 0.958703475f, 0.958730738f, 0.958757992f, 0.958785237f, + 0.958812473f, 0.958839701f, 0.958866920f, 0.958894130f, 0.958921331f, + 0.958948523f, 0.958975707f, 0.959002881f, 0.959030047f, 0.959057204f, + 0.959084352f, 0.959111492f, 0.959138622f, 0.959165744f, 0.959192857f, + 0.959219961f, 0.959247057f, 0.959274143f, 0.959301221f, 0.959328290f, + 0.959355350f, 0.959382401f, 0.959409444f, 0.959436477f, 0.959463502f, + 0.959490518f, 0.959517525f, 0.959544524f, 0.959571513f, 0.959598494f, + 0.959625466f, 0.959652429f, 0.959679383f, 0.959706328f, 0.959733265f, + 0.959760193f, 0.959787112f, 0.959814022f, 0.959840923f, 0.959867816f, + 0.959894699f, 0.959921574f, 0.959948440f, 0.959975297f, 0.960002146f, + 0.960028985f, 0.960055816f, 0.960082638f, 0.960109451f, 0.960136255f, + 0.960163051f, 0.960189837f, 0.960216615f, 0.960243384f, 0.960270144f, + 0.960296895f, 0.960323638f, 0.960350371f, 0.960377096f, 0.960403812f, + 0.960430519f, 0.960457218f, 0.960483907f, 0.960510588f, 0.960537260f, + 0.960563923f, 0.960590577f, 0.960617222f, 0.960643859f, 0.960670487f, + 0.960697105f, 0.960723715f, 0.960750317f, 0.960776909f, 0.960803493f, + 0.960830067f, 0.960856633f, 0.960883190f, 0.960909738f, 0.960936278f, + 0.960962808f, 0.960989330f, 0.961015843f, 0.961042347f, 0.961068842f, + 0.961095329f, 0.961121806f, 0.961148275f, 0.961174735f, 0.961201186f, + 0.961227628f, 0.961254061f, 0.961280486f, 0.961306902f, 0.961333308f, + 0.961359706f, 0.961386096f, 0.961412476f, 0.961438847f, 0.961465210f, + 0.961491564f, 0.961517909f, 0.961544245f, 0.961570572f, 0.961596891f, + 0.961623201f, 0.961649501f, 0.961675793f, 0.961702077f, 0.961728351f, + 0.961754616f, 0.961780873f, 0.961807121f, 0.961833360f, 0.961859590f, + 0.961885811f, 0.961912023f, 0.961938227f, 0.961964422f, 0.961990608f, + 0.962016785f, 0.962042953f, 0.962069112f, 0.962095263f, 0.962121404f, + 0.962147537f, 0.962173661f, 0.962199776f, 0.962225882f, 0.962251980f, + 0.962278069f, 0.962304148f, 0.962330219f, 0.962356281f, 0.962382334f, + 0.962408379f, 0.962434414f, 0.962460441f, 0.962486459f, 0.962512468f, + 0.962538468f, 0.962564459f, 0.962590442f, 0.962616415f, 0.962642380f, + 0.962668336f, 0.962694283f, 0.962720221f, 0.962746151f, 0.962772071f, + 0.962797983f, 0.962823886f, 0.962849780f, 0.962875665f, 0.962901541f, + 0.962927408f, 0.962953267f, 0.962979117f, 0.963004957f, 0.963030789f, + 0.963056613f, 0.963082427f, 0.963108232f, 0.963134029f, 0.963159817f, + 0.963185596f, 0.963211366f, 0.963237127f, 0.963262879f, 0.963288623f, + 0.963314357f, 0.963340083f, 0.963365800f, 0.963391508f, 0.963417207f, + 0.963442897f, 0.963468579f, 0.963494251f, 0.963519915f, 0.963545570f, + 0.963571216f, 0.963596853f, 0.963622482f, 0.963648101f, 0.963673712f, + 0.963699314f, 0.963724907f, 0.963750491f, 0.963776066f, 0.963801632f, + 0.963827190f, 0.963852738f, 0.963878278f, 0.963903809f, 0.963929331f, + 0.963954844f, 0.963980348f, 0.964005844f, 0.964031330f, 0.964056808f, + 0.964082277f, 0.964107737f, 0.964133188f, 0.964158631f, 0.964184064f, + 0.964209489f, 0.964234904f, 0.964260311f, 0.964285709f, 0.964311098f, + 0.964336478f, 0.964361850f, 0.964387212f, 0.964412566f, 0.964437911f, + 0.964463247f, 0.964488574f, 0.964513892f, 0.964539201f, 0.964564502f, + 0.964589793f, 0.964615076f, 0.964640350f, 0.964665615f, 0.964690871f, + 0.964716118f, 0.964741357f, 0.964766586f, 0.964791807f, 0.964817019f, + 0.964842222f, 0.964867416f, 0.964892601f, 0.964917777f, 0.964942945f, + 0.964968103f, 0.964993253f, 0.965018394f, 0.965043526f, 0.965068649f, + 0.965093763f, 0.965118868f, 0.965143965f, 0.965169052f, 0.965194131f, + 0.965219201f, 0.965244262f, 0.965269314f, 0.965294357f, 0.965319392f, + 0.965344417f, 0.965369434f, 0.965394442f, 0.965419441f, 0.965444431f, + 0.965469412f, 0.965494384f, 0.965519347f, 0.965544302f, 0.965569248f, + 0.965594184f, 0.965619112f, 0.965644031f, 0.965668941f, 0.965693843f, + 0.965718735f, 0.965743618f, 0.965768493f, 0.965793359f, 0.965818216f, + 0.965843064f, 0.965867903f, 0.965892733f, 0.965917554f, 0.965942367f, + 0.965967171f, 0.965991965f, 0.966016751f, 0.966041528f, 0.966066296f, + 0.966091055f, 0.966115806f, 0.966140547f, 0.966165280f, 0.966190003f, + 0.966214718f, 0.966239424f, 0.966264121f, 0.966288809f, 0.966313489f, + 0.966338159f, 0.966362821f, 0.966387473f, 0.966412117f, 0.966436752f, + 0.966461378f, 0.966485995f, 0.966510603f, 0.966535202f, 0.966559793f, + 0.966584374f, 0.966608947f, 0.966633511f, 0.966658066f, 0.966682612f, + 0.966707149f, 0.966731677f, 0.966756197f, 0.966780707f, 0.966805209f, + 0.966829701f, 0.966854185f, 0.966878660f, 0.966903126f, 0.966927583f, + 0.966952032f, 0.966976471f, 0.967000902f, 0.967025323f, 0.967049736f, + 0.967074140f, 0.967098535f, 0.967122921f, 0.967147298f, 0.967171666f, + 0.967196025f, 0.967220376f, 0.967244718f, 0.967269050f, 0.967293374f, + 0.967317689f, 0.967341995f, 0.967366292f, 0.967390580f, 0.967414860f, + 0.967439130f, 0.967463392f, 0.967487645f, 0.967511888f, 0.967536123f, + 0.967560349f, 0.967584566f, 0.967608775f, 0.967632974f, 0.967657164f, + 0.967681346f, 0.967705519f, 0.967729682f, 0.967753837f, 0.967777983f, + 0.967802120f, 0.967826248f, 0.967850368f, 0.967874478f, 0.967898579f, + 0.967922672f, 0.967946756f, 0.967970830f, 0.967994896f, 0.968018953f, + 0.968043001f, 0.968067041f, 0.968091071f, 0.968115092f, 0.968139105f, + 0.968163108f, 0.968187103f, 0.968211089f, 0.968235066f, 0.968259034f, + 0.968282993f, 0.968306943f, 0.968330884f, 0.968354817f, 0.968378740f, + 0.968402655f, 0.968426561f, 0.968450457f, 0.968474345f, 0.968498224f, + 0.968522094f, 0.968545955f, 0.968569808f, 0.968593651f, 0.968617486f, + 0.968641311f, 0.968665128f, 0.968688936f, 0.968712734f, 0.968736524f, + 0.968760305f, 0.968784078f, 0.968807841f, 0.968831595f, 0.968855341f, + 0.968879077f, 0.968902805f, 0.968926523f, 0.968950233f, 0.968973934f, + 0.968997626f, 0.969021309f, 0.969044983f, 0.969068649f, 0.969092305f, + 0.969115953f, 0.969139591f, 0.969163221f, 0.969186842f, 0.969210453f, + 0.969234056f, 0.969257650f, 0.969281235f, 0.969304812f, 0.969328379f, + 0.969351937f, 0.969375487f, 0.969399027f, 0.969422559f, 0.969446082f, + 0.969469595f, 0.969493100f, 0.969516596f, 0.969540083f, 0.969563562f, + 0.969587031f, 0.969610491f, 0.969633943f, 0.969657385f, 0.969680819f, + 0.969704243f, 0.969727659f, 0.969751066f, 0.969774464f, 0.969797853f, + 0.969821233f, 0.969844604f, 0.969867967f, 0.969891320f, 0.969914665f, + 0.969938000f, 0.969961327f, 0.969984644f, 0.970007953f, 0.970031253f, + 0.970054544f, 0.970077826f, 0.970101099f, 0.970124364f, 0.970147619f, + 0.970170865f, 0.970194103f, 0.970217331f, 0.970240551f, 0.970263762f, + 0.970286963f, 0.970310156f, 0.970333340f, 0.970356515f, 0.970379681f, + 0.970402839f, 0.970425987f, 0.970449126f, 0.970472257f, 0.970495378f, + 0.970518491f, 0.970541595f, 0.970564689f, 0.970587775f, 0.970610852f, + 0.970633920f, 0.970656979f, 0.970680029f, 0.970703071f, 0.970726103f, + 0.970749126f, 0.970772141f, 0.970795146f, 0.970818143f, 0.970841131f, + 0.970864109f, 0.970887079f, 0.970910040f, 0.970932992f, 0.970955935f, + 0.970978869f, 0.971001795f, 0.971024711f, 0.971047618f, 0.971070517f, + 0.971093406f, 0.971116287f, 0.971139158f, 0.971162021f, 0.971184875f, + 0.971207720f, 0.971230556f, 0.971253383f, 0.971276201f, 0.971299010f, + 0.971321810f, 0.971344602f, 0.971367384f, 0.971390158f, 0.971412922f, + 0.971435678f, 0.971458424f, 0.971481162f, 0.971503891f, 0.971526611f, + 0.971549322f, 0.971572024f, 0.971594717f, 0.971617401f, 0.971640076f, + 0.971662743f, 0.971685400f, 0.971708048f, 0.971730688f, 0.971753319f, + 0.971775940f, 0.971798553f, 0.971821157f, 0.971843752f, 0.971866337f, + 0.971888914f, 0.971911483f, 0.971934042f, 0.971956592f, 0.971979133f, + 0.972001665f, 0.972024189f, 0.972046703f, 0.972069209f, 0.972091705f, + 0.972114193f, 0.972136672f, 0.972159141f, 0.972181602f, 0.972204054f, + 0.972226497f, 0.972248931f, 0.972271356f, 0.972293772f, 0.972316180f, + 0.972338578f, 0.972360967f, 0.972383348f, 0.972405719f, 0.972428082f, + 0.972450435f, 0.972472780f, 0.972495115f, 0.972517442f, 0.972539760f, + 0.972562069f, 0.972584369f, 0.972606660f, 0.972628942f, 0.972651215f, + 0.972673479f, 0.972695735f, 0.972717981f, 0.972740218f, 0.972762447f, + 0.972784666f, 0.972806877f, 0.972829078f, 0.972851271f, 0.972873455f, + 0.972895629f, 0.972917795f, 0.972939952f, 0.972962100f, 0.972984239f, + 0.973006369f, 0.973028490f, 0.973050603f, 0.973072706f, 0.973094800f, + 0.973116885f, 0.973138962f, 0.973161029f, 0.973183088f, 0.973205137f, + 0.973227178f, 0.973249210f, 0.973271232f, 0.973293246f, 0.973315251f, + 0.973337247f, 0.973359234f, 0.973381212f, 0.973403181f, 0.973425141f, + 0.973447092f, 0.973469034f, 0.973490967f, 0.973512892f, 0.973534807f, + 0.973556714f, 0.973578611f, 0.973600499f, 0.973622379f, 0.973644250f, + 0.973666111f, 0.973687964f, 0.973709808f, 0.973731643f, 0.973753468f, + 0.973775285f, 0.973797093f, 0.973818892f, 0.973840682f, 0.973862464f, + 0.973884236f, 0.973905999f, 0.973927753f, 0.973949498f, 0.973971235f, + 0.973992962f, 0.974014681f, 0.974036390f, 0.974058091f, 0.974079782f, + 0.974101465f, 0.974123139f, 0.974144803f, 0.974166459f, 0.974188106f, + 0.974209744f, 0.974231373f, 0.974252993f, 0.974274604f, 0.974296206f, + 0.974317799f, 0.974339383f, 0.974360958f, 0.974382524f, 0.974404081f, + 0.974425630f, 0.974447169f, 0.974468699f, 0.974490221f, 0.974511733f, + 0.974533237f, 0.974554731f, 0.974576217f, 0.974597694f, 0.974619161f, + 0.974640620f, 0.974662070f, 0.974683511f, 0.974704943f, 0.974726365f, + 0.974747779f, 0.974769184f, 0.974790580f, 0.974811967f, 0.974833345f, + 0.974854715f, 0.974876075f, 0.974897426f, 0.974918768f, 0.974940102f, + 0.974961426f, 0.974982741f, 0.975004048f, 0.975025345f, 0.975046634f, + 0.975067913f, 0.975089184f, 0.975110445f, 0.975131698f, 0.975152941f, + 0.975174176f, 0.975195402f, 0.975216619f, 0.975237827f, 0.975259025f, + 0.975280215f, 0.975301396f, 0.975322568f, 0.975343731f, 0.975364885f, + 0.975386030f, 0.975407166f, 0.975428293f, 0.975449412f, 0.975470521f, + 0.975491621f, 0.975512712f, 0.975533795f, 0.975554868f, 0.975575932f, + 0.975596988f, 0.975618034f, 0.975639071f, 0.975660100f, 0.975681119f, + 0.975702130f, 0.975723132f, 0.975744124f, 0.975765108f, 0.975786083f, + 0.975807048f, 0.975828005f, 0.975848953f, 0.975869892f, 0.975890821f, + 0.975911742f, 0.975932654f, 0.975953557f, 0.975974451f, 0.975995336f, + 0.976016212f, 0.976037079f, 0.976057937f, 0.976078786f, 0.976099626f, + 0.976120457f, 0.976141280f, 0.976162093f, 0.976182897f, 0.976203692f, + 0.976224479f, 0.976245256f, 0.976266024f, 0.976286784f, 0.976307534f, + 0.976328275f, 0.976349008f, 0.976369731f, 0.976390446f, 0.976411151f, + 0.976431848f, 0.976452535f, 0.976473214f, 0.976493884f, 0.976514544f, + 0.976535196f, 0.976555839f, 0.976576472f, 0.976597097f, 0.976617713f, + 0.976638320f, 0.976658917f, 0.976679506f, 0.976700086f, 0.976720657f, + 0.976741219f, 0.976761772f, 0.976782316f, 0.976802851f, 0.976823377f, + 0.976843894f, 0.976864402f, 0.976884901f, 0.976905391f, 0.976925872f, + 0.976946344f, 0.976966807f, 0.976987261f, 0.977007706f, 0.977028143f, + 0.977048570f, 0.977068988f, 0.977089397f, 0.977109798f, 0.977130189f, + 0.977150571f, 0.977170944f, 0.977191309f, 0.977211664f, 0.977232011f, + 0.977252348f, 0.977272676f, 0.977292996f, 0.977313306f, 0.977333608f, + 0.977353900f, 0.977374184f, 0.977394458f, 0.977414724f, 0.977434980f, + 0.977455228f, 0.977475466f, 0.977495696f, 0.977515917f, 0.977536128f, + 0.977556331f, 0.977576524f, 0.977596709f, 0.977616885f, 0.977637051f, + 0.977657209f, 0.977677358f, 0.977697498f, 0.977717628f, 0.977737750f, + 0.977757863f, 0.977777967f, 0.977798061f, 0.977818147f, 0.977838224f, + 0.977858292f, 0.977878351f, 0.977898401f, 0.977918441f, 0.977938473f, + 0.977958496f, 0.977978510f, 0.977998515f, 0.978018511f, 0.978038498f, + 0.978058476f, 0.978078445f, 0.978098405f, 0.978118356f, 0.978138298f, + 0.978158231f, 0.978178155f, 0.978198070f, 0.978217976f, 0.978237873f, + 0.978257761f, 0.978277640f, 0.978297510f, 0.978317371f, 0.978337223f, + 0.978357066f, 0.978376900f, 0.978396725f, 0.978416541f, 0.978436348f, + 0.978456146f, 0.978475935f, 0.978495715f, 0.978515487f, 0.978535249f, + 0.978555002f, 0.978574746f, 0.978594481f, 0.978614207f, 0.978633924f, + 0.978653633f, 0.978673332f, 0.978693022f, 0.978712703f, 0.978732375f, + 0.978752038f, 0.978771693f, 0.978791338f, 0.978810974f, 0.978830601f, + 0.978850219f, 0.978869829f, 0.978889429f, 0.978909020f, 0.978928602f, + 0.978948175f, 0.978967740f, 0.978987295f, 0.979006841f, 0.979026378f, + 0.979045906f, 0.979065426f, 0.979084936f, 0.979104437f, 0.979123929f, + 0.979143412f, 0.979162887f, 0.979182352f, 0.979201808f, 0.979221255f, + 0.979240693f, 0.979260123f, 0.979279543f, 0.979298954f, 0.979318356f, + 0.979337749f, 0.979357134f, 0.979376509f, 0.979395875f, 0.979415232f, + 0.979434580f, 0.979453920f, 0.979473250f, 0.979492571f, 0.979511883f, + 0.979531186f, 0.979550481f, 0.979569766f, 0.979589042f, 0.979608309f, + 0.979627567f, 0.979646816f, 0.979666056f, 0.979685288f, 0.979704510f, + 0.979723723f, 0.979742927f, 0.979762122f, 0.979781308f, 0.979800485f, + 0.979819653f, 0.979838813f, 0.979857963f, 0.979877104f, 0.979896236f, + 0.979915359f, 0.979934473f, 0.979953578f, 0.979972674f, 0.979991761f, + 0.980010839f, 0.980029908f, 0.980048968f, 0.980068019f, 0.980087061f, + 0.980106094f, 0.980125118f, 0.980144133f, 0.980163139f, 0.980182136f, + 0.980201124f, 0.980220103f, 0.980239073f, 0.980258034f, 0.980276986f, + 0.980295928f, 0.980314862f, 0.980333787f, 0.980352703f, 0.980371610f, + 0.980390508f, 0.980409397f, 0.980428276f, 0.980447147f, 0.980466009f, + 0.980484862f, 0.980503706f, 0.980522540f, 0.980541366f, 0.980560183f, + 0.980578990f, 0.980597789f, 0.980616579f, 0.980635360f, 0.980654131f, + 0.980672894f, 0.980691647f, 0.980710392f, 0.980729128f, 0.980747854f, + 0.980766572f, 0.980785280f, 0.980803980f, 0.980822670f, 0.980841352f, + 0.980860024f, 0.980878688f, 0.980897342f, 0.980915988f, 0.980934624f, + 0.980953252f, 0.980971870f, 0.980990480f, 0.981009080f, 0.981027671f, + 0.981046254f, 0.981064827f, 0.981083391f, 0.981101946f, 0.981120493f, + 0.981139030f, 0.981157558f, 0.981176077f, 0.981194588f, 0.981213089f, + 0.981231581f, 0.981250064f, 0.981268538f, 0.981287003f, 0.981305459f, + 0.981323906f, 0.981342344f, 0.981360773f, 0.981379193f, 0.981397604f, + 0.981416006f, 0.981434399f, 0.981452783f, 0.981471158f, 0.981489524f, + 0.981507881f, 0.981526228f, 0.981544567f, 0.981562897f, 0.981581218f, + 0.981599530f, 0.981617832f, 0.981636126f, 0.981654411f, 0.981672686f, + 0.981690953f, 0.981709210f, 0.981727459f, 0.981745699f, 0.981763929f, + 0.981782151f, 0.981800363f, 0.981818566f, 0.981836761f, 0.981854946f, + 0.981873123f, 0.981891290f, 0.981909448f, 0.981927598f, 0.981945738f, + 0.981963869f, 0.981981991f, 0.982000105f, 0.982018209f, 0.982036304f, + 0.982054390f, 0.982072467f, 0.982090535f, 0.982108594f, 0.982126644f, + 0.982144685f, 0.982162717f, 0.982180740f, 0.982198754f, 0.982216759f, + 0.982234755f, 0.982252741f, 0.982270719f, 0.982288688f, 0.982306648f, + 0.982324598f, 0.982342540f, 0.982360473f, 0.982378396f, 0.982396311f, + 0.982414216f, 0.982432113f, 0.982450000f, 0.982467879f, 0.982485748f, + 0.982503609f, 0.982521460f, 0.982539302f, 0.982557136f, 0.982574960f, + 0.982592775f, 0.982610581f, 0.982628378f, 0.982646167f, 0.982663946f, + 0.982681716f, 0.982699477f, 0.982717229f, 0.982734972f, 0.982752706f, + 0.982770431f, 0.982788147f, 0.982805853f, 0.982823551f, 0.982841240f, + 0.982858920f, 0.982876590f, 0.982894252f, 0.982911905f, 0.982929548f, + 0.982947183f, 0.982964808f, 0.982982425f, 0.983000032f, 0.983017631f, + 0.983035220f, 0.983052801f, 0.983070372f, 0.983087934f, 0.983105487f, + 0.983123032f, 0.983140567f, 0.983158093f, 0.983175610f, 0.983193118f, + 0.983210617f, 0.983228107f, 0.983245588f, 0.983263060f, 0.983280523f, + 0.983297977f, 0.983315422f, 0.983332857f, 0.983350284f, 0.983367702f, + 0.983385110f, 0.983402510f, 0.983419900f, 0.983437282f, 0.983454655f, + 0.983472018f, 0.983489372f, 0.983506718f, 0.983524054f, 0.983541381f, + 0.983558700f, 0.983576009f, 0.983593309f, 0.983610600f, 0.983627882f, + 0.983645155f, 0.983662419f, 0.983679674f, 0.983696920f, 0.983714157f, + 0.983731385f, 0.983748604f, 0.983765813f, 0.983783014f, 0.983800206f, + 0.983817388f, 0.983834562f, 0.983851726f, 0.983868882f, 0.983886028f, + 0.983903166f, 0.983920294f, 0.983937413f, 0.983954524f, 0.983971625f, + 0.983988717f, 0.984005800f, 0.984022874f, 0.984039939f, 0.984056995f, + 0.984074042f, 0.984091080f, 0.984108109f, 0.984125129f, 0.984142140f, + 0.984159141f, 0.984176134f, 0.984193118f, 0.984210092f, 0.984227058f, + 0.984244014f, 0.984260962f, 0.984277900f, 0.984294830f, 0.984311750f, + 0.984328661f, 0.984345563f, 0.984362457f, 0.984379341f, 0.984396216f, + 0.984413082f, 0.984429939f, 0.984446787f, 0.984463626f, 0.984480455f, + 0.984497276f, 0.984514088f, 0.984530891f, 0.984547684f, 0.984564469f, + 0.984581244f, 0.984598011f, 0.984614768f, 0.984631517f, 0.984648256f, + 0.984664986f, 0.984681707f, 0.984698420f, 0.984715123f, 0.984731817f, + 0.984748502f, 0.984765178f, 0.984781845f, 0.984798503f, 0.984815151f, + 0.984831791f, 0.984848422f, 0.984865043f, 0.984881656f, 0.984898260f, + 0.984914854f, 0.984931440f, 0.984948016f, 0.984964583f, 0.984981142f, + 0.984997691f, 0.985014231f, 0.985030762f, 0.985047284f, 0.985063797f, + 0.985080301f, 0.985096796f, 0.985113282f, 0.985129759f, 0.985146226f, + 0.985162685f, 0.985179135f, 0.985195575f, 0.985212007f, 0.985228429f, + 0.985244843f, 0.985261247f, 0.985277642f, 0.985294029f, 0.985310406f, + 0.985326774f, 0.985343133f, 0.985359483f, 0.985375824f, 0.985392156f, + 0.985408479f, 0.985424792f, 0.985441097f, 0.985457393f, 0.985473679f, + 0.985489957f, 0.985506226f, 0.985522485f, 0.985538735f, 0.985554977f, + 0.985571209f, 0.985587432f, 0.985603646f, 0.985619851f, 0.985636047f, + 0.985652234f, 0.985668412f, 0.985684581f, 0.985700741f, 0.985716891f, + 0.985733033f, 0.985749166f, 0.985765289f, 0.985781404f, 0.985797509f, + 0.985813606f, 0.985829693f, 0.985845771f, 0.985861840f, 0.985877900f, + 0.985893951f, 0.985909993f, 0.985926026f, 0.985942050f, 0.985958065f, + 0.985974071f, 0.985990067f, 0.986006055f, 0.986022033f, 0.986038003f, + 0.986053963f, 0.986069915f, 0.986085857f, 0.986101790f, 0.986117714f, + 0.986133629f, 0.986149535f, 0.986165432f, 0.986181320f, 0.986197199f, + 0.986213069f, 0.986228930f, 0.986244781f, 0.986260624f, 0.986276457f, + 0.986292282f, 0.986308097f, 0.986323904f, 0.986339701f, 0.986355489f, + 0.986371268f, 0.986387038f, 0.986402799f, 0.986418551f, 0.986434294f, + 0.986450028f, 0.986465752f, 0.986481468f, 0.986497175f, 0.986512872f, + 0.986528561f, 0.986544240f, 0.986559910f, 0.986575572f, 0.986591224f, + 0.986606867f, 0.986622501f, 0.986638126f, 0.986653742f, 0.986669349f, + 0.986684946f, 0.986700535f, 0.986716115f, 0.986731685f, 0.986747247f, + 0.986762799f, 0.986778342f, 0.986793877f, 0.986809402f, 0.986824918f, + 0.986840425f, 0.986855923f, 0.986871412f, 0.986886892f, 0.986902363f, + 0.986917824f, 0.986933277f, 0.986948720f, 0.986964155f, 0.986979580f, + 0.986994997f, 0.987010404f, 0.987025802f, 0.987041191f, 0.987056571f, + 0.987071942f, 0.987087304f, 0.987102657f, 0.987118001f, 0.987133335f, + 0.987148661f, 0.987163978f, 0.987179285f, 0.987194583f, 0.987209873f, + 0.987225153f, 0.987240424f, 0.987255686f, 0.987270939f, 0.987286183f, + 0.987301418f, 0.987316644f, 0.987331861f, 0.987347068f, 0.987362267f, + 0.987377456f, 0.987392637f, 0.987407808f, 0.987422970f, 0.987438124f, + 0.987453268f, 0.987468403f, 0.987483529f, 0.987498646f, 0.987513753f, + 0.987528852f, 0.987543942f, 0.987559022f, 0.987574094f, 0.987589156f, + 0.987604210f, 0.987619254f, 0.987634289f, 0.987649315f, 0.987664332f, + 0.987679340f, 0.987694339f, 0.987709329f, 0.987724310f, 0.987739281f, + 0.987754244f, 0.987769197f, 0.987784142f, 0.987799077f, 0.987814003f, + 0.987828920f, 0.987843828f, 0.987858727f, 0.987873617f, 0.987888498f, + 0.987903370f, 0.987918233f, 0.987933086f, 0.987947931f, 0.987962766f, + 0.987977593f, 0.987992410f, 0.988007218f, 0.988022017f, 0.988036807f, + 0.988051588f, 0.988066360f, 0.988081123f, 0.988095876f, 0.988110621f, + 0.988125357f, 0.988140083f, 0.988154800f, 0.988169509f, 0.988184208f, + 0.988198898f, 0.988213579f, 0.988228251f, 0.988242914f, 0.988257568f, + 0.988272212f, 0.988286848f, 0.988301475f, 0.988316092f, 0.988330700f, + 0.988345300f, 0.988359890f, 0.988374471f, 0.988389043f, 0.988403606f, + 0.988418160f, 0.988432705f, 0.988447240f, 0.988461767f, 0.988476284f, + 0.988490793f, 0.988505292f, 0.988519782f, 0.988534264f, 0.988548736f, + 0.988563199f, 0.988577653f, 0.988592097f, 0.988606533f, 0.988620960f, + 0.988635377f, 0.988649786f, 0.988664185f, 0.988678576f, 0.988692957f, + 0.988707329f, 0.988721692f, 0.988736046f, 0.988750391f, 0.988764727f, + 0.988779053f, 0.988793371f, 0.988807679f, 0.988821979f, 0.988836269f, + 0.988850550f, 0.988864822f, 0.988879086f, 0.988893340f, 0.988907584f, + 0.988921820f, 0.988936047f, 0.988950265f, 0.988964473f, 0.988978672f, + 0.988992863f, 0.989007044f, 0.989021216f, 0.989035379f, 0.989049533f, + 0.989063678f, 0.989077814f, 0.989091941f, 0.989106058f, 0.989120167f, + 0.989134266f, 0.989148357f, 0.989162438f, 0.989176510f, 0.989190573f, + 0.989204627f, 0.989218672f, 0.989232708f, 0.989246734f, 0.989260752f, + 0.989274760f, 0.989288760f, 0.989302750f, 0.989316731f, 0.989330704f, + 0.989344667f, 0.989358621f, 0.989372565f, 0.989386501f, 0.989400428f, + 0.989414345f, 0.989428254f, 0.989442153f, 0.989456043f, 0.989469925f, + 0.989483797f, 0.989497660f, 0.989511514f, 0.989525358f, 0.989539194f, + 0.989553021f, 0.989566838f, 0.989580647f, 0.989594446f, 0.989608236f, + 0.989622017f, 0.989635790f, 0.989649552f, 0.989663306f, 0.989677051f, + 0.989690787f, 0.989704513f, 0.989718231f, 0.989731939f, 0.989745638f, + 0.989759329f, 0.989773010f, 0.989786682f, 0.989800344f, 0.989813998f, + 0.989827643f, 0.989841278f, 0.989854905f, 0.989868522f, 0.989882131f, + 0.989895730f, 0.989909320f, 0.989922901f, 0.989936473f, 0.989950036f, + 0.989963589f, 0.989977134f, 0.989990669f, 0.990004196f, 0.990017713f, + 0.990031221f, 0.990044720f, 0.990058210f, 0.990071691f, 0.990085163f, + 0.990098626f, 0.990112079f, 0.990125524f, 0.990138959f, 0.990152385f, + 0.990165803f, 0.990179211f, 0.990192610f, 0.990205999f, 0.990219380f, + 0.990232752f, 0.990246115f, 0.990259468f, 0.990272812f, 0.990286148f, + 0.990299474f, 0.990312791f, 0.990326099f, 0.990339398f, 0.990352687f, + 0.990365968f, 0.990379240f, 0.990392502f, 0.990405755f, 0.990419000f, + 0.990432235f, 0.990445461f, 0.990458678f, 0.990471886f, 0.990485084f, + 0.990498274f, 0.990511454f, 0.990524626f, 0.990537788f, 0.990550941f, + 0.990564085f, 0.990577220f, 0.990590346f, 0.990603463f, 0.990616571f, + 0.990629669f, 0.990642759f, 0.990655839f, 0.990668910f, 0.990681972f, + 0.990695025f, 0.990708069f, 0.990721104f, 0.990734130f, 0.990747147f, + 0.990760154f, 0.990773152f, 0.990786142f, 0.990799122f, 0.990812093f, + 0.990825055f, 0.990838008f, 0.990850952f, 0.990863886f, 0.990876812f, + 0.990889728f, 0.990902635f, 0.990915534f, 0.990928423f, 0.990941303f, + 0.990954174f, 0.990967035f, 0.990979888f, 0.990992732f, 0.991005566f, + 0.991018391f, 0.991031208f, 0.991044015f, 0.991056813f, 0.991069602f, + 0.991082381f, 0.991095152f, 0.991107914f, 0.991120666f, 0.991133410f, + 0.991146144f, 0.991158869f, 0.991171585f, 0.991184292f, 0.991196990f, + 0.991209678f, 0.991222358f, 0.991235028f, 0.991247690f, 0.991260342f, + 0.991272985f, 0.991285619f, 0.991298244f, 0.991310860f, 0.991323467f, + 0.991336064f, 0.991348653f, 0.991361232f, 0.991373802f, 0.991386363f, + 0.991398915f, 0.991411458f, 0.991423992f, 0.991436517f, 0.991449032f, + 0.991461539f, 0.991474036f, 0.991486524f, 0.991499003f, 0.991511473f, + 0.991523934f, 0.991536386f, 0.991548829f, 0.991561262f, 0.991573687f, + 0.991586102f, 0.991598508f, 0.991610905f, 0.991623293f, 0.991635672f, + 0.991648042f, 0.991660402f, 0.991672754f, 0.991685096f, 0.991697430f, + 0.991709754f, 0.991722069f, 0.991734375f, 0.991746671f, 0.991758959f, + 0.991771238f, 0.991783507f, 0.991795768f, 0.991808019f, 0.991820261f, + 0.991832494f, 0.991844718f, 0.991856933f, 0.991869138f, 0.991881335f, + 0.991893522f, 0.991905700f, 0.991917870f, 0.991930030f, 0.991942181f, + 0.991954322f, 0.991966455f, 0.991978579f, 0.991990693f, 0.992002799f, + 0.992014895f, 0.992026982f, 0.992039060f, 0.992051129f, 0.992063189f, + 0.992075239f, 0.992087281f, 0.992099313f, 0.992111336f, 0.992123351f, + 0.992135356f, 0.992147352f, 0.992159338f, 0.992171316f, 0.992183285f, + 0.992195244f, 0.992207194f, 0.992219136f, 0.992231068f, 0.992242991f, + 0.992254905f, 0.992266809f, 0.992278705f, 0.992290591f, 0.992302469f, + 0.992314337f, 0.992326196f, 0.992338046f, 0.992349887f, 0.992361719f, + 0.992373541f, 0.992385355f, 0.992397159f, 0.992408955f, 0.992420741f, + 0.992432518f, 0.992444286f, 0.992456044f, 0.992467794f, 0.992479535f, + 0.992491266f, 0.992502988f, 0.992514701f, 0.992526406f, 0.992538100f, + 0.992549786f, 0.992561463f, 0.992573130f, 0.992584789f, 0.992596438f, + 0.992608078f, 0.992619709f, 0.992631331f, 0.992642944f, 0.992654548f, + 0.992666142f, 0.992677728f, 0.992689304f, 0.992700871f, 0.992712429f, + 0.992723978f, 0.992735518f, 0.992747049f, 0.992758570f, 0.992770083f, + 0.992781586f, 0.992793080f, 0.992804565f, 0.992816041f, 0.992827508f, + 0.992838966f, 0.992850414f, 0.992861854f, 0.992873284f, 0.992884705f, + 0.992896117f, 0.992907520f, 0.992918914f, 0.992930299f, 0.992941674f, + 0.992953041f, 0.992964398f, 0.992975746f, 0.992987085f, 0.992998415f, + 0.993009736f, 0.993021048f, 0.993032350f, 0.993043644f, 0.993054928f, + 0.993066203f, 0.993077469f, 0.993088726f, 0.993099974f, 0.993111212f, + 0.993122442f, 0.993133662f, 0.993144873f, 0.993156076f, 0.993167269f, + 0.993178452f, 0.993189627f, 0.993200793f, 0.993211949f, 0.993223097f, + 0.993234235f, 0.993245364f, 0.993256484f, 0.993267595f, 0.993278696f, + 0.993289789f, 0.993300872f, 0.993311947f, 0.993323012f, 0.993334068f, + 0.993345115f, 0.993356153f, 0.993367181f, 0.993378201f, 0.993389211f, + 0.993400212f, 0.993411205f, 0.993422188f, 0.993433161f, 0.993444126f, + 0.993455082f, 0.993466028f, 0.993476966f, 0.993487894f, 0.993498813f, + 0.993509723f, 0.993520624f, 0.993531515f, 0.993542398f, 0.993553271f, + 0.993564136f, 0.993574991f, 0.993585837f, 0.993596674f, 0.993607501f, + 0.993618320f, 0.993629129f, 0.993639930f, 0.993650721f, 0.993661503f, + 0.993672276f, 0.993683040f, 0.993693795f, 0.993704540f, 0.993715277f, + 0.993726004f, 0.993736722f, 0.993747431f, 0.993758131f, 0.993768822f, + 0.993779503f, 0.993790176f, 0.993800839f, 0.993811493f, 0.993822138f, + 0.993832774f, 0.993843401f, 0.993854019f, 0.993864627f, 0.993875227f, + 0.993885817f, 0.993896398f, 0.993906970f, 0.993917533f, 0.993928087f, + 0.993938631f, 0.993949167f, 0.993959693f, 0.993970210f, 0.993980718f, + 0.993991217f, 0.994001707f, 0.994012187f, 0.994022659f, 0.994033121f, + 0.994043574f, 0.994054019f, 0.994064453f, 0.994074879f, 0.994085296f, + 0.994095704f, 0.994106102f, 0.994116491f, 0.994126871f, 0.994137242f, + 0.994147604f, 0.994157957f, 0.994168300f, 0.994178635f, 0.994188960f, + 0.994199276f, 0.994209583f, 0.994219881f, 0.994230170f, 0.994240449f, + 0.994250720f, 0.994260981f, 0.994271233f, 0.994281476f, 0.994291710f, + 0.994301935f, 0.994312151f, 0.994322357f, 0.994332555f, 0.994342743f, + 0.994352922f, 0.994363092f, 0.994373253f, 0.994383404f, 0.994393547f, + 0.994403680f, 0.994413804f, 0.994423919f, 0.994434025f, 0.994444122f, + 0.994454210f, 0.994464288f, 0.994474358f, 0.994484418f, 0.994494469f, + 0.994504511f, 0.994514544f, 0.994524567f, 0.994534582f, 0.994544587f, + 0.994554584f, 0.994564571f, 0.994574549f, 0.994584518f, 0.994594477f, + 0.994604428f, 0.994614369f, 0.994624301f, 0.994634225f, 0.994644138f, + 0.994654043f, 0.994663939f, 0.994673826f, 0.994683703f, 0.994693571f, + 0.994703430f, 0.994713280f, 0.994723121f, 0.994732953f, 0.994742775f, + 0.994752589f, 0.994762393f, 0.994772188f, 0.994781974f, 0.994791751f, + 0.994801519f, 0.994811277f, 0.994821026f, 0.994830767f, 0.994840498f, + 0.994850220f, 0.994859933f, 0.994869636f, 0.994879331f, 0.994889016f, + 0.994898692f, 0.994908359f, 0.994918017f, 0.994927666f, 0.994937306f, + 0.994946936f, 0.994956558f, 0.994966170f, 0.994975773f, 0.994985367f, + 0.994994952f, 0.995004527f, 0.995014094f, 0.995023651f, 0.995033199f, + 0.995042738f, 0.995052268f, 0.995061789f, 0.995071301f, 0.995080803f, + 0.995090297f, 0.995099781f, 0.995109256f, 0.995118722f, 0.995128178f, + 0.995137626f, 0.995147064f, 0.995156494f, 0.995165914f, 0.995175325f, + 0.995184727f, 0.995194119f, 0.995203503f, 0.995212877f, 0.995222243f, + 0.995231599f, 0.995240946f, 0.995250283f, 0.995259612f, 0.995268932f, + 0.995278242f, 0.995287543f, 0.995296835f, 0.995306118f, 0.995315392f, + 0.995324657f, 0.995333912f, 0.995343158f, 0.995352396f, 0.995361624f, + 0.995370843f, 0.995380052f, 0.995389253f, 0.995398444f, 0.995407627f, + 0.995416800f, 0.995425964f, 0.995435119f, 0.995444264f, 0.995453401f, + 0.995462528f, 0.995471646f, 0.995480755f, 0.995489855f, 0.995498946f, + 0.995508028f, 0.995517100f, 0.995526164f, 0.995535218f, 0.995544263f, + 0.995553299f, 0.995562325f, 0.995571343f, 0.995580352f, 0.995589351f, + 0.995598341f, 0.995607322f, 0.995616294f, 0.995625256f, 0.995634210f, + 0.995643154f, 0.995652089f, 0.995661016f, 0.995669932f, 0.995678840f, + 0.995687739f, 0.995696628f, 0.995705509f, 0.995714380f, 0.995723242f, + 0.995732095f, 0.995740938f, 0.995749773f, 0.995758598f, 0.995767414f, + 0.995776222f, 0.995785019f, 0.995793808f, 0.995802588f, 0.995811358f, + 0.995820120f, 0.995828872f, 0.995837615f, 0.995846349f, 0.995855073f, + 0.995863789f, 0.995872495f, 0.995881193f, 0.995889881f, 0.995898560f, + 0.995907229f, 0.995915890f, 0.995924542f, 0.995933184f, 0.995941817f, + 0.995950441f, 0.995959056f, 0.995967662f, 0.995976258f, 0.995984846f, + 0.995993424f, 0.996001993f, 0.996010553f, 0.996019104f, 0.996027645f, + 0.996036178f, 0.996044701f, 0.996053215f, 0.996061720f, 0.996070216f, + 0.996078703f, 0.996087180f, 0.996095648f, 0.996104108f, 0.996112558f, + 0.996120999f, 0.996129430f, 0.996137853f, 0.996146266f, 0.996154671f, + 0.996163066f, 0.996171452f, 0.996179829f, 0.996188196f, 0.996196555f, + 0.996204904f, 0.996213244f, 0.996221575f, 0.996229897f, 0.996238210f, + 0.996246513f, 0.996254808f, 0.996263093f, 0.996271369f, 0.996279636f, + 0.996287894f, 0.996296142f, 0.996304382f, 0.996312612f, 0.996320833f, + 0.996329045f, 0.996337248f, 0.996345442f, 0.996353626f, 0.996361802f, + 0.996369968f, 0.996378125f, 0.996386273f, 0.996394411f, 0.996402541f, + 0.996410661f, 0.996418773f, 0.996426875f, 0.996434968f, 0.996443051f, + 0.996451126f, 0.996459191f, 0.996467248f, 0.996475295f, 0.996483333f, + 0.996491362f, 0.996499381f, 0.996507392f, 0.996515393f, 0.996523385f, + 0.996531368f, 0.996539342f, 0.996547307f, 0.996555262f, 0.996563209f, + 0.996571146f, 0.996579074f, 0.996586993f, 0.996594902f, 0.996602803f, + 0.996610694f, 0.996618577f, 0.996626450f, 0.996634314f, 0.996642168f, + 0.996650014f, 0.996657850f, 0.996665678f, 0.996673496f, 0.996681305f, + 0.996689105f, 0.996696895f, 0.996704677f, 0.996712449f, 0.996720212f, + 0.996727966f, 0.996735711f, 0.996743447f, 0.996751173f, 0.996758890f, + 0.996766599f, 0.996774298f, 0.996781987f, 0.996789668f, 0.996797340f, + 0.996805002f, 0.996812655f, 0.996820299f, 0.996827934f, 0.996835560f, + 0.996843176f, 0.996850784f, 0.996858382f, 0.996865971f, 0.996873551f, + 0.996881122f, 0.996888683f, 0.996896236f, 0.996903779f, 0.996911313f, + 0.996918838f, 0.996926354f, 0.996933860f, 0.996941358f, 0.996948846f, + 0.996956325f, 0.996963795f, 0.996971256f, 0.996978707f, 0.996986150f, + 0.996993583f, 0.997001007f, 0.997008422f, 0.997015828f, 0.997023225f, + 0.997030612f, 0.997037990f, 0.997045360f, 0.997052720f, 0.997060070f, + 0.997067412f, 0.997074744f, 0.997082068f, 0.997089382f, 0.997096687f, + 0.997103983f, 0.997111269f, 0.997118547f, 0.997125815f, 0.997133074f, + 0.997140324f, 0.997147565f, 0.997154797f, 0.997162019f, 0.997169233f, + 0.997176437f, 0.997183632f, 0.997190818f, 0.997197994f, 0.997205162f, + 0.997212320f, 0.997219469f, 0.997226609f, 0.997233740f, 0.997240862f, + 0.997247974f, 0.997255078f, 0.997262172f, 0.997269257f, 0.997276333f, + 0.997283399f, 0.997290457f, 0.997297505f, 0.997304544f, 0.997311574f, + 0.997318595f, 0.997325607f, 0.997332609f, 0.997339602f, 0.997346587f, + 0.997353562f, 0.997360527f, 0.997367484f, 0.997374432f, 0.997381370f, + 0.997388299f, 0.997395219f, 0.997402130f, 0.997409032f, 0.997415924f, + 0.997422807f, 0.997429682f, 0.997436546f, 0.997443402f, 0.997450249f, + 0.997457086f, 0.997463915f, 0.997470734f, 0.997477544f, 0.997484345f, + 0.997491136f, 0.997497919f, 0.997504692f, 0.997511456f, 0.997518211f, + 0.997524957f, 0.997531694f, 0.997538421f, 0.997545139f, 0.997551848f, + 0.997558548f, 0.997565239f, 0.997571921f, 0.997578593f, 0.997585256f, + 0.997591910f, 0.997598555f, 0.997605191f, 0.997611818f, 0.997618435f, + 0.997625043f, 0.997631642f, 0.997638232f, 0.997644813f, 0.997651385f, + 0.997657947f, 0.997664500f, 0.997671044f, 0.997677579f, 0.997684105f, + 0.997690621f, 0.997697129f, 0.997703627f, 0.997710116f, 0.997716596f, + 0.997723067f, 0.997729528f, 0.997735981f, 0.997742424f, 0.997748858f, + 0.997755283f, 0.997761698f, 0.997768105f, 0.997774502f, 0.997780890f, + 0.997787269f, 0.997793639f, 0.997800000f, 0.997806351f, 0.997812693f, + 0.997819026f, 0.997825350f, 0.997831665f, 0.997837971f, 0.997844267f, + 0.997850554f, 0.997856833f, 0.997863101f, 0.997869361f, 0.997875612f, + 0.997881853f, 0.997888085f, 0.997894309f, 0.997900522f, 0.997906727f, + 0.997912923f, 0.997919109f, 0.997925286f, 0.997931454f, 0.997937613f, + 0.997943763f, 0.997949903f, 0.997956035f, 0.997962157f, 0.997968270f, + 0.997974374f, 0.997980468f, 0.997986554f, 0.997992630f, 0.997998697f, + 0.998004755f, 0.998010804f, 0.998016843f, 0.998022874f, 0.998028895f, + 0.998034907f, 0.998040910f, 0.998046904f, 0.998052888f, 0.998058864f, + 0.998064830f, 0.998070787f, 0.998076735f, 0.998082673f, 0.998088603f, + 0.998094523f, 0.998100434f, 0.998106336f, 0.998112229f, 0.998118113f, + 0.998123987f, 0.998129853f, 0.998135709f, 0.998141556f, 0.998147393f, + 0.998153222f, 0.998159041f, 0.998164852f, 0.998170653f, 0.998176445f, + 0.998182227f, 0.998188001f, 0.998193765f, 0.998199521f, 0.998205267f, + 0.998211003f, 0.998216731f, 0.998222450f, 0.998228159f, 0.998233859f, + 0.998239550f, 0.998245232f, 0.998250904f, 0.998256568f, 0.998262222f, + 0.998267867f, 0.998273503f, 0.998279130f, 0.998284747f, 0.998290356f, + 0.998295955f, 0.998301545f, 0.998307126f, 0.998312697f, 0.998318260f, + 0.998323813f, 0.998329357f, 0.998334892f, 0.998340418f, 0.998345935f, + 0.998351442f, 0.998356941f, 0.998362430f, 0.998367910f, 0.998373380f, + 0.998378842f, 0.998384294f, 0.998389737f, 0.998395171f, 0.998400596f, + 0.998406012f, 0.998411418f, 0.998416816f, 0.998422204f, 0.998427583f, + 0.998432953f, 0.998438313f, 0.998443665f, 0.998449007f, 0.998454340f, + 0.998459664f, 0.998464979f, 0.998470284f, 0.998475581f, 0.998480868f, + 0.998486146f, 0.998491415f, 0.998496674f, 0.998501925f, 0.998507166f, + 0.998512398f, 0.998517621f, 0.998522835f, 0.998528039f, 0.998533235f, + 0.998538421f, 0.998543598f, 0.998548766f, 0.998553925f, 0.998559074f, + 0.998564215f, 0.998569346f, 0.998574468f, 0.998579581f, 0.998584684f, + 0.998589779f, 0.998594864f, 0.998599940f, 0.998605007f, 0.998610065f, + 0.998615113f, 0.998620152f, 0.998625183f, 0.998630204f, 0.998635216f, + 0.998640218f, 0.998645212f, 0.998650196f, 0.998655171f, 0.998660137f, + 0.998665094f, 0.998670041f, 0.998674980f, 0.998679909f, 0.998684829f, + 0.998689740f, 0.998694642f, 0.998699534f, 0.998704417f, 0.998709291f, + 0.998714156f, 0.998719012f, 0.998723859f, 0.998728696f, 0.998733524f, + 0.998738344f, 0.998743153f, 0.998747954f, 0.998752746f, 0.998757528f, + 0.998762301f, 0.998767065f, 0.998771820f, 0.998776566f, 0.998781302f, + 0.998786029f, 0.998790747f, 0.998795456f, 0.998800156f, 0.998804846f, + 0.998809528f, 0.998814200f, 0.998818863f, 0.998823517f, 0.998828161f, + 0.998832797f, 0.998837423f, 0.998842040f, 0.998846648f, 0.998851247f, + 0.998855836f, 0.998860417f, 0.998864988f, 0.998869550f, 0.998874103f, + 0.998878646f, 0.998883181f, 0.998887706f, 0.998892222f, 0.998896729f, + 0.998901227f, 0.998905715f, 0.998910195f, 0.998914665f, 0.998919126f, + 0.998923578f, 0.998928020f, 0.998932454f, 0.998936878f, 0.998941293f, + 0.998945699f, 0.998950096f, 0.998954483f, 0.998958862f, 0.998963231f, + 0.998967591f, 0.998971942f, 0.998976283f, 0.998980616f, 0.998984939f, + 0.998989253f, 0.998993558f, 0.998997854f, 0.999002140f, 0.999006418f, + 0.999010686f, 0.999014945f, 0.999019195f, 0.999023435f, 0.999027667f, + 0.999031889f, 0.999036102f, 0.999040306f, 0.999044501f, 0.999048686f, + 0.999052863f, 0.999057030f, 0.999061188f, 0.999065336f, 0.999069476f, + 0.999073607f, 0.999077728f, 0.999081840f, 0.999085943f, 0.999090036f, + 0.999094121f, 0.999098196f, 0.999102262f, 0.999106319f, 0.999110367f, + 0.999114406f, 0.999118435f, 0.999122455f, 0.999126466f, 0.999130468f, + 0.999134461f, 0.999138444f, 0.999142419f, 0.999146384f, 0.999150340f, + 0.999154287f, 0.999158224f, 0.999162153f, 0.999166072f, 0.999169982f, + 0.999173883f, 0.999177774f, 0.999181657f, 0.999185530f, 0.999189394f, + 0.999193249f, 0.999197095f, 0.999200931f, 0.999204759f, 0.999208577f, + 0.999212386f, 0.999216186f, 0.999219976f, 0.999223758f, 0.999227530f, + 0.999231293f, 0.999235047f, 0.999238792f, 0.999242527f, 0.999246253f, + 0.999249971f, 0.999253679f, 0.999257377f, 0.999261067f, 0.999264747f, + 0.999268419f, 0.999272081f, 0.999275733f, 0.999279377f, 0.999283012f, + 0.999286637f, 0.999290253f, 0.999293860f, 0.999297458f, 0.999301046f, + 0.999304626f, 0.999308196f, 0.999311757f, 0.999315309f, 0.999318851f, + 0.999322385f, 0.999325909f, 0.999329424f, 0.999332930f, 0.999336426f, + 0.999339914f, 0.999343392f, 0.999346861f, 0.999350321f, 0.999353772f, + 0.999357214f, 0.999360646f, 0.999364069f, 0.999367483f, 0.999370888f, + 0.999374284f, 0.999377670f, 0.999381048f, 0.999384416f, 0.999387775f, + 0.999391124f, 0.999394465f, 0.999397796f, 0.999401118f, 0.999404431f, + 0.999407735f, 0.999411030f, 0.999414315f, 0.999417591f, 0.999420859f, + 0.999424116f, 0.999427365f, 0.999430605f, 0.999433835f, 0.999437056f, + 0.999440268f, 0.999443471f, 0.999446664f, 0.999449849f, 0.999453024f, + 0.999456190f, 0.999459347f, 0.999462494f, 0.999465633f, 0.999468762f, + 0.999471882f, 0.999474993f, 0.999478094f, 0.999481187f, 0.999484270f, + 0.999487344f, 0.999490409f, 0.999493465f, 0.999496512f, 0.999499549f, + 0.999502577f, 0.999505596f, 0.999508606f, 0.999511607f, 0.999514598f, + 0.999517580f, 0.999520553f, 0.999523517f, 0.999526472f, 0.999529418f, + 0.999532354f, 0.999535281f, 0.999538199f, 0.999541108f, 0.999544007f, + 0.999546898f, 0.999549779f, 0.999552651f, 0.999555514f, 0.999558367f, + 0.999561212f, 0.999564047f, 0.999566873f, 0.999569690f, 0.999572498f, + 0.999575296f, 0.999578085f, 0.999580865f, 0.999583636f, 0.999586398f, + 0.999589151f, 0.999591894f, 0.999594628f, 0.999597353f, 0.999600069f, + 0.999602776f, 0.999605473f, 0.999608161f, 0.999610840f, 0.999613510f, + 0.999616171f, 0.999618822f, 0.999621465f, 0.999624098f, 0.999626722f, + 0.999629337f, 0.999631942f, 0.999634538f, 0.999637126f, 0.999639704f, + 0.999642272f, 0.999644832f, 0.999647382f, 0.999649924f, 0.999652456f, + 0.999654979f, 0.999657492f, 0.999659997f, 0.999662492f, 0.999664978f, + 0.999667455f, 0.999669923f, 0.999672381f, 0.999674831f, 0.999677271f, + 0.999679702f, 0.999682124f, 0.999684536f, 0.999686940f, 0.999689334f, + 0.999691719f, 0.999694095f, 0.999696461f, 0.999698819f, 0.999701167f, + 0.999703506f, 0.999705836f, 0.999708157f, 0.999710468f, 0.999712770f, + 0.999715064f, 0.999717348f, 0.999719622f, 0.999721888f, 0.999724144f, + 0.999726391f, 0.999728629f, 0.999730858f, 0.999733078f, 0.999735288f, + 0.999737489f, 0.999739682f, 0.999741864f, 0.999744038f, 0.999746203f, + 0.999748358f, 0.999750504f, 0.999752641f, 0.999754769f, 0.999756887f, + 0.999758996f, 0.999761097f, 0.999763188f, 0.999765269f, 0.999767342f, + 0.999769405f, 0.999771460f, 0.999773505f, 0.999775540f, 0.999777567f, + 0.999779584f, 0.999781593f, 0.999783592f, 0.999785582f, 0.999787562f, + 0.999789534f, 0.999791496f, 0.999793449f, 0.999795393f, 0.999797328f, + 0.999799254f, 0.999801170f, 0.999803077f, 0.999804975f, 0.999806864f, + 0.999808743f, 0.999810614f, 0.999812475f, 0.999814327f, 0.999816170f, + 0.999818004f, 0.999819828f, 0.999821643f, 0.999823449f, 0.999825246f, + 0.999827034f, 0.999828812f, 0.999830582f, 0.999832342f, 0.999834093f, + 0.999835835f, 0.999837567f, 0.999839291f, 0.999841005f, 0.999842710f, + 0.999844405f, 0.999846092f, 0.999847770f, 0.999849438f, 0.999851097f, + 0.999852747f, 0.999854387f, 0.999856019f, 0.999857641f, 0.999859254f, + 0.999860858f, 0.999862453f, 0.999864038f, 0.999865615f, 0.999867182f, + 0.999868740f, 0.999870288f, 0.999871828f, 0.999873358f, 0.999874879f, + 0.999876391f, 0.999877894f, 0.999879388f, 0.999880872f, 0.999882347f, + 0.999883813f, 0.999885270f, 0.999886718f, 0.999888156f, 0.999889586f, + 0.999891006f, 0.999892417f, 0.999893818f, 0.999895211f, 0.999896594f, + 0.999897968f, 0.999899333f, 0.999900689f, 0.999902036f, 0.999903373f, + 0.999904701f, 0.999906020f, 0.999907330f, 0.999908630f, 0.999909922f, + 0.999911204f, 0.999912477f, 0.999913741f, 0.999914996f, 0.999916241f, + 0.999917477f, 0.999918704f, 0.999919922f, 0.999921131f, 0.999922330f, + 0.999923521f, 0.999924702f, 0.999925874f, 0.999927036f, 0.999928190f, + 0.999929334f, 0.999930470f, 0.999931596f, 0.999932712f, 0.999933820f, + 0.999934918f, 0.999936007f, 0.999937087f, 0.999938158f, 0.999939220f, + 0.999940272f, 0.999941316f, 0.999942350f, 0.999943375f, 0.999944390f, + 0.999945397f, 0.999946394f, 0.999947382f, 0.999948361f, 0.999949331f, + 0.999950291f, 0.999951243f, 0.999952185f, 0.999953118f, 0.999954041f, + 0.999954956f, 0.999955861f, 0.999956758f, 0.999957645f, 0.999958522f, + 0.999959391f, 0.999960250f, 0.999961101f, 0.999961942f, 0.999962774f, + 0.999963596f, 0.999964410f, 0.999965214f, 0.999966009f, 0.999966795f, + 0.999967572f, 0.999968339f, 0.999969097f, 0.999969846f, 0.999970586f, + 0.999971317f, 0.999972039f, 0.999972751f, 0.999973454f, 0.999974148f, + 0.999974833f, 0.999975509f, 0.999976175f, 0.999976832f, 0.999977480f, + 0.999978119f, 0.999978749f, 0.999979369f, 0.999979980f, 0.999980582f, + 0.999981175f, 0.999981759f, 0.999982333f, 0.999982899f, 0.999983455f, + 0.999984002f, 0.999984539f, 0.999985068f, 0.999985587f, 0.999986097f, + 0.999986598f, 0.999987090f, 0.999987573f, 0.999988046f, 0.999988510f, + 0.999988965f, 0.999989411f, 0.999989848f, 0.999990275f, 0.999990693f, + 0.999991102f, 0.999991502f, 0.999991893f, 0.999992274f, 0.999992647f, + 0.999993010f, 0.999993364f, 0.999993708f, 0.999994044f, 0.999994370f, + 0.999994687f, 0.999994995f, 0.999995294f, 0.999995583f, 0.999995864f, + 0.999996135f, 0.999996397f, 0.999996650f, 0.999996893f, 0.999997128f, + 0.999997353f, 0.999997569f, 0.999997776f, 0.999997973f, 0.999998162f, + 0.999998341f, 0.999998511f, 0.999998672f, 0.999998823f, 0.999998966f, + 0.999999099f, 0.999999223f, 0.999999338f, 0.999999444f, 0.999999540f, + 0.999999628f, 0.999999706f, 0.999999775f, 0.999999835f, 0.999999885f, + 0.999999926f, 0.999999959f, 0.999999982f, 0.999999995f, 1.000000000f}; + +} // namespace math +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/math/vec2d.cc b/apollo_common/src/math/vec2d.cc new file mode 100644 index 0000000..67c26be --- /dev/null +++ b/apollo_common/src/math/vec2d.cc @@ -0,0 +1,138 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/math/vec2d.h" + +#include +#include + +#include "apollo_common/log.h" + +namespace apollo { +namespace common { +namespace math { + +Vec2d Vec2d::CreateUnitVec2d(const double angle) { + return Vec2d(cos(angle), sin(angle)); +} + +double Vec2d::Length() const { return std::hypot(x_, y_); } + +double Vec2d::LengthSquare() const { return x_ * x_ + y_ * y_; } + +double Vec2d::Angle() const { return std::atan2(y_, x_); } + +void Vec2d::Normalize() { + const double l = Length(); + if (l > kMathEpsilon) { + x_ /= l; + y_ /= l; + } +} + +double Vec2d::DistanceTo(const Vec2d& other) const { + return std::hypot(x_ - other.x_, y_ - other.y_); +} + +double Vec2d::DistanceSquareTo(const Vec2d& other) const { + const double dx = x_ - other.x_; + const double dy = y_ - other.y_; + return dx * dx + dy * dy; +} + +double Vec2d::CrossProd(const Vec2d& other) const { + return x_ * other.y() - y_ * other.x(); +} + +double Vec2d::InnerProd(const Vec2d& other) const { + return x_ * other.x() + y_ * other.y(); +} + +Vec2d Vec2d::operator+(const Vec2d& other) const { + return Vec2d(x_ + other.x(), y_ + other.y()); +} + +Vec2d Vec2d::operator-(const Vec2d& other) const { + return Vec2d(x_ - other.x(), y_ - other.y()); +} + +Vec2d Vec2d::operator*(const double ratio) const { + return Vec2d(x_ * ratio, y_ * ratio); +} + +Vec2d Vec2d::operator/(const double ratio) const { + CHECK_GT(std::abs(ratio), kMathEpsilon); + return Vec2d(x_ / ratio, y_ / ratio); +} + +Vec2d& Vec2d::operator+=(const Vec2d& other) { + x_ += other.x(); + y_ += other.y(); + return *this; +} + +Vec2d& Vec2d::operator-=(const Vec2d& other) { + x_ -= other.x(); + y_ -= other.y(); + return *this; +} + +Vec2d& Vec2d::operator*=(const double ratio) { + x_ *= ratio; + y_ *= ratio; + return *this; +} + +Vec2d& Vec2d::operator/=(const double ratio) { + CHECK_GT(std::abs(ratio), kMathEpsilon); + x_ /= ratio; + y_ /= ratio; + return *this; +} + +bool Vec2d::operator==(const Vec2d& other) const { + return (std::abs(x_ - other.x()) < kMathEpsilon && + std::abs(y_ - other.y()) < kMathEpsilon); +} + +Vec2d operator*(const double ratio, const Vec2d& vec) { return vec * ratio; } + +std::string Vec2d::DebugString() const { + std::ostringstream sout; + sout << "vec2d ( x = " << x_ << " y = " << y_ << " )"; + sout.flush(); + return sout.str(); +} + +} // namespace math +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/monitor/monitor.cc b/apollo_common/src/monitor/monitor.cc new file mode 100644 index 0000000..175f48e --- /dev/null +++ b/apollo_common/src/monitor/monitor.cc @@ -0,0 +1,70 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/monitor/monitor.h" + +#include "apollo_common/adapters/adapter_manager.h" +#include "apollo_common/time/time.h" + +namespace apollo { +namespace common { +namespace monitor { + +using apollo::common::adapter::AdapterManager; +using apollo::common::time::Clock; + +void Monitor::Publish(const std::vector &messages) const { + // compose a monitor message + if (messages.empty()) { + return; + } + MonitorMessage monitor_msg; + + for (const auto &msg_item : messages) { + MonitorMessageItem *monitor_msg_item = monitor_msg.add_item(); + monitor_msg_item->set_source(source_); + monitor_msg_item->set_log_level(msg_item.first); + monitor_msg_item->set_msg(msg_item.second); + } + + // publish monitor messages + DoPublish(&monitor_msg); +} + +void Monitor::DoPublish(MonitorMessage *message) const { + AdapterManager::FillMonitorHeader("monitor", message->mutable_header()); + AdapterManager::PublishMonitor(*message); +} + +} // namespace monitor +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/monitor/monitor_buffer.cc b/apollo_common/src/monitor/monitor_buffer.cc new file mode 100644 index 0000000..86e26a9 --- /dev/null +++ b/apollo_common/src/monitor/monitor_buffer.cc @@ -0,0 +1,109 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/monitor/monitor_buffer.h" + +#include "apollo_common/adapters/adapter_manager.h" +#include "apollo_common/log.h" +#include "apollo_common/monitor/monitor.h" +#include "apollo_common/time/time.h" + +namespace apollo { +namespace common { +namespace monitor { + +using apollo::common::adapter::AdapterManager; +using apollo::common::time::Clock; + +MonitorBuffer::MonitorBuffer(Monitor* monitor) : monitor_(monitor) {} + +void MonitorBuffer::PrintLog() { + if (monitor_msg_items_.empty()) { + return; + } + const auto level = monitor_msg_items_.back().first; + const auto& msg = monitor_msg_items_.back().second; + switch (level) { + case MonitorMessageItem::INFO: + AINFO << msg; + break; + case MonitorMessageItem::WARN: + AWARN << msg; + break; + case MonitorMessageItem::ERROR: + AERROR << msg; + break; + case MonitorMessageItem::FATAL: + AFATAL << msg; + break; + default: + AERROR << "[unknown monitor level]: " << msg; + } +} + +void MonitorBuffer::Publish() { + if (!monitor_msg_items_.empty() && monitor_) { + monitor_->Publish(monitor_msg_items_); + monitor_msg_items_.clear(); + level_ = MonitorMessageItem::INFO; + } +} + +MonitorBuffer& MonitorBuffer::operator<<(const std::string& msg) { + if (monitor_msg_items_.empty() || monitor_msg_items_.back().first != level_) { + AddMonitorMsgItem(level_, msg); + } else { + monitor_msg_items_.back().second += msg; + } + return *this; +} + +MonitorBuffer& MonitorBuffer::operator<<(const char* msg) { + if (msg) { + std::string msg_str(msg); + return operator<<(msg_str); + } else { + return *this; + } +} + +MonitorBuffer::~MonitorBuffer() { Publish(); } + +void MonitorBuffer::AddMonitorMsgItem( + const MonitorMessageItem::LogLevel log_level, const std::string& msg) { + level_ = log_level; + monitor_msg_items_.push_back(std::make_pair(log_level, msg)); +} + +} // namespace monitor +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/util/file.cc b/apollo_common/src/util/file.cc new file mode 100644 index 0000000..4fd9a13 --- /dev/null +++ b/apollo_common/src/util/file.cc @@ -0,0 +1,107 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/util/file.h" + +#include +#include +#include + +namespace apollo { +namespace common { +namespace util { + +bool DirectoryExists(const std::string &directory_path) { + struct stat info; + if (stat(directory_path.c_str(), &info) != 0) { + return false; + } + + if (info.st_mode & S_IFDIR) { + return true; + } + + return false; +} + +bool EnsureDirectory(const std::string &directory_path) { + std::string path = directory_path; + for (size_t i = 1; i < directory_path.size(); ++i) { + if (directory_path[i] == '/') { + // Whenever a '/' is encountered, create a temporary view from + // the start of the path to the character right before this. + path[i] = 0; + + if (mkdir(path.c_str(), S_IRWXU) != 0) { + if (errno != EEXIST) { + return false; + } + } + + // Revert the temporary view back to the original. + path[i] = '/'; + } + } + + // Make the final (full) directory. + if (mkdir(path.c_str(), S_IRWXU) != 0) { + if (errno != EEXIST) { + return false; + } + } + + return true; +} + +bool RemoveAllFiles(const std::string &directory_path) { + DIR *directory = opendir(directory_path.c_str()); + struct dirent *file; + while ((file = readdir(directory)) != NULL) { + // skip directory_path/. and directory_path/.. + if (!strcmp(file->d_name, ".") || !strcmp(file->d_name, "..")) { + continue; + } + // build the path for each file in the folder + std::string file_path = directory_path + "/" + file->d_name; + if (unlink(file_path.c_str()) < 0) { + AERROR << "Fail to remove file " << file_path << ": " << strerror(errno); + closedir(directory); + return false; + } + } + closedir(directory); + return true; +} + +} // namespace util +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/util/string_tokenizer.cc b/apollo_common/src/util/string_tokenizer.cc new file mode 100644 index 0000000..a407e0b --- /dev/null +++ b/apollo_common/src/util/string_tokenizer.cc @@ -0,0 +1,74 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/util/string_tokenizer.h" + +namespace apollo { +namespace common { +namespace util { + +StringTokenizer::StringTokenizer(const std::string& s, + const std::string& delims) { + s_ = s; + delims_ = delims; + + last_index_ = s_.find_first_not_of(delims, 0); + index_ = s_.find_first_of(delims, last_index_); +} + +std::vector StringTokenizer::Split(const std::string& str, + const std::string& delims) { + std::vector tokens; + std::string::size_type last_index = str.find_first_not_of(delims, 0); + std::string::size_type index = str.find_first_of(delims, last_index); + + while (std::string::npos != index || std::string::npos != last_index) { + tokens.push_back(str.substr(last_index, index - last_index)); + last_index = str.find_first_not_of(delims, index); + index = str.find_first_of(delims, last_index); + } + return tokens; +} + +std::string StringTokenizer::Next() { + if (std::string::npos != index_ || std::string::npos != last_index_) { + auto token = s_.substr(last_index_, index_ - last_index_); + last_index_ = s_.find_first_not_of(delims_, index_); + index_ = s_.find_first_of(delims_, last_index_); + return token; + } + return ""; +} + +} // namespace util +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/util/util.cc b/apollo_common/src/util/util.cc new file mode 100644 index 0000000..5122aa0 --- /dev/null +++ b/apollo_common/src/util/util.cc @@ -0,0 +1,46 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/util/util.h" + +namespace apollo { +namespace common { +namespace util { + +bool EndWith(const std::string& original, const std::string& pattern) { + return original.length() >= pattern.length() && + original.substr(original.length() - pattern.length()) == pattern; +} + +} // namespace util +} // namespace common +} // namespace apollo diff --git a/apollo_common/src/vehicle_state/vehicle_state.cc b/apollo_common/src/vehicle_state/vehicle_state.cc new file mode 100644 index 0000000..8016714 --- /dev/null +++ b/apollo_common/src/vehicle_state/vehicle_state.cc @@ -0,0 +1,171 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/vehicle_state/vehicle_state.h" + +#include + +#include "apollo_common/math/quaternion.h" +#include "apollo_common/log.h" + +// #include "modules/localization/common/localization_gflags.h" + +namespace apollo { +namespace common { +namespace vehicle_state { + +VehicleState::VehicleState( + const localization::LocalizationEstimate &localization) { + ConstructExceptLinearVelocity(&localization); + if (localization.has_pose() && localization.pose().has_linear_velocity()) { + linear_v_ = localization.pose().linear_velocity().y(); + } +} + +VehicleState::VehicleState( + const localization::LocalizationEstimate *localization, + const canbus::Chassis *chassis) { + ConstructExceptLinearVelocity(localization); + if (chassis != nullptr) { + linear_v_ = chassis->speed_mps(); + } +} + +void VehicleState::ConstructExceptLinearVelocity( + const localization::LocalizationEstimate *localization) { + if (localization == nullptr || !localization->has_pose()) { + AERROR << "Invalid localization input."; + return; + } + localization_ptr_ = localization; + if (localization->pose().has_position()) { + x_ = localization->pose().position().x(); + y_ = localization->pose().position().y(); + z_ = localization->pose().position().z(); + } + + const auto &orientation = localization->pose().orientation(); + heading_ = ::apollo::common::math::QuaternionToHeading( + orientation.qw(), orientation.qx(), orientation.qy(), orientation.qz()); + + // if (FLAGS_enable_map_reference_unify) { + // angular_v_ = localization->pose().angular_velocity_vrf().z(); + // linear_a_ = localization->pose().linear_acceleration_vrf().y(); + // } else + { + angular_v_ = localization->pose().angular_velocity().z(); + linear_a_ = localization->pose().linear_acceleration().y(); + } +} + +double VehicleState::x() const { return x_; } + +double VehicleState::y() const { return y_; } + +double VehicleState::z() const { return z_; } + +double VehicleState::heading() const { return heading_; } + +double VehicleState::linear_velocity() const { return linear_v_; } + +double VehicleState::angular_velocity() const { return angular_v_; } + +double VehicleState::linear_acceleration() const { return linear_a_; } + +void VehicleState::set_x(const double x) { x_ = x; } + +void VehicleState::set_y(const double y) { y_ = y; } + +void VehicleState::set_z(const double z) { z_ = z; } + +void VehicleState::set_heading(const double heading) { heading_ = heading; } + +void VehicleState::set_linear_velocity(const double linear_velocity) { + linear_v_ = linear_velocity; +} + +void VehicleState::set_angular_velocity(const double angular_velocity) { + angular_v_ = angular_velocity; +} + +Eigen::Vector2d VehicleState::EstimateFuturePosition(const double t) const { + Eigen::Vector3d vec_distance(0.0, 0.0, 0.0); + // Predict distance travel vector + if (std::fabs(angular_v_) < 0.0001) { + vec_distance[0] = 0.0; + vec_distance[1] = linear_v_ * t; + } else { + vec_distance[0] = + -linear_v_ / angular_v_ * (1.0 - std::cos(angular_v_ * t)); + vec_distance[1] = std::sin(angular_v_ * t) * linear_v_ / angular_v_; + } + + // If we have rotation information, take it into consideration. + if (localization_ptr_ != nullptr && localization_ptr_->has_pose() && + localization_ptr_->pose().has_orientation()) { + const auto &orientation = localization_ptr_->pose().orientation(); + Eigen::Quaternion quaternion(orientation.qw(), orientation.qx(), + orientation.qy(), orientation.qz()); + Eigen::Vector3d pos_vec(x_, y_, z_); + auto future_pos_3d = quaternion.toRotationMatrix() * vec_distance + pos_vec; + return Eigen::Vector2d(future_pos_3d[0], future_pos_3d[1]); + } + + // If no valid rotation information provided from localization, + // return the estimated future position without rotation. + return Eigen::Vector2d(vec_distance[0] + x_, vec_distance[1] + y_); +} + +Eigen::Vector2d VehicleState::ComputeCOMPosition( + const double rear_to_com_distance) const { + // set length as distance between rear wheel and center of mass. + Eigen::Vector3d v(0.0, rear_to_com_distance, 0.0); + Eigen::Vector3d pos_vec(x_, y_, z_); + // Initialize the COM position without rotation + Eigen::Vector3d com_pos_3d = v + pos_vec; + + // If we have rotation information, take it into consideration. + if (localization_ptr_ != nullptr && localization_ptr_->has_pose() && + localization_ptr_->pose().has_orientation()) { + const auto &orientation = localization_ptr_->pose().orientation(); + Eigen::Quaternion quaternion(orientation.qw(), orientation.qx(), + orientation.qy(), orientation.qz()); + // Update the COM position with rotation + com_pos_3d = quaternion.toRotationMatrix() * v + pos_vec; + } + + return Eigen::Vector2d(com_pos_3d[0], com_pos_3d[1]); +} + +} // namespace vehicle_state +} // namespace common +} // namespace apollo diff --git a/apollo_control/CMakeLists.txt b/apollo_control/CMakeLists.txt new file mode 100644 index 0000000..2dee4d6 --- /dev/null +++ b/apollo_control/CMakeLists.txt @@ -0,0 +1,62 @@ +cmake_minimum_required(VERSION 3.0.2) +project(apollo_control) + +add_compile_options(-std=c++17) +# set(CMAKE_BUILD_TYPE "Debug") +set(CMAKE_BUILD_TYPE "Release") + +find_package(Eigen3 REQUIRED) + +find_package(catkin REQUIRED COMPONENTS + roscpp + apollo_msgs + apollo_common +) + +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES apollo_control +# CATKIN_DEPENDS roscpp +# DEPENDS system_lib +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIR} +) + +add_executable(${PROJECT_NAME} + src/main.cc + src/control.cc + # common + src/common/control_gflags.cc + src/common/hysteresis_filter.cc + src/common/interpolation_2d.cc + src/common/pid_controller.cc + src/common/trajectory_analyzer.cc + # controller + src/controller/controller_agent.cc + src/controller/lat_controller.cc + src/controller/lon_controller.cc + # filters + src/filters/digital_filter_coefficients.cc + src/filters/digital_filter.cc + src/filters/mean_filter.cc +) +add_dependencies(${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} + protobuf + glog + gflags +) + +# install +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) \ No newline at end of file diff --git a/apollo_control/README.md b/apollo_control/README.md new file mode 100644 index 0000000..e075608 --- /dev/null +++ b/apollo_control/README.md @@ -0,0 +1,13 @@ +# Control + +## Introduction + Based on planning and current car status, use different control algorithms to + generate comfortable driving experience. + +## Input + * Planning trajectory + * Car status + * HMI AUTO mode change request + +## Output + * control command (steering, throttle, brake) to canbus. \ No newline at end of file diff --git a/apollo_control/conf/adapter.conf b/apollo_control/conf/adapter.conf new file mode 100644 index 0000000..922be32 --- /dev/null +++ b/apollo_control/conf/adapter.conf @@ -0,0 +1,31 @@ +config { + type: LOCALIZATION + mode: RECEIVE_ONLY + message_history_limit: 10 +} +config { + type: PAD + mode: RECEIVE_ONLY + message_history_limit: 10 +} +config { + type: PLANNING_TRAJECTORY + mode: RECEIVE_ONLY + message_history_limit: 10 +} +config { + type: CHASSIS + mode: RECEIVE_ONLY + message_history_limit: 10 +} +config { + type: CONTROL_COMMAND + mode: PUBLISH_ONLY + message_history_limit: 10 +} +config { + type: MONITOR + mode: DUPLEX + message_history_limit: 1 +} +is_ros: true diff --git a/apollo_control/conf/control.conf b/apollo_control/conf/control.conf new file mode 100644 index 0000000..1393d56 --- /dev/null +++ b/apollo_control/conf/control.conf @@ -0,0 +1,12 @@ +--enable_csv_debug +--use_state_exact_match +--noenable_speed_station_preview +--noenable_interpolation_by_time +--noenable_control_watchdog +--v=3 +--nouse_preview_speed_for_table +--noenable_input_timestamp_check + +# glog +--colorlogtostderr=1 +--stderrthreshold=0 diff --git a/apollo_control/conf/lincoln.pb.txt b/apollo_control/conf/lincoln.pb.txt new file mode 100644 index 0000000..3d7fefc --- /dev/null +++ b/apollo_control/conf/lincoln.pb.txt @@ -0,0 +1,6560 @@ +control_period: 0.01 +trajectory_period: 0.1 +chassis_period: 0.01 +localization_period: 0.01 +max_status_interval_sec: 0.1 +max_planning_interval_sec: 0.2 +max_planning_delay_threshold: 4.0 +action: STOP +soft_estop_brake: 50.0 +active_controllers: LAT_CONTROLLER +active_controllers: LON_CONTROLLER +max_steering_percentage_allowed: 100 +lat_controller_conf { + ts: 0.01 + preview_window: 0 + cf: 155494.663 + cr: 155494.663 + wheelbase: 2.85 + mass_fl: 520 + mass_fr: 520 + mass_rl: 520 + mass_rr: 520 + eps: 0.01 + matrix_q: 0.05 + matrix_q: 0.0 + matrix_q: 1.0 + matrix_q: 0.0 + cutoff_freq: 10 + mean_filter_window_size: 10 + steer_transmission_ratio: 16 + steer_single_direction_max_degree: 470 + max_iteration: 150 +} +lon_controller_conf { + ts: 0.01 + brake_deadzone: 15.5 + throttle_deadzone: 18.0 + speed_controller_input_limit: 2.0 + station_error_limit: 2.0 + preview_window: 20.0 + standstill_acceleration: -3.0 + station_pid_conf { + integrator_enable: false + integrator_saturation_level: 0.3 + kp: 0.2 + ki: 0.0 + kd: 0.0 + } + low_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 0.5 + ki: 0.3 + kd: 0.0 + } + high_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 1.0 + ki: 0.3 + kd: 0.0 + } + switch_speed: 2.0 + throttle_filter_conf { + cutoff_freq: 10 + } + brake_filter_conf { + cutoff_freq: 10 + } + acceleration_filter_conf { + cutoff_freq: 5 + } + calibration_table { + calibration { + speed: 0.0 + acceleration: -1.43 + command: -35.0 + } + calibration { + speed: 0.0 + acceleration: -1.28 + command: -27.0 + } + calibration { + speed: 0.0 + acceleration: -1.17 + command: -25.0 + } + calibration { + speed: 0.0 + acceleration: -1.02 + command: -30.0 + } + calibration { + speed: 0.0 + acceleration: -0.48 + command: -27.5 + } + calibration { + speed: 0.0 + acceleration: 0.09 + command: -20.0 + } + calibration { + speed: 0.0 + acceleration: 0.32 + command: -15.0 + } + calibration { + speed: 0.0 + acceleration: 0.35 + command: -17.0 + } + calibration { + speed: 0.0 + acceleration: 0.37 + command: 17.0 + } + calibration { + speed: 0.0 + acceleration: 0.39 + command: 15.0 + } + calibration { + speed: 0.0 + acceleration: 0.41 + command: -13.0 + } + calibration { + speed: 0.0 + acceleration: 0.72 + command: 20.0 + } + calibration { + speed: 0.0 + acceleration: 0.97 + command: 22.0 + } + calibration { + speed: 0.0 + acceleration: 1.4 + command: 25.0 + } + calibration { + speed: 0.0 + acceleration: 1.43 + command: 27.0 + } + calibration { + speed: 0.0 + acceleration: 1.53 + command: 30.0 + } + calibration { + speed: 0.0 + acceleration: 1.65 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 1.79 + command: 40.0 + } + calibration { + speed: 0.0 + acceleration: 1.89 + command: 45.0 + } + calibration { + speed: 0.0 + acceleration: 1.94 + command: 50.0 + } + calibration { + speed: 0.0 + acceleration: 2.03 + command: 55.0 + } + calibration { + speed: 0.0 + acceleration: 2.08 + command: 65.0 + } + calibration { + speed: 0.0 + acceleration: 2.11 + command: 60.0 + } + calibration { + speed: 0.0 + acceleration: 2.3 + command: 80.0 + } + calibration { + speed: 0.0 + acceleration: 2.33 + command: 70.0 + } + calibration { + speed: 0.0 + acceleration: 2.34 + command: 75.0 + } + calibration { + speed: 0.2 + acceleration: -1.87 + command: -35.0 + } + calibration { + speed: 0.2 + acceleration: -1.41 + command: -27.0 + } + calibration { + speed: 0.2 + acceleration: -1.25 + command: -30.0 + } + calibration { + speed: 0.2 + acceleration: -1.22 + command: -25.0 + } + calibration { + speed: 0.2 + acceleration: -0.87 + command: -33.0 + } + calibration { + speed: 0.2 + acceleration: -0.48 + command: -22.0 + } + calibration { + speed: 0.2 + acceleration: 0.09 + command: -20.0 + } + calibration { + speed: 0.2 + acceleration: 0.32 + command: -15.0 + } + calibration { + speed: 0.2 + acceleration: 0.36 + command: -17.0 + } + calibration { + speed: 0.2 + acceleration: 0.38 + command: 17.0 + } + calibration { + speed: 0.2 + acceleration: 0.39 + command: 15.0 + } + calibration { + speed: 0.2 + acceleration: 0.41 + command: -13.0 + } + calibration { + speed: 0.2 + acceleration: 0.74 + command: 20.0 + } + calibration { + speed: 0.2 + acceleration: 0.98 + command: 22.0 + } + calibration { + speed: 0.2 + acceleration: 1.43 + command: 25.0 + } + calibration { + speed: 0.2 + acceleration: 1.48 + command: 27.0 + } + calibration { + speed: 0.2 + acceleration: 1.59 + command: 30.0 + } + calibration { + speed: 0.2 + acceleration: 1.72 + command: 35.0 + } + calibration { + speed: 0.2 + acceleration: 1.87 + command: 40.0 + } + calibration { + speed: 0.2 + acceleration: 1.98 + command: 45.0 + } + calibration { + speed: 0.2 + acceleration: 2.03 + command: 50.0 + } + calibration { + speed: 0.2 + acceleration: 2.15 + command: 55.0 + } + calibration { + speed: 0.2 + acceleration: 2.22 + command: 65.0 + } + calibration { + speed: 0.2 + acceleration: 2.23 + command: 60.0 + } + calibration { + speed: 0.2 + acceleration: 2.44 + command: 80.0 + } + calibration { + speed: 0.2 + acceleration: 2.45 + command: 70.0 + } + calibration { + speed: 0.2 + acceleration: 2.47 + command: 75.0 + } + calibration { + speed: 0.4 + acceleration: -6.89 + command: -35.0 + } + calibration { + speed: 0.4 + acceleration: -5.78 + command: -33.0 + } + calibration { + speed: 0.4 + acceleration: -4.19 + command: -30.0 + } + calibration { + speed: 0.4 + acceleration: -2.88 + command: -27.0 + } + calibration { + speed: 0.4 + acceleration: -1.77 + command: -25.0 + } + calibration { + speed: 0.4 + acceleration: -0.48 + command: -22.0 + } + calibration { + speed: 0.4 + acceleration: 0.01 + command: -20.0 + } + calibration { + speed: 0.4 + acceleration: 0.31 + command: -15.0 + } + calibration { + speed: 0.4 + acceleration: 0.35 + command: 15.0 + } + calibration { + speed: 0.4 + acceleration: 0.38 + command: -17.0 + } + calibration { + speed: 0.4 + acceleration: 0.4 + command: -13.0 + } + calibration { + speed: 0.4 + acceleration: 0.43 + command: 17.0 + } + calibration { + speed: 0.4 + acceleration: 0.82 + command: 20.0 + } + calibration { + speed: 0.4 + acceleration: 1.07 + command: 22.0 + } + calibration { + speed: 0.4 + acceleration: 1.57 + command: 25.0 + } + calibration { + speed: 0.4 + acceleration: 1.66 + command: 27.0 + } + calibration { + speed: 0.4 + acceleration: 1.78 + command: 30.0 + } + calibration { + speed: 0.4 + acceleration: 1.94 + command: 35.0 + } + calibration { + speed: 0.4 + acceleration: 2.12 + command: 40.0 + } + calibration { + speed: 0.4 + acceleration: 2.22 + command: 45.0 + } + calibration { + speed: 0.4 + acceleration: 2.24 + command: 50.0 + } + calibration { + speed: 0.4 + acceleration: 2.43 + command: 55.0 + } + calibration { + speed: 0.4 + acceleration: 2.47 + command: 60.0 + } + calibration { + speed: 0.4 + acceleration: 2.54 + command: 65.0 + } + calibration { + speed: 0.4 + acceleration: 2.67 + command: 75.0 + } + calibration { + speed: 0.4 + acceleration: 2.68 + command: 70.0 + } + calibration { + speed: 0.4 + acceleration: 2.71 + command: 80.0 + } + calibration { + speed: 0.6 + acceleration: -8.63 + command: -35.0 + } + calibration { + speed: 0.6 + acceleration: -7.54 + command: -33.0 + } + calibration { + speed: 0.6 + acceleration: -5.04 + command: -30.0 + } + calibration { + speed: 0.6 + acceleration: -2.98 + command: -27.0 + } + calibration { + speed: 0.6 + acceleration: -1.66 + command: -25.0 + } + calibration { + speed: 0.6 + acceleration: -0.5 + command: -22.0 + } + calibration { + speed: 0.6 + acceleration: 0.02 + command: -20.0 + } + calibration { + speed: 0.6 + acceleration: 0.31 + command: -15.0 + } + calibration { + speed: 0.6 + acceleration: 0.35 + command: -13.0 + } + calibration { + speed: 0.6 + acceleration: 0.36 + command: 15.0 + } + calibration { + speed: 0.6 + acceleration: 0.38 + command: -17.0 + } + calibration { + speed: 0.6 + acceleration: 0.43 + command: 17.0 + } + calibration { + speed: 0.6 + acceleration: 0.85 + command: 20.0 + } + calibration { + speed: 0.6 + acceleration: 1.18 + command: 22.0 + } + calibration { + speed: 0.6 + acceleration: 1.71 + command: 25.0 + } + calibration { + speed: 0.6 + acceleration: 1.85 + command: 27.0 + } + calibration { + speed: 0.6 + acceleration: 1.96 + command: 30.0 + } + calibration { + speed: 0.6 + acceleration: 2.16 + command: 35.0 + } + calibration { + speed: 0.6 + acceleration: 2.34 + command: 40.0 + } + calibration { + speed: 0.6 + acceleration: 2.37 + command: 50.0 + } + calibration { + speed: 0.6 + acceleration: 2.4 + command: 45.0 + } + calibration { + speed: 0.6 + acceleration: 2.57 + command: 60.0 + } + calibration { + speed: 0.6 + acceleration: 2.61 + command: 55.0 + } + calibration { + speed: 0.6 + acceleration: 2.72 + command: 65.0 + } + calibration { + speed: 0.6 + acceleration: 2.77 + command: 72.5 + } + calibration { + speed: 0.6 + acceleration: 2.8 + command: 80.0 + } + calibration { + speed: 0.8 + acceleration: -9.18 + command: -35.0 + } + calibration { + speed: 0.8 + acceleration: -8.26 + command: -33.0 + } + calibration { + speed: 0.8 + acceleration: -5.13 + command: -30.0 + } + calibration { + speed: 0.8 + acceleration: -2.78 + command: -27.0 + } + calibration { + speed: 0.8 + acceleration: -1.71 + command: -25.0 + } + calibration { + speed: 0.8 + acceleration: -0.48 + command: -22.0 + } + calibration { + speed: 0.8 + acceleration: 0.01 + command: -20.0 + } + calibration { + speed: 0.8 + acceleration: 0.29 + command: -15.0 + } + calibration { + speed: 0.8 + acceleration: 0.31 + command: 1.0 + } + calibration { + speed: 0.8 + acceleration: 0.35 + command: -17.0 + } + calibration { + speed: 0.8 + acceleration: 0.37 + command: 17.0 + } + calibration { + speed: 0.8 + acceleration: 0.87 + command: 20.0 + } + calibration { + speed: 0.8 + acceleration: 1.23 + command: 22.0 + } + calibration { + speed: 0.8 + acceleration: 1.82 + command: 25.0 + } + calibration { + speed: 0.8 + acceleration: 1.99 + command: 27.0 + } + calibration { + speed: 0.8 + acceleration: 2.1 + command: 30.0 + } + calibration { + speed: 0.8 + acceleration: 2.34 + command: 35.0 + } + calibration { + speed: 0.8 + acceleration: 2.46 + command: 50.0 + } + calibration { + speed: 0.8 + acceleration: 2.52 + command: 42.5 + } + calibration { + speed: 0.8 + acceleration: 2.61 + command: 60.0 + } + calibration { + speed: 0.8 + acceleration: 2.7 + command: 55.0 + } + calibration { + speed: 0.8 + acceleration: 2.73 + command: 70.0 + } + calibration { + speed: 0.8 + acceleration: 2.74 + command: 75.0 + } + calibration { + speed: 0.8 + acceleration: 2.76 + command: 65.0 + } + calibration { + speed: 0.8 + acceleration: 2.78 + command: 80.0 + } + calibration { + speed: 1.0 + acceleration: -9.17 + command: -35.0 + } + calibration { + speed: 1.0 + acceleration: -8.44 + command: -33.0 + } + calibration { + speed: 1.0 + acceleration: -4.97 + command: -30.0 + } + calibration { + speed: 1.0 + acceleration: -2.72 + command: -27.0 + } + calibration { + speed: 1.0 + acceleration: -1.74 + command: -25.0 + } + calibration { + speed: 1.0 + acceleration: -0.5 + command: -22.0 + } + calibration { + speed: 1.0 + acceleration: -0.07 + command: -20.0 + } + calibration { + speed: 1.0 + acceleration: 0.21 + command: -15.0 + } + calibration { + speed: 1.0 + acceleration: 0.27 + command: -13.0 + } + calibration { + speed: 1.0 + acceleration: 0.28 + command: -1.0 + } + calibration { + speed: 1.0 + acceleration: 0.32 + command: 17.0 + } + calibration { + speed: 1.0 + acceleration: 0.89 + command: 20.0 + } + calibration { + speed: 1.0 + acceleration: 1.25 + command: 22.0 + } + calibration { + speed: 1.0 + acceleration: 1.89 + command: 25.0 + } + calibration { + speed: 1.0 + acceleration: 2.09 + command: 27.0 + } + calibration { + speed: 1.0 + acceleration: 2.2 + command: 30.0 + } + calibration { + speed: 1.0 + acceleration: 2.49 + command: 35.0 + } + calibration { + speed: 1.0 + acceleration: 2.56 + command: 50.0 + } + calibration { + speed: 1.0 + acceleration: 2.62 + command: 45.0 + } + calibration { + speed: 1.0 + acceleration: 2.66 + command: 40.0 + } + calibration { + speed: 1.0 + acceleration: 2.67 + command: 60.0 + } + calibration { + speed: 1.0 + acceleration: 2.7 + command: 70.0 + } + calibration { + speed: 1.0 + acceleration: 2.73 + command: 75.0 + } + calibration { + speed: 1.0 + acceleration: 2.76 + command: 66.6666666667 + } + calibration { + speed: 1.2 + acceleration: -9.07 + command: -35.0 + } + calibration { + speed: 1.2 + acceleration: -8.35 + command: -33.0 + } + calibration { + speed: 1.2 + acceleration: -4.79 + command: -30.0 + } + calibration { + speed: 1.2 + acceleration: -2.78 + command: -27.0 + } + calibration { + speed: 1.2 + acceleration: -1.71 + command: -25.0 + } + calibration { + speed: 1.2 + acceleration: -0.53 + command: -22.0 + } + calibration { + speed: 1.2 + acceleration: -0.09 + command: -20.0 + } + calibration { + speed: 1.2 + acceleration: 0.14 + command: -15.0 + } + calibration { + speed: 1.2 + acceleration: 0.19 + command: 15.0 + } + calibration { + speed: 1.2 + acceleration: 0.21 + command: -13.0 + } + calibration { + speed: 1.2 + acceleration: 0.22 + command: -17.0 + } + calibration { + speed: 1.2 + acceleration: 0.23 + command: 17.0 + } + calibration { + speed: 1.2 + acceleration: 0.87 + command: 20.0 + } + calibration { + speed: 1.2 + acceleration: 1.27 + command: 22.0 + } + calibration { + speed: 1.2 + acceleration: 1.95 + command: 25.0 + } + calibration { + speed: 1.2 + acceleration: 2.16 + command: 27.0 + } + calibration { + speed: 1.2 + acceleration: 2.27 + command: 30.0 + } + calibration { + speed: 1.2 + acceleration: 2.59 + command: 35.0 + } + calibration { + speed: 1.2 + acceleration: 2.68 + command: 50.0 + } + calibration { + speed: 1.2 + acceleration: 2.71 + command: 45.0 + } + calibration { + speed: 1.2 + acceleration: 2.74 + command: 70.0 + } + calibration { + speed: 1.2 + acceleration: 2.77 + command: 40.0 + } + calibration { + speed: 1.2 + acceleration: 2.78 + command: 60.0 + } + calibration { + speed: 1.2 + acceleration: 2.8 + command: 73.3333333333 + } + calibration { + speed: 1.2 + acceleration: 2.82 + command: 55.0 + } + calibration { + speed: 1.4 + acceleration: -8.98 + command: -35.0 + } + calibration { + speed: 1.4 + acceleration: -8.12 + command: -33.0 + } + calibration { + speed: 1.4 + acceleration: -4.67 + command: -30.0 + } + calibration { + speed: 1.4 + acceleration: -2.82 + command: -27.0 + } + calibration { + speed: 1.4 + acceleration: -1.69 + command: -25.0 + } + calibration { + speed: 1.4 + acceleration: -0.54 + command: -22.0 + } + calibration { + speed: 1.4 + acceleration: -0.14 + command: -20.0 + } + calibration { + speed: 1.4 + acceleration: 0.11 + command: -15.0 + } + calibration { + speed: 1.4 + acceleration: 0.14 + command: -17.0 + } + calibration { + speed: 1.4 + acceleration: 0.15 + command: 1.0 + } + calibration { + speed: 1.4 + acceleration: 0.18 + command: 17.0 + } + calibration { + speed: 1.4 + acceleration: 0.87 + command: 20.0 + } + calibration { + speed: 1.4 + acceleration: 1.3 + command: 22.0 + } + calibration { + speed: 1.4 + acceleration: 1.99 + command: 25.0 + } + calibration { + speed: 1.4 + acceleration: 2.23 + command: 27.0 + } + calibration { + speed: 1.4 + acceleration: 2.35 + command: 30.0 + } + calibration { + speed: 1.4 + acceleration: 2.68 + command: 35.0 + } + calibration { + speed: 1.4 + acceleration: 2.77 + command: 50.0 + } + calibration { + speed: 1.4 + acceleration: 2.8 + command: 45.0 + } + calibration { + speed: 1.4 + acceleration: 2.82 + command: 70.0 + } + calibration { + speed: 1.4 + acceleration: 2.84 + command: 40.0 + } + calibration { + speed: 1.4 + acceleration: 2.87 + command: 60.0 + } + calibration { + speed: 1.4 + acceleration: 2.88 + command: 72.5 + } + calibration { + speed: 1.4 + acceleration: 2.89 + command: 65.0 + } + calibration { + speed: 1.6 + acceleration: -8.91 + command: -35.0 + } + calibration { + speed: 1.6 + acceleration: -7.88 + command: -33.0 + } + calibration { + speed: 1.6 + acceleration: -4.66 + command: -30.0 + } + calibration { + speed: 1.6 + acceleration: -2.79 + command: -27.0 + } + calibration { + speed: 1.6 + acceleration: -1.69 + command: -25.0 + } + calibration { + speed: 1.6 + acceleration: -0.56 + command: -22.0 + } + calibration { + speed: 1.6 + acceleration: -0.2 + command: -20.0 + } + calibration { + speed: 1.6 + acceleration: 0.04 + command: -15.0 + } + calibration { + speed: 1.6 + acceleration: 0.05 + command: 15.0 + } + calibration { + speed: 1.6 + acceleration: 0.08 + command: -17.0 + } + calibration { + speed: 1.6 + acceleration: 0.09 + command: -13.0 + } + calibration { + speed: 1.6 + acceleration: 0.13 + command: 17.0 + } + calibration { + speed: 1.6 + acceleration: 0.8 + command: 20.0 + } + calibration { + speed: 1.6 + acceleration: 1.29 + command: 22.0 + } + calibration { + speed: 1.6 + acceleration: 2.03 + command: 25.0 + } + calibration { + speed: 1.6 + acceleration: 2.29 + command: 27.0 + } + calibration { + speed: 1.6 + acceleration: 2.41 + command: 30.0 + } + calibration { + speed: 1.6 + acceleration: 2.74 + command: 35.0 + } + calibration { + speed: 1.6 + acceleration: 2.85 + command: 47.5 + } + calibration { + speed: 1.6 + acceleration: 2.89 + command: 70.0 + } + calibration { + speed: 1.6 + acceleration: 2.9 + command: 40.0 + } + calibration { + speed: 1.6 + acceleration: 2.94 + command: 60.0 + } + calibration { + speed: 1.6 + acceleration: 2.95 + command: 70.0 + } + calibration { + speed: 1.6 + acceleration: 2.96 + command: 75.0 + } + calibration { + speed: 1.8 + acceleration: -8.81 + command: -35.0 + } + calibration { + speed: 1.8 + acceleration: -7.64 + command: -33.0 + } + calibration { + speed: 1.8 + acceleration: -4.71 + command: -30.0 + } + calibration { + speed: 1.8 + acceleration: -2.72 + command: -27.0 + } + calibration { + speed: 1.8 + acceleration: -1.68 + command: -25.0 + } + calibration { + speed: 1.8 + acceleration: -0.58 + command: -22.0 + } + calibration { + speed: 1.8 + acceleration: -0.24 + command: -20.0 + } + calibration { + speed: 1.8 + acceleration: -0.02 + command: -15.0 + } + calibration { + speed: 1.8 + acceleration: 0.02 + command: -1.0 + } + calibration { + speed: 1.8 + acceleration: 0.03 + command: -13.0 + } + calibration { + speed: 1.8 + acceleration: 0.08 + command: 17.0 + } + calibration { + speed: 1.8 + acceleration: 0.78 + command: 20.0 + } + calibration { + speed: 1.8 + acceleration: 1.25 + command: 22.0 + } + calibration { + speed: 1.8 + acceleration: 2.05 + command: 25.0 + } + calibration { + speed: 1.8 + acceleration: 2.34 + command: 27.0 + } + calibration { + speed: 1.8 + acceleration: 2.48 + command: 30.0 + } + calibration { + speed: 1.8 + acceleration: 2.8 + command: 35.0 + } + calibration { + speed: 1.8 + acceleration: 2.9 + command: 47.5 + } + calibration { + speed: 1.8 + acceleration: 2.93 + command: 70.0 + } + calibration { + speed: 1.8 + acceleration: 2.95 + command: 40.0 + } + calibration { + speed: 1.8 + acceleration: 2.96 + command: 80.0 + } + calibration { + speed: 1.8 + acceleration: 2.97 + command: 60.0 + } + calibration { + speed: 1.8 + acceleration: 2.98 + command: 67.5 + } + calibration { + speed: 2.0 + acceleration: -8.72 + command: -35.0 + } + calibration { + speed: 2.0 + acceleration: -7.47 + command: -33.0 + } + calibration { + speed: 2.0 + acceleration: -4.78 + command: -30.0 + } + calibration { + speed: 2.0 + acceleration: -2.66 + command: -27.0 + } + calibration { + speed: 2.0 + acceleration: -1.67 + command: -25.0 + } + calibration { + speed: 2.0 + acceleration: -0.62 + command: -22.0 + } + calibration { + speed: 2.0 + acceleration: -0.3 + command: -20.0 + } + calibration { + speed: 2.0 + acceleration: -0.07 + command: 15.0 + } + calibration { + speed: 2.0 + acceleration: -0.05 + command: -17.0 + } + calibration { + speed: 2.0 + acceleration: -0.03 + command: -13.0 + } + calibration { + speed: 2.0 + acceleration: -0.02 + command: -15.0 + } + calibration { + speed: 2.0 + acceleration: 0.05 + command: 17.0 + } + calibration { + speed: 2.0 + acceleration: 0.7 + command: 20.0 + } + calibration { + speed: 2.0 + acceleration: 1.22 + command: 22.0 + } + calibration { + speed: 2.0 + acceleration: 2.05 + command: 25.0 + } + calibration { + speed: 2.0 + acceleration: 2.36 + command: 27.0 + } + calibration { + speed: 2.0 + acceleration: 2.51 + command: 30.0 + } + calibration { + speed: 2.0 + acceleration: 2.85 + command: 35.0 + } + calibration { + speed: 2.0 + acceleration: 2.92 + command: 70.0 + } + calibration { + speed: 2.0 + acceleration: 2.95 + command: 58.3333333333 + } + calibration { + speed: 2.0 + acceleration: 2.96 + command: 70.0 + } + calibration { + speed: 2.0 + acceleration: 2.98 + command: 55.0 + } + calibration { + speed: 2.0 + acceleration: 2.99 + command: 40.0 + } + calibration { + speed: 2.0 + acceleration: 3.01 + command: 60.0 + } + calibration { + speed: 2.2 + acceleration: -8.65 + command: -35.0 + } + calibration { + speed: 2.2 + acceleration: -7.37 + command: -33.0 + } + calibration { + speed: 2.2 + acceleration: -4.84 + command: -30.0 + } + calibration { + speed: 2.2 + acceleration: -2.64 + command: -27.0 + } + calibration { + speed: 2.2 + acceleration: -1.66 + command: -25.0 + } + calibration { + speed: 2.2 + acceleration: -0.67 + command: -22.0 + } + calibration { + speed: 2.2 + acceleration: -0.32 + command: -20.0 + } + calibration { + speed: 2.2 + acceleration: -0.13 + command: 1.0 + } + calibration { + speed: 2.2 + acceleration: -0.1 + command: -15.0 + } + calibration { + speed: 2.2 + acceleration: -0.09 + command: -17.0 + } + calibration { + speed: 2.2 + acceleration: 0.08 + command: 17.0 + } + calibration { + speed: 2.2 + acceleration: 0.59 + command: 20.0 + } + calibration { + speed: 2.2 + acceleration: 1.13 + command: 22.0 + } + calibration { + speed: 2.2 + acceleration: 2.02 + command: 25.0 + } + calibration { + speed: 2.2 + acceleration: 2.35 + command: 27.0 + } + calibration { + speed: 2.2 + acceleration: 2.53 + command: 30.0 + } + calibration { + speed: 2.2 + acceleration: 2.89 + command: 35.0 + } + calibration { + speed: 2.2 + acceleration: 2.9 + command: 70.0 + } + calibration { + speed: 2.2 + acceleration: 2.93 + command: 65.0 + } + calibration { + speed: 2.2 + acceleration: 2.94 + command: 80.0 + } + calibration { + speed: 2.2 + acceleration: 2.95 + command: 75.0 + } + calibration { + speed: 2.2 + acceleration: 2.98 + command: 55.0 + } + calibration { + speed: 2.2 + acceleration: 3.0 + command: 50.0 + } + calibration { + speed: 2.2 + acceleration: 3.01 + command: 45.0 + } + calibration { + speed: 2.2 + acceleration: 3.03 + command: 50.0 + } + calibration { + speed: 2.4 + acceleration: -8.64 + command: -35.0 + } + calibration { + speed: 2.4 + acceleration: -7.35 + command: -33.0 + } + calibration { + speed: 2.4 + acceleration: -4.87 + command: -30.0 + } + calibration { + speed: 2.4 + acceleration: -2.63 + command: -27.0 + } + calibration { + speed: 2.4 + acceleration: -1.66 + command: -25.0 + } + calibration { + speed: 2.4 + acceleration: -0.65 + command: -22.0 + } + calibration { + speed: 2.4 + acceleration: -0.32 + command: -20.0 + } + calibration { + speed: 2.4 + acceleration: -0.14 + command: -13.0 + } + calibration { + speed: 2.4 + acceleration: -0.13 + command: 15.0 + } + calibration { + speed: 2.4 + acceleration: -0.1 + command: -15.0 + } + calibration { + speed: 2.4 + acceleration: -0.09 + command: -17.0 + } + calibration { + speed: 2.4 + acceleration: 0.08 + command: 17.0 + } + calibration { + speed: 2.4 + acceleration: 0.5 + command: 20.0 + } + calibration { + speed: 2.4 + acceleration: 1.03 + command: 22.0 + } + calibration { + speed: 2.4 + acceleration: 1.96 + command: 25.0 + } + calibration { + speed: 2.4 + acceleration: 2.32 + command: 27.0 + } + calibration { + speed: 2.4 + acceleration: 2.54 + command: 30.0 + } + calibration { + speed: 2.4 + acceleration: 2.89 + command: 70.0 + } + calibration { + speed: 2.4 + acceleration: 2.91 + command: 35.0 + } + calibration { + speed: 2.4 + acceleration: 2.93 + command: 65.0 + } + calibration { + speed: 2.4 + acceleration: 2.95 + command: 80.0 + } + calibration { + speed: 2.4 + acceleration: 2.97 + command: 75.0 + } + calibration { + speed: 2.4 + acceleration: 3.0 + command: 55.0 + } + calibration { + speed: 2.4 + acceleration: 3.05 + command: 50.0 + } + calibration { + speed: 2.4 + acceleration: 3.06 + command: 60.0 + } + calibration { + speed: 2.4 + acceleration: 3.07 + command: 45.0 + } + calibration { + speed: 2.4 + acceleration: 3.08 + command: 40.0 + } + calibration { + speed: 2.6 + acceleration: -8.68 + command: -35.0 + } + calibration { + speed: 2.6 + acceleration: -7.36 + command: -33.0 + } + calibration { + speed: 2.6 + acceleration: -4.86 + command: -30.0 + } + calibration { + speed: 2.6 + acceleration: -2.64 + command: -27.0 + } + calibration { + speed: 2.6 + acceleration: -1.68 + command: -25.0 + } + calibration { + speed: 2.6 + acceleration: -0.64 + command: -22.0 + } + calibration { + speed: 2.6 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 2.6 + acceleration: -0.13 + command: 15.0 + } + calibration { + speed: 2.6 + acceleration: -0.12 + command: -14.0 + } + calibration { + speed: 2.6 + acceleration: -0.11 + command: -17.0 + } + calibration { + speed: 2.6 + acceleration: 0.06 + command: 17.0 + } + calibration { + speed: 2.6 + acceleration: 0.4 + command: 20.0 + } + calibration { + speed: 2.6 + acceleration: 0.92 + command: 22.0 + } + calibration { + speed: 2.6 + acceleration: 1.9 + command: 25.0 + } + calibration { + speed: 2.6 + acceleration: 2.28 + command: 27.0 + } + calibration { + speed: 2.6 + acceleration: 2.55 + command: 30.0 + } + calibration { + speed: 2.6 + acceleration: 2.91 + command: 70.0 + } + calibration { + speed: 2.6 + acceleration: 2.92 + command: 35.0 + } + calibration { + speed: 2.6 + acceleration: 2.96 + command: 65.0 + } + calibration { + speed: 2.6 + acceleration: 2.99 + command: 80.0 + } + calibration { + speed: 2.6 + acceleration: 3.01 + command: 75.0 + } + calibration { + speed: 2.6 + acceleration: 3.03 + command: 55.0 + } + calibration { + speed: 2.6 + acceleration: 3.09 + command: 60.0 + } + calibration { + speed: 2.6 + acceleration: 3.11 + command: 50.0 + } + calibration { + speed: 2.6 + acceleration: 3.12 + command: 42.5 + } + calibration { + speed: 2.8 + acceleration: -8.76 + command: -35.0 + } + calibration { + speed: 2.8 + acceleration: -7.41 + command: -33.0 + } + calibration { + speed: 2.8 + acceleration: -4.84 + command: -30.0 + } + calibration { + speed: 2.8 + acceleration: -2.64 + command: -27.0 + } + calibration { + speed: 2.8 + acceleration: -1.7 + command: -25.0 + } + calibration { + speed: 2.8 + acceleration: -0.65 + command: -22.0 + } + calibration { + speed: 2.8 + acceleration: -0.3 + command: -20.0 + } + calibration { + speed: 2.8 + acceleration: -0.13 + command: -5.0 + } + calibration { + speed: 2.8 + acceleration: -0.11 + command: -15.0 + } + calibration { + speed: 2.8 + acceleration: 0.06 + command: 17.0 + } + calibration { + speed: 2.8 + acceleration: 0.35 + command: 20.0 + } + calibration { + speed: 2.8 + acceleration: 0.84 + command: 22.0 + } + calibration { + speed: 2.8 + acceleration: 1.82 + command: 25.0 + } + calibration { + speed: 2.8 + acceleration: 2.24 + command: 27.0 + } + calibration { + speed: 2.8 + acceleration: 2.57 + command: 30.0 + } + calibration { + speed: 2.8 + acceleration: 2.93 + command: 35.0 + } + calibration { + speed: 2.8 + acceleration: 2.94 + command: 70.0 + } + calibration { + speed: 2.8 + acceleration: 3.02 + command: 65.0 + } + calibration { + speed: 2.8 + acceleration: 3.03 + command: 80.0 + } + calibration { + speed: 2.8 + acceleration: 3.04 + command: 75.0 + } + calibration { + speed: 2.8 + acceleration: 3.06 + command: 55.0 + } + calibration { + speed: 2.8 + acceleration: 3.13 + command: 60.0 + } + calibration { + speed: 2.8 + acceleration: 3.15 + command: 45.0 + } + calibration { + speed: 3.0 + acceleration: -8.84 + command: -35.0 + } + calibration { + speed: 3.0 + acceleration: -7.48 + command: -33.0 + } + calibration { + speed: 3.0 + acceleration: -4.82 + command: -30.0 + } + calibration { + speed: 3.0 + acceleration: -2.64 + command: -27.0 + } + calibration { + speed: 3.0 + acceleration: -1.73 + command: -25.0 + } + calibration { + speed: 3.0 + acceleration: -0.63 + command: -22.0 + } + calibration { + speed: 3.0 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 3.0 + acceleration: -0.13 + command: 0.0 + } + calibration { + speed: 3.0 + acceleration: -0.12 + command: -13.0 + } + calibration { + speed: 3.0 + acceleration: -0.1 + command: -17.0 + } + calibration { + speed: 3.0 + acceleration: 0.03 + command: 17.0 + } + calibration { + speed: 3.0 + acceleration: 0.31 + command: 20.0 + } + calibration { + speed: 3.0 + acceleration: 0.76 + command: 22.0 + } + calibration { + speed: 3.0 + acceleration: 1.72 + command: 25.0 + } + calibration { + speed: 3.0 + acceleration: 2.2 + command: 27.0 + } + calibration { + speed: 3.0 + acceleration: 2.58 + command: 30.0 + } + calibration { + speed: 3.0 + acceleration: 2.94 + command: 35.0 + } + calibration { + speed: 3.0 + acceleration: 2.96 + command: 70.0 + } + calibration { + speed: 3.0 + acceleration: 3.04 + command: 72.5 + } + calibration { + speed: 3.0 + acceleration: 3.05 + command: 75.0 + } + calibration { + speed: 3.0 + acceleration: 3.07 + command: 55.0 + } + calibration { + speed: 3.0 + acceleration: 3.14 + command: 60.0 + } + calibration { + speed: 3.0 + acceleration: 3.15 + command: 45.0 + } + calibration { + speed: 3.0 + acceleration: 3.16 + command: 40.0 + } + calibration { + speed: 3.0 + acceleration: 3.17 + command: 50.0 + } + calibration { + speed: 3.2 + acceleration: -8.93 + command: -35.0 + } + calibration { + speed: 3.2 + acceleration: -7.55 + command: -33.0 + } + calibration { + speed: 3.2 + acceleration: -4.8 + command: -30.0 + } + calibration { + speed: 3.2 + acceleration: -2.63 + command: -27.0 + } + calibration { + speed: 3.2 + acceleration: -1.74 + command: -25.0 + } + calibration { + speed: 3.2 + acceleration: -0.63 + command: -22.0 + } + calibration { + speed: 3.2 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 3.2 + acceleration: -0.15 + command: 15.0 + } + calibration { + speed: 3.2 + acceleration: -0.13 + command: -14.0 + } + calibration { + speed: 3.2 + acceleration: -0.12 + command: -17.0 + } + calibration { + speed: 3.2 + acceleration: 0.04 + command: 17.0 + } + calibration { + speed: 3.2 + acceleration: 0.27 + command: 20.0 + } + calibration { + speed: 3.2 + acceleration: 0.7 + command: 22.0 + } + calibration { + speed: 3.2 + acceleration: 1.65 + command: 25.0 + } + calibration { + speed: 3.2 + acceleration: 2.12 + command: 27.0 + } + calibration { + speed: 3.2 + acceleration: 2.57 + command: 30.0 + } + calibration { + speed: 3.2 + acceleration: 2.93 + command: 35.0 + } + calibration { + speed: 3.2 + acceleration: 2.96 + command: 70.0 + } + calibration { + speed: 3.2 + acceleration: 3.03 + command: 80.0 + } + calibration { + speed: 3.2 + acceleration: 3.04 + command: 70.0 + } + calibration { + speed: 3.2 + acceleration: 3.07 + command: 55.0 + } + calibration { + speed: 3.2 + acceleration: 3.13 + command: 45.0 + } + calibration { + speed: 3.2 + acceleration: 3.15 + command: 60.0 + } + calibration { + speed: 3.2 + acceleration: 3.17 + command: 45.0 + } + calibration { + speed: 3.4 + acceleration: -9.0 + command: -35.0 + } + calibration { + speed: 3.4 + acceleration: -7.6 + command: -33.0 + } + calibration { + speed: 3.4 + acceleration: -4.79 + command: -30.0 + } + calibration { + speed: 3.4 + acceleration: -2.61 + command: -27.0 + } + calibration { + speed: 3.4 + acceleration: -1.74 + command: -25.0 + } + calibration { + speed: 3.4 + acceleration: -0.65 + command: -22.0 + } + calibration { + speed: 3.4 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 3.4 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 3.4 + acceleration: -0.14 + command: -13.0 + } + calibration { + speed: 3.4 + acceleration: -0.13 + command: -17.0 + } + calibration { + speed: 3.4 + acceleration: -0.11 + command: -15.0 + } + calibration { + speed: 3.4 + acceleration: 0.06 + command: 17.0 + } + calibration { + speed: 3.4 + acceleration: 0.27 + command: 20.0 + } + calibration { + speed: 3.4 + acceleration: 0.63 + command: 22.0 + } + calibration { + speed: 3.4 + acceleration: 1.58 + command: 25.0 + } + calibration { + speed: 3.4 + acceleration: 2.04 + command: 27.0 + } + calibration { + speed: 3.4 + acceleration: 2.54 + command: 30.0 + } + calibration { + speed: 3.4 + acceleration: 2.92 + command: 35.0 + } + calibration { + speed: 3.4 + acceleration: 2.96 + command: 70.0 + } + calibration { + speed: 3.4 + acceleration: 3.02 + command: 80.0 + } + calibration { + speed: 3.4 + acceleration: 3.03 + command: 70.0 + } + calibration { + speed: 3.4 + acceleration: 3.05 + command: 55.0 + } + calibration { + speed: 3.4 + acceleration: 3.12 + command: 45.0 + } + calibration { + speed: 3.4 + acceleration: 3.14 + command: 60.0 + } + calibration { + speed: 3.4 + acceleration: 3.15 + command: 50.0 + } + calibration { + speed: 3.4 + acceleration: 3.16 + command: 40.0 + } + calibration { + speed: 3.6 + acceleration: -9.02 + command: -35.0 + } + calibration { + speed: 3.6 + acceleration: -7.61 + command: -33.0 + } + calibration { + speed: 3.6 + acceleration: -4.79 + command: -30.0 + } + calibration { + speed: 3.6 + acceleration: -2.6 + command: -27.0 + } + calibration { + speed: 3.6 + acceleration: -1.71 + command: -25.0 + } + calibration { + speed: 3.6 + acceleration: -0.63 + command: -22.0 + } + calibration { + speed: 3.6 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 3.6 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 3.6 + acceleration: -0.15 + command: 15.0 + } + calibration { + speed: 3.6 + acceleration: -0.13 + command: -15.0 + } + calibration { + speed: 3.6 + acceleration: -0.11 + command: -17.0 + } + calibration { + speed: 3.6 + acceleration: 0.29 + command: 20.0 + } + calibration { + speed: 3.6 + acceleration: 0.58 + command: 22.0 + } + calibration { + speed: 3.6 + acceleration: 1.51 + command: 25.0 + } + calibration { + speed: 3.6 + acceleration: 1.99 + command: 27.0 + } + calibration { + speed: 3.6 + acceleration: 2.5 + command: 30.0 + } + calibration { + speed: 3.6 + acceleration: 2.89 + command: 35.0 + } + calibration { + speed: 3.6 + acceleration: 2.96 + command: 70.0 + } + calibration { + speed: 3.6 + acceleration: 3.01 + command: 80.0 + } + calibration { + speed: 3.6 + acceleration: 3.02 + command: 65.0 + } + calibration { + speed: 3.6 + acceleration: 3.03 + command: 55.0 + } + calibration { + speed: 3.6 + acceleration: 3.04 + command: 75.0 + } + calibration { + speed: 3.6 + acceleration: 3.11 + command: 45.0 + } + calibration { + speed: 3.6 + acceleration: 3.12 + command: 55.0 + } + calibration { + speed: 3.6 + acceleration: 3.14 + command: 40.0 + } + calibration { + speed: 3.8 + acceleration: -9.01 + command: -35.0 + } + calibration { + speed: 3.8 + acceleration: -7.6 + command: -33.0 + } + calibration { + speed: 3.8 + acceleration: -4.79 + command: -30.0 + } + calibration { + speed: 3.8 + acceleration: -2.61 + command: -27.0 + } + calibration { + speed: 3.8 + acceleration: -1.71 + command: -25.0 + } + calibration { + speed: 3.8 + acceleration: -0.67 + command: -22.0 + } + calibration { + speed: 3.8 + acceleration: -0.3 + command: -20.0 + } + calibration { + speed: 3.8 + acceleration: -0.16 + command: -15.0 + } + calibration { + speed: 3.8 + acceleration: -0.15 + command: -1.0 + } + calibration { + speed: 3.8 + acceleration: -0.14 + command: -13.0 + } + calibration { + speed: 3.8 + acceleration: 0.26 + command: 20.0 + } + calibration { + speed: 3.8 + acceleration: 0.52 + command: 22.0 + } + calibration { + speed: 3.8 + acceleration: 1.42 + command: 25.0 + } + calibration { + speed: 3.8 + acceleration: 1.94 + command: 27.0 + } + calibration { + speed: 3.8 + acceleration: 2.43 + command: 30.0 + } + calibration { + speed: 3.8 + acceleration: 2.85 + command: 35.0 + } + calibration { + speed: 3.8 + acceleration: 2.99 + command: 70.0 + } + calibration { + speed: 3.8 + acceleration: 3.0 + command: 55.0 + } + calibration { + speed: 3.8 + acceleration: 3.04 + command: 72.5 + } + calibration { + speed: 3.8 + acceleration: 3.07 + command: 75.0 + } + calibration { + speed: 3.8 + acceleration: 3.1 + command: 50.0 + } + calibration { + speed: 3.8 + acceleration: 3.11 + command: 52.5 + } + calibration { + speed: 3.8 + acceleration: 3.13 + command: 40.0 + } + calibration { + speed: 4.0 + acceleration: -8.99 + command: -35.0 + } + calibration { + speed: 4.0 + acceleration: -7.58 + command: -33.0 + } + calibration { + speed: 4.0 + acceleration: -4.79 + command: -30.0 + } + calibration { + speed: 4.0 + acceleration: -2.65 + command: -27.0 + } + calibration { + speed: 4.0 + acceleration: -1.76 + command: -25.0 + } + calibration { + speed: 4.0 + acceleration: -0.64 + command: -22.0 + } + calibration { + speed: 4.0 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 4.0 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 4.0 + acceleration: -0.16 + command: -15.0 + } + calibration { + speed: 4.0 + acceleration: -0.15 + command: -15.0 + } + calibration { + speed: 4.0 + acceleration: -0.02 + command: 17.0 + } + calibration { + speed: 4.0 + acceleration: 0.24 + command: 20.0 + } + calibration { + speed: 4.0 + acceleration: 0.49 + command: 22.0 + } + calibration { + speed: 4.0 + acceleration: 1.33 + command: 25.0 + } + calibration { + speed: 4.0 + acceleration: 1.84 + command: 27.0 + } + calibration { + speed: 4.0 + acceleration: 2.35 + command: 30.0 + } + calibration { + speed: 4.0 + acceleration: 2.8 + command: 35.0 + } + calibration { + speed: 4.0 + acceleration: 3.01 + command: 55.0 + } + calibration { + speed: 4.0 + acceleration: 3.02 + command: 70.0 + } + calibration { + speed: 4.0 + acceleration: 3.08 + command: 65.0 + } + calibration { + speed: 4.0 + acceleration: 3.09 + command: 50.0 + } + calibration { + speed: 4.0 + acceleration: 3.1 + command: 60.0 + } + calibration { + speed: 4.0 + acceleration: 3.11 + command: 75.0 + } + calibration { + speed: 4.0 + acceleration: 3.12 + command: 52.5 + } + calibration { + speed: 4.2 + acceleration: -8.98 + command: -35.0 + } + calibration { + speed: 4.2 + acceleration: -7.53 + command: -33.0 + } + calibration { + speed: 4.2 + acceleration: -4.78 + command: -30.0 + } + calibration { + speed: 4.2 + acceleration: -2.67 + command: -27.0 + } + calibration { + speed: 4.2 + acceleration: -1.79 + command: -25.0 + } + calibration { + speed: 4.2 + acceleration: -0.6 + command: -22.0 + } + calibration { + speed: 4.2 + acceleration: -0.28 + command: -20.0 + } + calibration { + speed: 4.2 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 4.2 + acceleration: -0.17 + command: 15.0 + } + calibration { + speed: 4.2 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 4.2 + acceleration: -0.12 + command: -17.0 + } + calibration { + speed: 4.2 + acceleration: -0.04 + command: 17.0 + } + calibration { + speed: 4.2 + acceleration: 0.22 + command: 20.0 + } + calibration { + speed: 4.2 + acceleration: 0.47 + command: 22.0 + } + calibration { + speed: 4.2 + acceleration: 1.22 + command: 25.0 + } + calibration { + speed: 4.2 + acceleration: 1.71 + command: 27.0 + } + calibration { + speed: 4.2 + acceleration: 2.25 + command: 30.0 + } + calibration { + speed: 4.2 + acceleration: 2.75 + command: 35.0 + } + calibration { + speed: 4.2 + acceleration: 3.04 + command: 55.0 + } + calibration { + speed: 4.2 + acceleration: 3.06 + command: 55.0 + } + calibration { + speed: 4.2 + acceleration: 3.1 + command: 50.0 + } + calibration { + speed: 4.2 + acceleration: 3.12 + command: 65.0 + } + calibration { + speed: 4.2 + acceleration: 3.13 + command: 52.5 + } + calibration { + speed: 4.2 + acceleration: 3.16 + command: 77.5 + } + calibration { + speed: 4.4 + acceleration: -8.88 + command: -35.0 + } + calibration { + speed: 4.4 + acceleration: -7.48 + command: -33.0 + } + calibration { + speed: 4.4 + acceleration: -4.77 + command: -30.0 + } + calibration { + speed: 4.4 + acceleration: -2.67 + command: -27.0 + } + calibration { + speed: 4.4 + acceleration: -1.79 + command: -25.0 + } + calibration { + speed: 4.4 + acceleration: -0.63 + command: -22.0 + } + calibration { + speed: 4.4 + acceleration: -0.27 + command: -20.0 + } + calibration { + speed: 4.4 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 4.4 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 4.4 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 4.4 + acceleration: -0.15 + command: -13.0 + } + calibration { + speed: 4.4 + acceleration: -0.03 + command: 17.0 + } + calibration { + speed: 4.4 + acceleration: 0.2 + command: 20.0 + } + calibration { + speed: 4.4 + acceleration: 0.43 + command: 22.0 + } + calibration { + speed: 4.4 + acceleration: 1.14 + command: 25.0 + } + calibration { + speed: 4.4 + acceleration: 1.59 + command: 27.0 + } + calibration { + speed: 4.4 + acceleration: 2.15 + command: 30.0 + } + calibration { + speed: 4.4 + acceleration: 2.68 + command: 35.0 + } + calibration { + speed: 4.4 + acceleration: 3.02 + command: 40.0 + } + calibration { + speed: 4.4 + acceleration: 3.07 + command: 55.0 + } + calibration { + speed: 4.4 + acceleration: 3.08 + command: 70.0 + } + calibration { + speed: 4.4 + acceleration: 3.11 + command: 50.0 + } + calibration { + speed: 4.4 + acceleration: 3.12 + command: 45.0 + } + calibration { + speed: 4.4 + acceleration: 3.16 + command: 62.5 + } + calibration { + speed: 4.4 + acceleration: 3.19 + command: 80.0 + } + calibration { + speed: 4.4 + acceleration: 3.21 + command: 75.0 + } + calibration { + speed: 4.6 + acceleration: -8.79 + command: -35.0 + } + calibration { + speed: 4.6 + acceleration: -7.43 + command: -33.0 + } + calibration { + speed: 4.6 + acceleration: -4.76 + command: -30.0 + } + calibration { + speed: 4.6 + acceleration: -2.64 + command: -27.0 + } + calibration { + speed: 4.6 + acceleration: -1.77 + command: -25.0 + } + calibration { + speed: 4.6 + acceleration: -0.62 + command: -22.0 + } + calibration { + speed: 4.6 + acceleration: -0.26 + command: -20.0 + } + calibration { + speed: 4.6 + acceleration: -0.18 + command: 1.0 + } + calibration { + speed: 4.6 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 4.6 + acceleration: -0.15 + command: -17.0 + } + calibration { + speed: 4.6 + acceleration: -0.01 + command: 17.0 + } + calibration { + speed: 4.6 + acceleration: 0.15 + command: 20.0 + } + calibration { + speed: 4.6 + acceleration: 0.39 + command: 22.0 + } + calibration { + speed: 4.6 + acceleration: 1.04 + command: 25.0 + } + calibration { + speed: 4.6 + acceleration: 1.49 + command: 27.0 + } + calibration { + speed: 4.6 + acceleration: 2.04 + command: 30.0 + } + calibration { + speed: 4.6 + acceleration: 2.62 + command: 35.0 + } + calibration { + speed: 4.6 + acceleration: 2.97 + command: 40.0 + } + calibration { + speed: 4.6 + acceleration: 3.08 + command: 45.0 + } + calibration { + speed: 4.6 + acceleration: 3.1 + command: 55.0 + } + calibration { + speed: 4.6 + acceleration: 3.12 + command: 60.0 + } + calibration { + speed: 4.6 + acceleration: 3.17 + command: 65.0 + } + calibration { + speed: 4.6 + acceleration: 3.19 + command: 60.0 + } + calibration { + speed: 4.6 + acceleration: 3.21 + command: 80.0 + } + calibration { + speed: 4.6 + acceleration: 3.23 + command: 75.0 + } + calibration { + speed: 4.8 + acceleration: -8.56 + command: -35.0 + } + calibration { + speed: 4.8 + acceleration: -7.39 + command: -33.0 + } + calibration { + speed: 4.8 + acceleration: -4.76 + command: -30.0 + } + calibration { + speed: 4.8 + acceleration: -2.6 + command: -27.0 + } + calibration { + speed: 4.8 + acceleration: -1.78 + command: -25.0 + } + calibration { + speed: 4.8 + acceleration: -0.65 + command: -22.0 + } + calibration { + speed: 4.8 + acceleration: -0.3 + command: -20.0 + } + calibration { + speed: 4.8 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 4.8 + acceleration: -0.16 + command: 0.0 + } + calibration { + speed: 4.8 + acceleration: -0.08 + command: 17.0 + } + calibration { + speed: 4.8 + acceleration: 0.11 + command: 20.0 + } + calibration { + speed: 4.8 + acceleration: 0.34 + command: 22.0 + } + calibration { + speed: 4.8 + acceleration: 0.94 + command: 25.0 + } + calibration { + speed: 4.8 + acceleration: 1.38 + command: 27.0 + } + calibration { + speed: 4.8 + acceleration: 1.92 + command: 30.0 + } + calibration { + speed: 4.8 + acceleration: 2.55 + command: 35.0 + } + calibration { + speed: 4.8 + acceleration: 2.92 + command: 40.0 + } + calibration { + speed: 4.8 + acceleration: 3.04 + command: 45.0 + } + calibration { + speed: 4.8 + acceleration: 3.12 + command: 52.5 + } + calibration { + speed: 4.8 + acceleration: 3.14 + command: 70.0 + } + calibration { + speed: 4.8 + acceleration: 3.17 + command: 65.0 + } + calibration { + speed: 4.8 + acceleration: 3.19 + command: 80.0 + } + calibration { + speed: 4.8 + acceleration: 3.22 + command: 67.5 + } + calibration { + speed: 5.0 + acceleration: -8.57 + command: -35.0 + } + calibration { + speed: 5.0 + acceleration: -7.36 + command: -33.0 + } + calibration { + speed: 5.0 + acceleration: -4.76 + command: -30.0 + } + calibration { + speed: 5.0 + acceleration: -2.6 + command: -27.0 + } + calibration { + speed: 5.0 + acceleration: -1.8 + command: -25.0 + } + calibration { + speed: 5.0 + acceleration: -0.63 + command: -22.0 + } + calibration { + speed: 5.0 + acceleration: -0.33 + command: -20.0 + } + calibration { + speed: 5.0 + acceleration: -0.2 + command: 15.0 + } + calibration { + speed: 5.0 + acceleration: -0.18 + command: -14.0 + } + calibration { + speed: 5.0 + acceleration: -0.16 + command: -17.0 + } + calibration { + speed: 5.0 + acceleration: -0.08 + command: 17.0 + } + calibration { + speed: 5.0 + acceleration: 0.11 + command: 20.0 + } + calibration { + speed: 5.0 + acceleration: 0.34 + command: 22.0 + } + calibration { + speed: 5.0 + acceleration: 0.86 + command: 25.0 + } + calibration { + speed: 5.0 + acceleration: 1.27 + command: 27.0 + } + calibration { + speed: 5.0 + acceleration: 1.8 + command: 30.0 + } + calibration { + speed: 5.0 + acceleration: 2.46 + command: 35.0 + } + calibration { + speed: 5.0 + acceleration: 2.87 + command: 40.0 + } + calibration { + speed: 5.0 + acceleration: 2.97 + command: 45.0 + } + calibration { + speed: 5.0 + acceleration: 3.1 + command: 50.0 + } + calibration { + speed: 5.0 + acceleration: 3.14 + command: 55.0 + } + calibration { + speed: 5.0 + acceleration: 3.15 + command: 70.0 + } + calibration { + speed: 5.0 + acceleration: 3.16 + command: 80.0 + } + calibration { + speed: 5.0 + acceleration: 3.19 + command: 65.0 + } + calibration { + speed: 5.0 + acceleration: 3.2 + command: 75.0 + } + calibration { + speed: 5.0 + acceleration: 3.24 + command: 60.0 + } + calibration { + speed: 5.2 + acceleration: -8.6 + command: -35.0 + } + calibration { + speed: 5.2 + acceleration: -7.35 + command: -33.0 + } + calibration { + speed: 5.2 + acceleration: -4.77 + command: -30.0 + } + calibration { + speed: 5.2 + acceleration: -2.62 + command: -27.0 + } + calibration { + speed: 5.2 + acceleration: -1.8 + command: -25.0 + } + calibration { + speed: 5.2 + acceleration: -0.67 + command: -22.0 + } + calibration { + speed: 5.2 + acceleration: -0.3 + command: -20.0 + } + calibration { + speed: 5.2 + acceleration: -0.19 + command: 15.0 + } + calibration { + speed: 5.2 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 5.2 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 5.2 + acceleration: -0.16 + command: -15.0 + } + calibration { + speed: 5.2 + acceleration: -0.09 + command: 17.0 + } + calibration { + speed: 5.2 + acceleration: 0.1 + command: 20.0 + } + calibration { + speed: 5.2 + acceleration: 0.3 + command: 22.0 + } + calibration { + speed: 5.2 + acceleration: 0.79 + command: 25.0 + } + calibration { + speed: 5.2 + acceleration: 1.19 + command: 27.0 + } + calibration { + speed: 5.2 + acceleration: 1.71 + command: 30.0 + } + calibration { + speed: 5.2 + acceleration: 2.38 + command: 35.0 + } + calibration { + speed: 5.2 + acceleration: 2.83 + command: 40.0 + } + calibration { + speed: 5.2 + acceleration: 2.92 + command: 45.0 + } + calibration { + speed: 5.2 + acceleration: 3.07 + command: 50.0 + } + calibration { + speed: 5.2 + acceleration: 3.15 + command: 67.5 + } + calibration { + speed: 5.2 + acceleration: 3.16 + command: 70.0 + } + calibration { + speed: 5.2 + acceleration: 3.19 + command: 70.0 + } + calibration { + speed: 5.2 + acceleration: 3.25 + command: 60.0 + } + calibration { + speed: 5.4 + acceleration: -8.6 + command: -35.0 + } + calibration { + speed: 5.4 + acceleration: -7.35 + command: -33.0 + } + calibration { + speed: 5.4 + acceleration: -4.78 + command: -30.0 + } + calibration { + speed: 5.4 + acceleration: -2.65 + command: -27.0 + } + calibration { + speed: 5.4 + acceleration: -1.8 + command: -25.0 + } + calibration { + speed: 5.4 + acceleration: -0.65 + command: -22.0 + } + calibration { + speed: 5.4 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 5.4 + acceleration: -0.2 + command: 15.0 + } + calibration { + speed: 5.4 + acceleration: -0.19 + command: -17.0 + } + calibration { + speed: 5.4 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 5.4 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 5.4 + acceleration: -0.08 + command: 17.0 + } + calibration { + speed: 5.4 + acceleration: 0.13 + command: 20.0 + } + calibration { + speed: 5.4 + acceleration: 0.29 + command: 22.0 + } + calibration { + speed: 5.4 + acceleration: 0.76 + command: 25.0 + } + calibration { + speed: 5.4 + acceleration: 1.12 + command: 27.0 + } + calibration { + speed: 5.4 + acceleration: 1.62 + command: 30.0 + } + calibration { + speed: 5.4 + acceleration: 2.31 + command: 35.0 + } + calibration { + speed: 5.4 + acceleration: 2.78 + command: 40.0 + } + calibration { + speed: 5.4 + acceleration: 2.89 + command: 45.0 + } + calibration { + speed: 5.4 + acceleration: 3.04 + command: 50.0 + } + calibration { + speed: 5.4 + acceleration: 3.16 + command: 68.3333333333 + } + calibration { + speed: 5.4 + acceleration: 3.19 + command: 75.0 + } + calibration { + speed: 5.4 + acceleration: 3.2 + command: 65.0 + } + calibration { + speed: 5.4 + acceleration: 3.26 + command: 60.0 + } + calibration { + speed: 5.6 + acceleration: -8.65 + command: -35.0 + } + calibration { + speed: 5.6 + acceleration: -7.36 + command: -33.0 + } + calibration { + speed: 5.6 + acceleration: -4.78 + command: -30.0 + } + calibration { + speed: 5.6 + acceleration: -2.65 + command: -27.0 + } + calibration { + speed: 5.6 + acceleration: -1.81 + command: -25.0 + } + calibration { + speed: 5.6 + acceleration: -0.67 + command: -22.0 + } + calibration { + speed: 5.6 + acceleration: -0.32 + command: -20.0 + } + calibration { + speed: 5.6 + acceleration: -0.18 + command: 0.0 + } + calibration { + speed: 5.6 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 5.6 + acceleration: -0.15 + command: -13.0 + } + calibration { + speed: 5.6 + acceleration: -0.07 + command: 17.0 + } + calibration { + speed: 5.6 + acceleration: 0.09 + command: 20.0 + } + calibration { + speed: 5.6 + acceleration: 0.29 + command: 22.0 + } + calibration { + speed: 5.6 + acceleration: 0.7 + command: 25.0 + } + calibration { + speed: 5.6 + acceleration: 1.06 + command: 27.0 + } + calibration { + speed: 5.6 + acceleration: 1.54 + command: 30.0 + } + calibration { + speed: 5.6 + acceleration: 2.24 + command: 35.0 + } + calibration { + speed: 5.6 + acceleration: 2.72 + command: 40.0 + } + calibration { + speed: 5.6 + acceleration: 2.86 + command: 45.0 + } + calibration { + speed: 5.6 + acceleration: 3.01 + command: 50.0 + } + calibration { + speed: 5.6 + acceleration: 3.16 + command: 70.0 + } + calibration { + speed: 5.6 + acceleration: 3.17 + command: 55.0 + } + calibration { + speed: 5.6 + acceleration: 3.18 + command: 80.0 + } + calibration { + speed: 5.6 + acceleration: 3.19 + command: 65.0 + } + calibration { + speed: 5.6 + acceleration: 3.2 + command: 75.0 + } + calibration { + speed: 5.6 + acceleration: 3.27 + command: 60.0 + } + calibration { + speed: 5.8 + acceleration: -8.68 + command: -35.0 + } + calibration { + speed: 5.8 + acceleration: -7.38 + command: -33.0 + } + calibration { + speed: 5.8 + acceleration: -4.78 + command: -30.0 + } + calibration { + speed: 5.8 + acceleration: -2.65 + command: -27.0 + } + calibration { + speed: 5.8 + acceleration: -1.82 + command: -25.0 + } + calibration { + speed: 5.8 + acceleration: -0.67 + command: -22.0 + } + calibration { + speed: 5.8 + acceleration: -0.33 + command: -20.0 + } + calibration { + speed: 5.8 + acceleration: -0.21 + command: 15.0 + } + calibration { + speed: 5.8 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 5.8 + acceleration: -0.19 + command: -17.0 + } + calibration { + speed: 5.8 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 5.8 + acceleration: -0.07 + command: 17.0 + } + calibration { + speed: 5.8 + acceleration: 0.07 + command: 20.0 + } + calibration { + speed: 5.8 + acceleration: 0.29 + command: 22.0 + } + calibration { + speed: 5.8 + acceleration: 0.69 + command: 25.0 + } + calibration { + speed: 5.8 + acceleration: 1.01 + command: 27.0 + } + calibration { + speed: 5.8 + acceleration: 1.47 + command: 30.0 + } + calibration { + speed: 5.8 + acceleration: 2.18 + command: 35.0 + } + calibration { + speed: 5.8 + acceleration: 2.66 + command: 40.0 + } + calibration { + speed: 5.8 + acceleration: 2.83 + command: 45.0 + } + calibration { + speed: 5.8 + acceleration: 2.99 + command: 50.0 + } + calibration { + speed: 5.8 + acceleration: 3.16 + command: 62.5 + } + calibration { + speed: 5.8 + acceleration: 3.19 + command: 65.0 + } + calibration { + speed: 5.8 + acceleration: 3.2 + command: 77.5 + } + calibration { + speed: 5.8 + acceleration: 3.27 + command: 60.0 + } + calibration { + speed: 6.0 + acceleration: -8.86 + command: -35.0 + } + calibration { + speed: 6.0 + acceleration: -7.41 + command: -33.0 + } + calibration { + speed: 6.0 + acceleration: -4.76 + command: -30.0 + } + calibration { + speed: 6.0 + acceleration: -2.65 + command: -27.0 + } + calibration { + speed: 6.0 + acceleration: -1.81 + command: -25.0 + } + calibration { + speed: 6.0 + acceleration: -0.66 + command: -22.0 + } + calibration { + speed: 6.0 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 6.0 + acceleration: -0.23 + command: -13.0 + } + calibration { + speed: 6.0 + acceleration: -0.2 + command: 0.0 + } + calibration { + speed: 6.0 + acceleration: -0.18 + command: -17.0 + } + calibration { + speed: 6.0 + acceleration: -0.1 + command: 17.0 + } + calibration { + speed: 6.0 + acceleration: 0.09 + command: 20.0 + } + calibration { + speed: 6.0 + acceleration: 0.27 + command: 22.0 + } + calibration { + speed: 6.0 + acceleration: 0.7 + command: 25.0 + } + calibration { + speed: 6.0 + acceleration: 0.98 + command: 27.0 + } + calibration { + speed: 6.0 + acceleration: 1.41 + command: 30.0 + } + calibration { + speed: 6.0 + acceleration: 2.13 + command: 35.0 + } + calibration { + speed: 6.0 + acceleration: 2.6 + command: 40.0 + } + calibration { + speed: 6.0 + acceleration: 2.78 + command: 45.0 + } + calibration { + speed: 6.0 + acceleration: 2.95 + command: 50.0 + } + calibration { + speed: 6.0 + acceleration: 3.14 + command: 55.0 + } + calibration { + speed: 6.0 + acceleration: 3.17 + command: 70.0 + } + calibration { + speed: 6.0 + acceleration: 3.19 + command: 65.0 + } + calibration { + speed: 6.0 + acceleration: 3.2 + command: 80.0 + } + calibration { + speed: 6.0 + acceleration: 3.21 + command: 75.0 + } + calibration { + speed: 6.0 + acceleration: 3.28 + command: 60.0 + } + calibration { + speed: 6.2 + acceleration: -8.91 + command: -35.0 + } + calibration { + speed: 6.2 + acceleration: -7.42 + command: -33.0 + } + calibration { + speed: 6.2 + acceleration: -4.74 + command: -30.0 + } + calibration { + speed: 6.2 + acceleration: -2.64 + command: -27.0 + } + calibration { + speed: 6.2 + acceleration: -1.8 + command: -25.0 + } + calibration { + speed: 6.2 + acceleration: -0.65 + command: -22.0 + } + calibration { + speed: 6.2 + acceleration: -0.34 + command: -20.0 + } + calibration { + speed: 6.2 + acceleration: -0.19 + command: 0.0 + } + calibration { + speed: 6.2 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 6.2 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 6.2 + acceleration: -0.08 + command: 17.0 + } + calibration { + speed: 6.2 + acceleration: 0.06 + command: 20.0 + } + calibration { + speed: 6.2 + acceleration: 0.28 + command: 22.0 + } + calibration { + speed: 6.2 + acceleration: 0.63 + command: 25.0 + } + calibration { + speed: 6.2 + acceleration: 0.94 + command: 27.0 + } + calibration { + speed: 6.2 + acceleration: 1.37 + command: 30.0 + } + calibration { + speed: 6.2 + acceleration: 2.08 + command: 35.0 + } + calibration { + speed: 6.2 + acceleration: 2.54 + command: 40.0 + } + calibration { + speed: 6.2 + acceleration: 2.7 + command: 45.0 + } + calibration { + speed: 6.2 + acceleration: 2.91 + command: 50.0 + } + calibration { + speed: 6.2 + acceleration: 3.11 + command: 55.0 + } + calibration { + speed: 6.2 + acceleration: 3.17 + command: 70.0 + } + calibration { + speed: 6.2 + acceleration: 3.2 + command: 73.3333333333 + } + calibration { + speed: 6.2 + acceleration: 3.27 + command: 60.0 + } + calibration { + speed: 6.4 + acceleration: -8.96 + command: -35.0 + } + calibration { + speed: 6.4 + acceleration: -7.45 + command: -33.0 + } + calibration { + speed: 6.4 + acceleration: -4.72 + command: -30.0 + } + calibration { + speed: 6.4 + acceleration: -2.65 + command: -27.0 + } + calibration { + speed: 6.4 + acceleration: -1.8 + command: -25.0 + } + calibration { + speed: 6.4 + acceleration: -0.67 + command: -22.0 + } + calibration { + speed: 6.4 + acceleration: -0.34 + command: -20.0 + } + calibration { + speed: 6.4 + acceleration: -0.2 + command: 15.0 + } + calibration { + speed: 6.4 + acceleration: -0.19 + command: -15.0 + } + calibration { + speed: 6.4 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 6.4 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 6.4 + acceleration: -0.07 + command: 17.0 + } + calibration { + speed: 6.4 + acceleration: 0.07 + command: 20.0 + } + calibration { + speed: 6.4 + acceleration: 0.25 + command: 22.0 + } + calibration { + speed: 6.4 + acceleration: 0.63 + command: 25.0 + } + calibration { + speed: 6.4 + acceleration: 0.91 + command: 27.0 + } + calibration { + speed: 6.4 + acceleration: 1.34 + command: 30.0 + } + calibration { + speed: 6.4 + acceleration: 2.02 + command: 35.0 + } + calibration { + speed: 6.4 + acceleration: 2.49 + command: 40.0 + } + calibration { + speed: 6.4 + acceleration: 2.64 + command: 45.0 + } + calibration { + speed: 6.4 + acceleration: 2.87 + command: 50.0 + } + calibration { + speed: 6.4 + acceleration: 3.08 + command: 55.0 + } + calibration { + speed: 6.4 + acceleration: 3.17 + command: 70.0 + } + calibration { + speed: 6.4 + acceleration: 3.2 + command: 77.5 + } + calibration { + speed: 6.4 + acceleration: 3.21 + command: 65.0 + } + calibration { + speed: 6.4 + acceleration: 3.26 + command: 60.0 + } + calibration { + speed: 6.6 + acceleration: -8.98 + command: -35.0 + } + calibration { + speed: 6.6 + acceleration: -7.48 + command: -33.0 + } + calibration { + speed: 6.6 + acceleration: -4.7 + command: -30.0 + } + calibration { + speed: 6.6 + acceleration: -2.65 + command: -27.0 + } + calibration { + speed: 6.6 + acceleration: -1.8 + command: -25.0 + } + calibration { + speed: 6.6 + acceleration: -0.66 + command: -22.0 + } + calibration { + speed: 6.6 + acceleration: -0.32 + command: -20.0 + } + calibration { + speed: 6.6 + acceleration: -0.23 + command: 15.0 + } + calibration { + speed: 6.6 + acceleration: -0.21 + command: -15.0 + } + calibration { + speed: 6.6 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 6.6 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 6.6 + acceleration: -0.08 + command: 17.0 + } + calibration { + speed: 6.6 + acceleration: 0.07 + command: 20.0 + } + calibration { + speed: 6.6 + acceleration: 0.23 + command: 22.0 + } + calibration { + speed: 6.6 + acceleration: 0.62 + command: 25.0 + } + calibration { + speed: 6.6 + acceleration: 0.89 + command: 27.0 + } + calibration { + speed: 6.6 + acceleration: 1.29 + command: 30.0 + } + calibration { + speed: 6.6 + acceleration: 1.97 + command: 35.0 + } + calibration { + speed: 6.6 + acceleration: 2.43 + command: 40.0 + } + calibration { + speed: 6.6 + acceleration: 2.6 + command: 45.0 + } + calibration { + speed: 6.6 + acceleration: 2.83 + command: 50.0 + } + calibration { + speed: 6.6 + acceleration: 3.04 + command: 55.0 + } + calibration { + speed: 6.6 + acceleration: 3.17 + command: 70.0 + } + calibration { + speed: 6.6 + acceleration: 3.19 + command: 80.0 + } + calibration { + speed: 6.6 + acceleration: 3.21 + command: 75.0 + } + calibration { + speed: 6.6 + acceleration: 3.22 + command: 65.0 + } + calibration { + speed: 6.6 + acceleration: 3.25 + command: 60.0 + } + calibration { + speed: 6.8 + acceleration: -9.02 + command: -35.0 + } + calibration { + speed: 6.8 + acceleration: -7.49 + command: -33.0 + } + calibration { + speed: 6.8 + acceleration: -4.69 + command: -30.0 + } + calibration { + speed: 6.8 + acceleration: -2.64 + command: -27.0 + } + calibration { + speed: 6.8 + acceleration: -1.79 + command: -25.0 + } + calibration { + speed: 6.8 + acceleration: -0.65 + command: -22.0 + } + calibration { + speed: 6.8 + acceleration: -0.33 + command: -20.0 + } + calibration { + speed: 6.8 + acceleration: -0.22 + command: 1.0 + } + calibration { + speed: 6.8 + acceleration: -0.19 + command: -17.0 + } + calibration { + speed: 6.8 + acceleration: -0.16 + command: -15.0 + } + calibration { + speed: 6.8 + acceleration: -0.1 + command: 17.0 + } + calibration { + speed: 6.8 + acceleration: 0.03 + command: 20.0 + } + calibration { + speed: 6.8 + acceleration: 0.21 + command: 22.0 + } + calibration { + speed: 6.8 + acceleration: 0.59 + command: 25.0 + } + calibration { + speed: 6.8 + acceleration: 0.85 + command: 27.0 + } + calibration { + speed: 6.8 + acceleration: 1.25 + command: 30.0 + } + calibration { + speed: 6.8 + acceleration: 1.92 + command: 35.0 + } + calibration { + speed: 6.8 + acceleration: 2.38 + command: 40.0 + } + calibration { + speed: 6.8 + acceleration: 2.56 + command: 45.0 + } + calibration { + speed: 6.8 + acceleration: 2.79 + command: 50.0 + } + calibration { + speed: 6.8 + acceleration: 3.01 + command: 55.0 + } + calibration { + speed: 6.8 + acceleration: 3.17 + command: 70.0 + } + calibration { + speed: 6.8 + acceleration: 3.19 + command: 80.0 + } + calibration { + speed: 6.8 + acceleration: 3.23 + command: 70.0 + } + calibration { + speed: 6.8 + acceleration: 3.24 + command: 60.0 + } + calibration { + speed: 7.0 + acceleration: -9.01 + command: -35.0 + } + calibration { + speed: 7.0 + acceleration: -7.51 + command: -33.0 + } + calibration { + speed: 7.0 + acceleration: -4.7 + command: -30.0 + } + calibration { + speed: 7.0 + acceleration: -2.63 + command: -27.0 + } + calibration { + speed: 7.0 + acceleration: -1.78 + command: -25.0 + } + calibration { + speed: 7.0 + acceleration: -0.71 + command: -22.0 + } + calibration { + speed: 7.0 + acceleration: -0.33 + command: -20.0 + } + calibration { + speed: 7.0 + acceleration: -0.27 + command: -13.0 + } + calibration { + speed: 7.0 + acceleration: -0.25 + command: -17.0 + } + calibration { + speed: 7.0 + acceleration: -0.22 + command: 0.0 + } + calibration { + speed: 7.0 + acceleration: -0.1 + command: 17.0 + } + calibration { + speed: 7.0 + acceleration: 0.06 + command: 20.0 + } + calibration { + speed: 7.0 + acceleration: 0.22 + command: 22.0 + } + calibration { + speed: 7.0 + acceleration: 0.55 + command: 25.0 + } + calibration { + speed: 7.0 + acceleration: 0.83 + command: 27.0 + } + calibration { + speed: 7.0 + acceleration: 1.21 + command: 30.0 + } + calibration { + speed: 7.0 + acceleration: 1.88 + command: 35.0 + } + calibration { + speed: 7.0 + acceleration: 2.34 + command: 40.0 + } + calibration { + speed: 7.0 + acceleration: 2.51 + command: 45.0 + } + calibration { + speed: 7.0 + acceleration: 2.75 + command: 50.0 + } + calibration { + speed: 7.0 + acceleration: 2.98 + command: 55.0 + } + calibration { + speed: 7.0 + acceleration: 3.18 + command: 70.0 + } + calibration { + speed: 7.0 + acceleration: 3.2 + command: 80.0 + } + calibration { + speed: 7.0 + acceleration: 3.22 + command: 65.0 + } + calibration { + speed: 7.0 + acceleration: 3.23 + command: 60.0 + } + calibration { + speed: 7.0 + acceleration: 3.24 + command: 75.0 + } + calibration { + speed: 7.2 + acceleration: -9.0 + command: -35.0 + } + calibration { + speed: 7.2 + acceleration: -7.51 + command: -33.0 + } + calibration { + speed: 7.2 + acceleration: -4.71 + command: -30.0 + } + calibration { + speed: 7.2 + acceleration: -2.63 + command: -27.0 + } + calibration { + speed: 7.2 + acceleration: -1.79 + command: -25.0 + } + calibration { + speed: 7.2 + acceleration: -0.7 + command: -22.0 + } + calibration { + speed: 7.2 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 7.2 + acceleration: -0.23 + command: 15.0 + } + calibration { + speed: 7.2 + acceleration: -0.22 + command: -17.0 + } + calibration { + speed: 7.2 + acceleration: -0.2 + command: -15.0 + } + calibration { + speed: 7.2 + acceleration: -0.17 + command: -13.0 + } + calibration { + speed: 7.2 + acceleration: -0.11 + command: 17.0 + } + calibration { + speed: 7.2 + acceleration: 0.07 + command: 20.0 + } + calibration { + speed: 7.2 + acceleration: 0.19 + command: 22.0 + } + calibration { + speed: 7.2 + acceleration: 0.55 + command: 25.0 + } + calibration { + speed: 7.2 + acceleration: 0.78 + command: 27.0 + } + calibration { + speed: 7.2 + acceleration: 1.16 + command: 30.0 + } + calibration { + speed: 7.2 + acceleration: 1.83 + command: 35.0 + } + calibration { + speed: 7.2 + acceleration: 2.3 + command: 40.0 + } + calibration { + speed: 7.2 + acceleration: 2.45 + command: 45.0 + } + calibration { + speed: 7.2 + acceleration: 2.7 + command: 50.0 + } + calibration { + speed: 7.2 + acceleration: 2.95 + command: 55.0 + } + calibration { + speed: 7.2 + acceleration: 3.18 + command: 70.0 + } + calibration { + speed: 7.2 + acceleration: 3.21 + command: 70.0 + } + calibration { + speed: 7.2 + acceleration: 3.22 + command: 65.0 + } + calibration { + speed: 7.2 + acceleration: 3.25 + command: 75.0 + } + calibration { + speed: 7.4 + acceleration: -9.0 + command: -35.0 + } + calibration { + speed: 7.4 + acceleration: -7.51 + command: -33.0 + } + calibration { + speed: 7.4 + acceleration: -4.72 + command: -30.0 + } + calibration { + speed: 7.4 + acceleration: -2.62 + command: -27.0 + } + calibration { + speed: 7.4 + acceleration: -1.79 + command: -25.0 + } + calibration { + speed: 7.4 + acceleration: -0.65 + command: -22.0 + } + calibration { + speed: 7.4 + acceleration: -0.32 + command: -20.0 + } + calibration { + speed: 7.4 + acceleration: -0.24 + command: 15.0 + } + calibration { + speed: 7.4 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 7.4 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 7.4 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 7.4 + acceleration: -0.13 + command: 17.0 + } + calibration { + speed: 7.4 + acceleration: 0.02 + command: 20.0 + } + calibration { + speed: 7.4 + acceleration: 0.21 + command: 22.0 + } + calibration { + speed: 7.4 + acceleration: 0.53 + command: 25.0 + } + calibration { + speed: 7.4 + acceleration: 0.78 + command: 27.0 + } + calibration { + speed: 7.4 + acceleration: 1.15 + command: 30.0 + } + calibration { + speed: 7.4 + acceleration: 1.79 + command: 35.0 + } + calibration { + speed: 7.4 + acceleration: 2.26 + command: 40.0 + } + calibration { + speed: 7.4 + acceleration: 2.38 + command: 45.0 + } + calibration { + speed: 7.4 + acceleration: 2.64 + command: 50.0 + } + calibration { + speed: 7.4 + acceleration: 2.92 + command: 55.0 + } + calibration { + speed: 7.4 + acceleration: 3.19 + command: 65.0 + } + calibration { + speed: 7.4 + acceleration: 3.21 + command: 65.0 + } + calibration { + speed: 7.4 + acceleration: 3.22 + command: 80.0 + } + calibration { + speed: 7.4 + acceleration: 3.23 + command: 75.0 + } + calibration { + speed: 7.6 + acceleration: -8.99 + command: -35.0 + } + calibration { + speed: 7.6 + acceleration: -7.5 + command: -33.0 + } + calibration { + speed: 7.6 + acceleration: -4.72 + command: -30.0 + } + calibration { + speed: 7.6 + acceleration: -2.64 + command: -27.0 + } + calibration { + speed: 7.6 + acceleration: -1.79 + command: -25.0 + } + calibration { + speed: 7.6 + acceleration: -0.71 + command: -22.0 + } + calibration { + speed: 7.6 + acceleration: -0.36 + command: -20.0 + } + calibration { + speed: 7.6 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 7.6 + acceleration: -0.25 + command: 15.0 + } + calibration { + speed: 7.6 + acceleration: -0.2 + command: -17.0 + } + calibration { + speed: 7.6 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 7.6 + acceleration: -0.14 + command: 17.0 + } + calibration { + speed: 7.6 + acceleration: 0.02 + command: 20.0 + } + calibration { + speed: 7.6 + acceleration: 0.16 + command: 22.0 + } + calibration { + speed: 7.6 + acceleration: 0.52 + command: 25.0 + } + calibration { + speed: 7.6 + acceleration: 0.75 + command: 27.0 + } + calibration { + speed: 7.6 + acceleration: 1.12 + command: 30.0 + } + calibration { + speed: 7.6 + acceleration: 1.76 + command: 35.0 + } + calibration { + speed: 7.6 + acceleration: 2.2 + command: 40.0 + } + calibration { + speed: 7.6 + acceleration: 2.32 + command: 45.0 + } + calibration { + speed: 7.6 + acceleration: 2.58 + command: 50.0 + } + calibration { + speed: 7.6 + acceleration: 2.88 + command: 55.0 + } + calibration { + speed: 7.6 + acceleration: 3.16 + command: 60.0 + } + calibration { + speed: 7.6 + acceleration: 3.19 + command: 67.5 + } + calibration { + speed: 7.6 + acceleration: 3.22 + command: 75.0 + } + calibration { + speed: 7.6 + acceleration: 3.23 + command: 80.0 + } + calibration { + speed: 7.8 + acceleration: -8.99 + command: -35.0 + } + calibration { + speed: 7.8 + acceleration: -7.49 + command: -33.0 + } + calibration { + speed: 7.8 + acceleration: -4.71 + command: -30.0 + } + calibration { + speed: 7.8 + acceleration: -2.66 + command: -27.0 + } + calibration { + speed: 7.8 + acceleration: -1.8 + command: -25.0 + } + calibration { + speed: 7.8 + acceleration: -0.72 + command: -22.0 + } + calibration { + speed: 7.8 + acceleration: -0.38 + command: -20.0 + } + calibration { + speed: 7.8 + acceleration: -0.25 + command: 15.0 + } + calibration { + speed: 7.8 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 7.8 + acceleration: -0.2 + command: -15.0 + } + calibration { + speed: 7.8 + acceleration: -0.13 + command: 17.0 + } + calibration { + speed: 7.8 + acceleration: 0.03 + command: 20.0 + } + calibration { + speed: 7.8 + acceleration: 0.16 + command: 22.0 + } + calibration { + speed: 7.8 + acceleration: 0.51 + command: 25.0 + } + calibration { + speed: 7.8 + acceleration: 0.71 + command: 27.0 + } + calibration { + speed: 7.8 + acceleration: 1.08 + command: 30.0 + } + calibration { + speed: 7.8 + acceleration: 1.73 + command: 35.0 + } + calibration { + speed: 7.8 + acceleration: 2.15 + command: 40.0 + } + calibration { + speed: 7.8 + acceleration: 2.28 + command: 45.0 + } + calibration { + speed: 7.8 + acceleration: 2.52 + command: 50.0 + } + calibration { + speed: 7.8 + acceleration: 2.83 + command: 55.0 + } + calibration { + speed: 7.8 + acceleration: 3.14 + command: 60.0 + } + calibration { + speed: 7.8 + acceleration: 3.18 + command: 70.0 + } + calibration { + speed: 7.8 + acceleration: 3.2 + command: 65.0 + } + calibration { + speed: 7.8 + acceleration: 3.21 + command: 75.0 + } + calibration { + speed: 7.8 + acceleration: 3.24 + command: 80.0 + } + calibration { + speed: 8.0 + acceleration: -9.0 + command: -35.0 + } + calibration { + speed: 8.0 + acceleration: -7.48 + command: -33.0 + } + calibration { + speed: 8.0 + acceleration: -4.7 + command: -30.0 + } + calibration { + speed: 8.0 + acceleration: -2.68 + command: -27.0 + } + calibration { + speed: 8.0 + acceleration: -1.81 + command: -25.0 + } + calibration { + speed: 8.0 + acceleration: -0.71 + command: -22.0 + } + calibration { + speed: 8.0 + acceleration: -0.35 + command: -20.0 + } + calibration { + speed: 8.0 + acceleration: -0.26 + command: 15.0 + } + calibration { + speed: 8.0 + acceleration: -0.23 + command: -14.0 + } + calibration { + speed: 8.0 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 8.0 + acceleration: -0.13 + command: 17.0 + } + calibration { + speed: 8.0 + acceleration: -0.02 + command: 20.0 + } + calibration { + speed: 8.0 + acceleration: 0.16 + command: 22.0 + } + calibration { + speed: 8.0 + acceleration: 0.48 + command: 25.0 + } + calibration { + speed: 8.0 + acceleration: 0.69 + command: 27.0 + } + calibration { + speed: 8.0 + acceleration: 1.05 + command: 30.0 + } + calibration { + speed: 8.0 + acceleration: 1.69 + command: 35.0 + } + calibration { + speed: 8.0 + acceleration: 2.11 + command: 40.0 + } + calibration { + speed: 8.0 + acceleration: 2.25 + command: 45.0 + } + calibration { + speed: 8.0 + acceleration: 2.48 + command: 50.0 + } + calibration { + speed: 8.0 + acceleration: 2.79 + command: 55.0 + } + calibration { + speed: 8.0 + acceleration: 3.11 + command: 60.0 + } + calibration { + speed: 8.0 + acceleration: 3.17 + command: 70.0 + } + calibration { + speed: 8.0 + acceleration: 3.21 + command: 65.0 + } + calibration { + speed: 8.0 + acceleration: 3.22 + command: 75.0 + } + calibration { + speed: 8.0 + acceleration: 3.23 + command: 80.0 + } + calibration { + speed: 8.2 + acceleration: -9.03 + command: -35.0 + } + calibration { + speed: 8.2 + acceleration: -7.48 + command: -33.0 + } + calibration { + speed: 8.2 + acceleration: -4.69 + command: -30.0 + } + calibration { + speed: 8.2 + acceleration: -2.68 + command: -27.0 + } + calibration { + speed: 8.2 + acceleration: -1.84 + command: -25.0 + } + calibration { + speed: 8.2 + acceleration: -0.68 + command: -22.0 + } + calibration { + speed: 8.2 + acceleration: -0.37 + command: -20.0 + } + calibration { + speed: 8.2 + acceleration: -0.3 + command: -15.0 + } + calibration { + speed: 8.2 + acceleration: -0.26 + command: -13.0 + } + calibration { + speed: 8.2 + acceleration: -0.24 + command: 15.0 + } + calibration { + speed: 8.2 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 8.2 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 8.2 + acceleration: -0.08 + command: 20.0 + } + calibration { + speed: 8.2 + acceleration: 0.14 + command: 22.0 + } + calibration { + speed: 8.2 + acceleration: 0.47 + command: 25.0 + } + calibration { + speed: 8.2 + acceleration: 0.67 + command: 27.0 + } + calibration { + speed: 8.2 + acceleration: 1.01 + command: 30.0 + } + calibration { + speed: 8.2 + acceleration: 1.66 + command: 35.0 + } + calibration { + speed: 8.2 + acceleration: 2.07 + command: 40.0 + } + calibration { + speed: 8.2 + acceleration: 2.23 + command: 45.0 + } + calibration { + speed: 8.2 + acceleration: 2.46 + command: 50.0 + } + calibration { + speed: 8.2 + acceleration: 2.77 + command: 55.0 + } + calibration { + speed: 8.2 + acceleration: 3.09 + command: 60.0 + } + calibration { + speed: 8.2 + acceleration: 3.15 + command: 70.0 + } + calibration { + speed: 8.2 + acceleration: 3.21 + command: 80.0 + } + calibration { + speed: 8.2 + acceleration: 3.22 + command: 65.0 + } + calibration { + speed: 8.2 + acceleration: 3.24 + command: 75.0 + } + calibration { + speed: 8.4 + acceleration: -9.08 + command: -35.0 + } + calibration { + speed: 8.4 + acceleration: -7.49 + command: -33.0 + } + calibration { + speed: 8.4 + acceleration: -4.68 + command: -30.0 + } + calibration { + speed: 8.4 + acceleration: -2.65 + command: -27.0 + } + calibration { + speed: 8.4 + acceleration: -1.83 + command: -25.0 + } + calibration { + speed: 8.4 + acceleration: -0.69 + command: -22.0 + } + calibration { + speed: 8.4 + acceleration: -0.37 + command: -20.0 + } + calibration { + speed: 8.4 + acceleration: -0.3 + command: -15.0 + } + calibration { + speed: 8.4 + acceleration: -0.27 + command: -17.0 + } + calibration { + speed: 8.4 + acceleration: -0.25 + command: 1.0 + } + calibration { + speed: 8.4 + acceleration: -0.19 + command: 17.0 + } + calibration { + speed: 8.4 + acceleration: -0.08 + command: 20.0 + } + calibration { + speed: 8.4 + acceleration: 0.15 + command: 22.0 + } + calibration { + speed: 8.4 + acceleration: 0.43 + command: 25.0 + } + calibration { + speed: 8.4 + acceleration: 0.63 + command: 27.0 + } + calibration { + speed: 8.4 + acceleration: 0.99 + command: 30.0 + } + calibration { + speed: 8.4 + acceleration: 1.61 + command: 35.0 + } + calibration { + speed: 8.4 + acceleration: 2.03 + command: 40.0 + } + calibration { + speed: 8.4 + acceleration: 2.19 + command: 45.0 + } + calibration { + speed: 8.4 + acceleration: 2.43 + command: 50.0 + } + calibration { + speed: 8.4 + acceleration: 2.77 + command: 55.0 + } + calibration { + speed: 8.4 + acceleration: 3.07 + command: 60.0 + } + calibration { + speed: 8.4 + acceleration: 3.14 + command: 70.0 + } + calibration { + speed: 8.4 + acceleration: 3.18 + command: 80.0 + } + calibration { + speed: 8.4 + acceleration: 3.23 + command: 65.0 + } + calibration { + speed: 8.4 + acceleration: 3.26 + command: 75.0 + } + calibration { + speed: 8.6 + acceleration: -9.15 + command: -35.0 + } + calibration { + speed: 8.6 + acceleration: -7.5 + command: -33.0 + } + calibration { + speed: 8.6 + acceleration: -4.69 + command: -30.0 + } + calibration { + speed: 8.6 + acceleration: -2.6 + command: -27.0 + } + calibration { + speed: 8.6 + acceleration: -1.79 + command: -25.0 + } + calibration { + speed: 8.6 + acceleration: -0.68 + command: -22.0 + } + calibration { + speed: 8.6 + acceleration: -0.39 + command: -20.0 + } + calibration { + speed: 8.6 + acceleration: -0.3 + command: 15.0 + } + calibration { + speed: 8.6 + acceleration: -0.27 + command: -13.0 + } + calibration { + speed: 8.6 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 8.6 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 8.6 + acceleration: -0.18 + command: 17.0 + } + calibration { + speed: 8.6 + acceleration: -0.06 + command: 20.0 + } + calibration { + speed: 8.6 + acceleration: 0.1 + command: 22.0 + } + calibration { + speed: 8.6 + acceleration: 0.42 + command: 25.0 + } + calibration { + speed: 8.6 + acceleration: 0.62 + command: 27.0 + } + calibration { + speed: 8.6 + acceleration: 0.96 + command: 30.0 + } + calibration { + speed: 8.6 + acceleration: 1.56 + command: 35.0 + } + calibration { + speed: 8.6 + acceleration: 1.99 + command: 40.0 + } + calibration { + speed: 8.6 + acceleration: 2.15 + command: 45.0 + } + calibration { + speed: 8.6 + acceleration: 2.4 + command: 50.0 + } + calibration { + speed: 8.6 + acceleration: 2.77 + command: 55.0 + } + calibration { + speed: 8.6 + acceleration: 3.06 + command: 60.0 + } + calibration { + speed: 8.6 + acceleration: 3.14 + command: 70.0 + } + calibration { + speed: 8.6 + acceleration: 3.15 + command: 80.0 + } + calibration { + speed: 8.6 + acceleration: 3.23 + command: 65.0 + } + calibration { + speed: 8.6 + acceleration: 3.27 + command: 75.0 + } + calibration { + speed: 8.8 + acceleration: -9.22 + command: -35.0 + } + calibration { + speed: 8.8 + acceleration: -7.55 + command: -33.0 + } + calibration { + speed: 8.8 + acceleration: -4.7 + command: -30.0 + } + calibration { + speed: 8.8 + acceleration: -2.57 + command: -27.0 + } + calibration { + speed: 8.8 + acceleration: -1.77 + command: -25.0 + } + calibration { + speed: 8.8 + acceleration: -0.71 + command: -22.0 + } + calibration { + speed: 8.8 + acceleration: -0.34 + command: -20.0 + } + calibration { + speed: 8.8 + acceleration: -0.3 + command: -13.0 + } + calibration { + speed: 8.8 + acceleration: -0.25 + command: 15.0 + } + calibration { + speed: 8.8 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 8.8 + acceleration: -0.21 + command: -15.0 + } + calibration { + speed: 8.8 + acceleration: -0.16 + command: 17.0 + } + calibration { + speed: 8.8 + acceleration: -0.05 + command: 20.0 + } + calibration { + speed: 8.8 + acceleration: 0.12 + command: 22.0 + } + calibration { + speed: 8.8 + acceleration: 0.4 + command: 25.0 + } + calibration { + speed: 8.8 + acceleration: 0.61 + command: 27.0 + } + calibration { + speed: 8.8 + acceleration: 0.93 + command: 30.0 + } + calibration { + speed: 8.8 + acceleration: 1.51 + command: 35.0 + } + calibration { + speed: 8.8 + acceleration: 1.95 + command: 40.0 + } + calibration { + speed: 8.8 + acceleration: 2.1 + command: 45.0 + } + calibration { + speed: 8.8 + acceleration: 2.37 + command: 50.0 + } + calibration { + speed: 8.8 + acceleration: 2.75 + command: 55.0 + } + calibration { + speed: 8.8 + acceleration: 3.04 + command: 60.0 + } + calibration { + speed: 8.8 + acceleration: 3.12 + command: 80.0 + } + calibration { + speed: 8.8 + acceleration: 3.15 + command: 70.0 + } + calibration { + speed: 8.8 + acceleration: 3.23 + command: 65.0 + } + calibration { + speed: 8.8 + acceleration: 3.25 + command: 75.0 + } + calibration { + speed: 9.0 + acceleration: -9.27 + command: -35.0 + } + calibration { + speed: 9.0 + acceleration: -7.6 + command: -33.0 + } + calibration { + speed: 9.0 + acceleration: -4.71 + command: -30.0 + } + calibration { + speed: 9.0 + acceleration: -2.57 + command: -27.0 + } + calibration { + speed: 9.0 + acceleration: -1.8 + command: -25.0 + } + calibration { + speed: 9.0 + acceleration: -0.74 + command: -22.0 + } + calibration { + speed: 9.0 + acceleration: -0.41 + command: -20.0 + } + calibration { + speed: 9.0 + acceleration: -0.29 + command: -15.0 + } + calibration { + speed: 9.0 + acceleration: -0.27 + command: -13.0 + } + calibration { + speed: 9.0 + acceleration: -0.24 + command: 15.0 + } + calibration { + speed: 9.0 + acceleration: -0.2 + command: 17.0 + } + calibration { + speed: 9.0 + acceleration: -0.19 + command: -17.0 + } + calibration { + speed: 9.0 + acceleration: -0.15 + command: 20.0 + } + calibration { + speed: 9.0 + acceleration: 0.12 + command: 22.0 + } + calibration { + speed: 9.0 + acceleration: 0.38 + command: 25.0 + } + calibration { + speed: 9.0 + acceleration: 0.57 + command: 27.0 + } + calibration { + speed: 9.0 + acceleration: 0.88 + command: 30.0 + } + calibration { + speed: 9.0 + acceleration: 1.47 + command: 35.0 + } + calibration { + speed: 9.0 + acceleration: 1.91 + command: 40.0 + } + calibration { + speed: 9.0 + acceleration: 2.07 + command: 45.0 + } + calibration { + speed: 9.0 + acceleration: 2.33 + command: 50.0 + } + calibration { + speed: 9.0 + acceleration: 2.71 + command: 55.0 + } + calibration { + speed: 9.0 + acceleration: 3.03 + command: 60.0 + } + calibration { + speed: 9.0 + acceleration: 3.09 + command: 80.0 + } + calibration { + speed: 9.0 + acceleration: 3.16 + command: 70.0 + } + calibration { + speed: 9.0 + acceleration: 3.21 + command: 70.0 + } + calibration { + speed: 9.2 + acceleration: -9.34 + command: -35.0 + } + calibration { + speed: 9.2 + acceleration: -7.67 + command: -33.0 + } + calibration { + speed: 9.2 + acceleration: -4.69 + command: -30.0 + } + calibration { + speed: 9.2 + acceleration: -2.61 + command: -27.0 + } + calibration { + speed: 9.2 + acceleration: -1.85 + command: -25.0 + } + calibration { + speed: 9.2 + acceleration: -0.71 + command: -22.0 + } + calibration { + speed: 9.2 + acceleration: -0.39 + command: -20.0 + } + calibration { + speed: 9.2 + acceleration: -0.28 + command: -15.0 + } + calibration { + speed: 9.2 + acceleration: -0.27 + command: 15.0 + } + calibration { + speed: 9.2 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 9.2 + acceleration: -0.21 + command: -13.0 + } + calibration { + speed: 9.2 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 9.2 + acceleration: -0.08 + command: 20.0 + } + calibration { + speed: 9.2 + acceleration: 0.1 + command: 22.0 + } + calibration { + speed: 9.2 + acceleration: 0.34 + command: 25.0 + } + calibration { + speed: 9.2 + acceleration: 0.56 + command: 27.0 + } + calibration { + speed: 9.2 + acceleration: 0.87 + command: 30.0 + } + calibration { + speed: 9.2 + acceleration: 1.44 + command: 35.0 + } + calibration { + speed: 9.2 + acceleration: 1.86 + command: 40.0 + } + calibration { + speed: 9.2 + acceleration: 2.05 + command: 45.0 + } + calibration { + speed: 9.2 + acceleration: 2.3 + command: 50.0 + } + calibration { + speed: 9.2 + acceleration: 2.65 + command: 55.0 + } + calibration { + speed: 9.2 + acceleration: 3.02 + command: 60.0 + } + calibration { + speed: 9.2 + acceleration: 3.05 + command: 80.0 + } + calibration { + speed: 9.2 + acceleration: 3.17 + command: 75.0 + } + calibration { + speed: 9.2 + acceleration: 3.18 + command: 70.0 + } + calibration { + speed: 9.2 + acceleration: 3.2 + command: 65.0 + } + calibration { + speed: 9.4 + acceleration: -9.37 + command: -35.0 + } + calibration { + speed: 9.4 + acceleration: -7.76 + command: -33.0 + } + calibration { + speed: 9.4 + acceleration: -4.65 + command: -30.0 + } + calibration { + speed: 9.4 + acceleration: -2.66 + command: -27.0 + } + calibration { + speed: 9.4 + acceleration: -1.87 + command: -25.0 + } + calibration { + speed: 9.4 + acceleration: -0.73 + command: -22.0 + } + calibration { + speed: 9.4 + acceleration: -0.37 + command: -20.0 + } + calibration { + speed: 9.4 + acceleration: -0.31 + command: 15.0 + } + calibration { + speed: 9.4 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 9.4 + acceleration: -0.24 + command: -15.0 + } + calibration { + speed: 9.4 + acceleration: -0.16 + command: 17.0 + } + calibration { + speed: 9.4 + acceleration: -0.1 + command: 20.0 + } + calibration { + speed: 9.4 + acceleration: 0.1 + command: 22.0 + } + calibration { + speed: 9.4 + acceleration: 0.38 + command: 25.0 + } + calibration { + speed: 9.4 + acceleration: 0.53 + command: 27.0 + } + calibration { + speed: 9.4 + acceleration: 0.8 + command: 30.0 + } + calibration { + speed: 9.4 + acceleration: 1.38 + command: 35.0 + } + calibration { + speed: 9.4 + acceleration: 1.82 + command: 40.0 + } + calibration { + speed: 9.4 + acceleration: 2.04 + command: 45.0 + } + calibration { + speed: 9.4 + acceleration: 2.28 + command: 50.0 + } + calibration { + speed: 9.4 + acceleration: 2.6 + command: 55.0 + } + calibration { + speed: 9.4 + acceleration: 2.99 + command: 60.0 + } + calibration { + speed: 9.4 + acceleration: 3.02 + command: 80.0 + } + calibration { + speed: 9.4 + acceleration: 3.15 + command: 75.0 + } + calibration { + speed: 9.4 + acceleration: 3.19 + command: 70.0 + } + calibration { + speed: 9.4 + acceleration: 3.2 + command: 65.0 + } + calibration { + speed: 9.6 + acceleration: -9.36 + command: -35.0 + } + calibration { + speed: 9.6 + acceleration: -7.87 + command: -33.0 + } + calibration { + speed: 9.6 + acceleration: -4.56 + command: -30.0 + } + calibration { + speed: 9.6 + acceleration: -2.68 + command: -27.0 + } + calibration { + speed: 9.6 + acceleration: -1.88 + command: -25.0 + } + calibration { + speed: 9.6 + acceleration: -0.73 + command: -22.0 + } + calibration { + speed: 9.6 + acceleration: -0.38 + command: -20.0 + } + calibration { + speed: 9.6 + acceleration: -0.29 + command: 15.0 + } + calibration { + speed: 9.6 + acceleration: -0.28 + command: -15.0 + } + calibration { + speed: 9.6 + acceleration: -0.27 + command: -13.0 + } + calibration { + speed: 9.6 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 9.6 + acceleration: -0.2 + command: 17.0 + } + calibration { + speed: 9.6 + acceleration: -0.07 + command: 20.0 + } + calibration { + speed: 9.6 + acceleration: 0.09 + command: 22.0 + } + calibration { + speed: 9.6 + acceleration: 0.34 + command: 25.0 + } + calibration { + speed: 9.6 + acceleration: 0.53 + command: 27.0 + } + calibration { + speed: 9.6 + acceleration: 0.8 + command: 30.0 + } + calibration { + speed: 9.6 + acceleration: 1.36 + command: 35.0 + } + calibration { + speed: 9.6 + acceleration: 1.79 + command: 40.0 + } + calibration { + speed: 9.6 + acceleration: 2.01 + command: 45.0 + } + calibration { + speed: 9.6 + acceleration: 2.25 + command: 50.0 + } + calibration { + speed: 9.6 + acceleration: 2.57 + command: 55.0 + } + calibration { + speed: 9.6 + acceleration: 2.98 + command: 60.0 + } + calibration { + speed: 9.6 + acceleration: 2.99 + command: 80.0 + } + calibration { + speed: 9.6 + acceleration: 3.15 + command: 75.0 + } + calibration { + speed: 9.6 + acceleration: 3.2 + command: 70.0 + } + calibration { + speed: 9.6 + acceleration: 3.21 + command: 65.0 + } + calibration { + speed: 9.8 + acceleration: -9.31 + command: -35.0 + } + calibration { + speed: 9.8 + acceleration: -7.97 + command: -33.0 + } + calibration { + speed: 9.8 + acceleration: -4.51 + command: -30.0 + } + calibration { + speed: 9.8 + acceleration: -2.67 + command: -27.0 + } + calibration { + speed: 9.8 + acceleration: -1.9 + command: -25.0 + } + calibration { + speed: 9.8 + acceleration: -0.73 + command: -22.0 + } + calibration { + speed: 9.8 + acceleration: -0.39 + command: -20.0 + } + calibration { + speed: 9.8 + acceleration: -0.28 + command: -14.0 + } + calibration { + speed: 9.8 + acceleration: -0.27 + command: -17.0 + } + calibration { + speed: 9.8 + acceleration: -0.24 + command: 15.0 + } + calibration { + speed: 9.8 + acceleration: -0.22 + command: 17.0 + } + calibration { + speed: 9.8 + acceleration: -0.13 + command: 20.0 + } + calibration { + speed: 9.8 + acceleration: 0.08 + command: 22.0 + } + calibration { + speed: 9.8 + acceleration: 0.34 + command: 25.0 + } + calibration { + speed: 9.8 + acceleration: 0.5 + command: 27.0 + } + calibration { + speed: 9.8 + acceleration: 0.78 + command: 30.0 + } + calibration { + speed: 9.8 + acceleration: 1.35 + command: 35.0 + } + calibration { + speed: 9.8 + acceleration: 1.76 + command: 40.0 + } + calibration { + speed: 9.8 + acceleration: 1.97 + command: 45.0 + } + calibration { + speed: 9.8 + acceleration: 2.21 + command: 50.0 + } + calibration { + speed: 9.8 + acceleration: 2.55 + command: 55.0 + } + calibration { + speed: 9.8 + acceleration: 2.96 + command: 60.0 + } + calibration { + speed: 9.8 + acceleration: 2.98 + command: 80.0 + } + calibration { + speed: 9.8 + acceleration: 3.15 + command: 75.0 + } + calibration { + speed: 9.8 + acceleration: 3.2 + command: 70.0 + } + calibration { + speed: 9.8 + acceleration: 3.21 + command: 65.0 + } + calibration { + speed: 10.0 + acceleration: -9.18 + command: -35.0 + } + calibration { + speed: 10.0 + acceleration: -8.04 + command: -33.0 + } + calibration { + speed: 10.0 + acceleration: -4.75 + command: -30.0 + } + calibration { + speed: 10.0 + acceleration: -2.65 + command: -27.0 + } + calibration { + speed: 10.0 + acceleration: -1.92 + command: -25.0 + } + calibration { + speed: 10.0 + acceleration: -0.75 + command: -22.0 + } + calibration { + speed: 10.0 + acceleration: -0.36 + command: -20.0 + } + calibration { + speed: 10.0 + acceleration: -0.29 + command: -13.0 + } + calibration { + speed: 10.0 + acceleration: -0.27 + command: -15.0 + } + calibration { + speed: 10.0 + acceleration: -0.25 + command: 15.0 + } + calibration { + speed: 10.0 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 10.0 + acceleration: -0.21 + command: 17.0 + } + calibration { + speed: 10.0 + acceleration: -0.08 + command: 20.0 + } + calibration { + speed: 10.0 + acceleration: 0.08 + command: 22.0 + } + calibration { + speed: 10.0 + acceleration: 0.32 + command: 25.0 + } + calibration { + speed: 10.0 + acceleration: 0.49 + command: 27.0 + } + calibration { + speed: 10.0 + acceleration: 0.75 + command: 30.0 + } + calibration { + speed: 10.0 + acceleration: 1.3 + command: 35.0 + } + calibration { + speed: 10.0 + acceleration: 1.71 + command: 40.0 + } + calibration { + speed: 10.0 + acceleration: 1.92 + command: 45.0 + } + calibration { + speed: 10.0 + acceleration: 2.17 + command: 50.0 + } + calibration { + speed: 10.0 + acceleration: 2.53 + command: 55.0 + } + calibration { + speed: 10.0 + acceleration: 2.94 + command: 60.0 + } + calibration { + speed: 10.0 + acceleration: 2.99 + command: 80.0 + } + calibration { + speed: 10.0 + acceleration: 3.14 + command: 75.0 + } + calibration { + speed: 10.0 + acceleration: 3.19 + command: 70.0 + } + calibration { + speed: 10.0 + acceleration: 3.21 + command: 65.0 + } + } +} diff --git a/apollo_control/conf/lincoln_062145.pb.txt b/apollo_control/conf/lincoln_062145.pb.txt new file mode 100644 index 0000000..6e76664 --- /dev/null +++ b/apollo_control/conf/lincoln_062145.pb.txt @@ -0,0 +1,8110 @@ +control_period: 0.01 +max_planning_interval_sec: 0.2 +max_planning_delay_threshold: 4.0 +action: STOP +soft_estop_brake: 50.0 +active_controllers: LAT_CONTROLLER +active_controllers: LON_CONTROLLER +max_steering_percentage_allowed: 100 +max_status_interval_sec: 0.1 +lat_controller_conf { + ts: 0.01 + preview_window: 0 + cf: 155494.663 + cr: 155494.663 + wheelbase: 2.85 + mass_fl: 520 + mass_fr: 520 + mass_rl: 520 + mass_rr: 520 + eps: 0.01 + matrix_q: 0.05 + matrix_q: 0.0 + matrix_q: 1.0 + matrix_q: 0.0 + cutoff_freq: 10 + mean_filter_window_size: 10 + steer_transmission_ratio: 16 + steer_single_direction_max_degree: 470 + max_iteration: 150 +} +lon_controller_conf { + ts: 0.01 + brake_deadzone: 15.5 + throttle_deadzone: 18.0 + speed_controller_input_limit: 2.0 + station_error_limit: 2.0 + preview_window: 20.0 + standstill_acceleration: -3.0 + station_pid_conf { + integrator_enable: false + integrator_saturation_level: 0.3 + kp: 0.2 + ki: 0.0 + kd: 0.0 + } + low_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 0.5 + ki: 0.3 + kd: 0.0 + } + high_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 1.0 + ki: 0.3 + kd: 0.0 + } + switch_speed: 2.0 + throttle_filter_conf { + cutoff_freq: 10 + } + brake_filter_conf { + cutoff_freq: 10 + } + acceleration_filter_conf { + cutoff_freq: 5 + } + calibration_table { + calibration { + speed: 0.0 + acceleration: -4.65 + command: -35.0 + } + calibration { + speed: 0.0 + acceleration: -3.85 + command: -33.0 + } + calibration { + speed: 0.0 + acceleration: -3.48 + command: -32.0 + } + calibration { + speed: 0.0 + acceleration: -3.13 + command: -31.0 + } + calibration { + speed: 0.0 + acceleration: -2.85 + command: -30.0 + } + calibration { + speed: 0.0 + acceleration: -2.53 + command: -29.0 + } + calibration { + speed: 0.0 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 0.0 + acceleration: -1.7 + command: -27.0 + } + calibration { + speed: 0.0 + acceleration: -1.19 + command: -26.0 + } + calibration { + speed: 0.0 + acceleration: -0.65 + command: -25.0 + } + calibration { + speed: 0.0 + acceleration: -0.3 + command: -24.0 + } + calibration { + speed: 0.0 + acceleration: 0.1 + command: -22.0 + } + calibration { + speed: 0.0 + acceleration: 0.31 + command: -13.0 + } + calibration { + speed: 0.0 + acceleration: 0.34 + command: -20.0 + } + calibration { + speed: 0.0 + acceleration: 0.36 + command: -15.0 + } + calibration { + speed: 0.0 + acceleration: 0.38 + command: -17.0 + } + calibration { + speed: 0.0 + acceleration: 0.84 + command: 20.0 + } + calibration { + speed: 0.0 + acceleration: 0.97 + command: 22.0 + } + calibration { + speed: 0.0 + acceleration: 1.39 + command: 25.0 + } + calibration { + speed: 0.0 + acceleration: 1.46 + command: 27.0 + } + calibration { + speed: 0.0 + acceleration: 1.53 + command: 30.0 + } + calibration { + speed: 0.0 + acceleration: 1.6 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 1.69 + command: 40.0 + } + calibration { + speed: 0.0 + acceleration: 1.72 + command: 45.0 + } + calibration { + speed: 0.0 + acceleration: 1.88 + command: 50.0 + } + calibration { + speed: 0.0 + acceleration: 1.95 + command: 60.0 + } + calibration { + speed: 0.0 + acceleration: 1.96 + command: 62.5 + } + calibration { + speed: 0.0 + acceleration: 2.05 + command: 65.0 + } + calibration { + speed: 0.0 + acceleration: 2.07 + command: 75.0 + } + calibration { + speed: 0.0 + acceleration: 2.08 + command: 80.0 + } + calibration { + speed: 0.2 + acceleration: -4.95 + command: -35.0 + } + calibration { + speed: 0.2 + acceleration: -3.99 + command: -33.0 + } + calibration { + speed: 0.2 + acceleration: -3.61 + command: -32.0 + } + calibration { + speed: 0.2 + acceleration: -3.25 + command: -31.0 + } + calibration { + speed: 0.2 + acceleration: -2.91 + command: -30.0 + } + calibration { + speed: 0.2 + acceleration: -2.57 + command: -29.0 + } + calibration { + speed: 0.2 + acceleration: -2.24 + command: -28.0 + } + calibration { + speed: 0.2 + acceleration: -1.71 + command: -27.0 + } + calibration { + speed: 0.2 + acceleration: -1.2 + command: -26.0 + } + calibration { + speed: 0.2 + acceleration: -0.65 + command: -25.0 + } + calibration { + speed: 0.2 + acceleration: -0.3 + command: -24.0 + } + calibration { + speed: 0.2 + acceleration: 0.1 + command: -22.0 + } + calibration { + speed: 0.2 + acceleration: 0.31 + command: -13.0 + } + calibration { + speed: 0.2 + acceleration: 0.34 + command: -20.0 + } + calibration { + speed: 0.2 + acceleration: 0.36 + command: -15.0 + } + calibration { + speed: 0.2 + acceleration: 0.38 + command: -17.0 + } + calibration { + speed: 0.2 + acceleration: 0.84 + command: 20.0 + } + calibration { + speed: 0.2 + acceleration: 0.98 + command: 22.0 + } + calibration { + speed: 0.2 + acceleration: 1.42 + command: 25.0 + } + calibration { + speed: 0.2 + acceleration: 1.51 + command: 27.0 + } + calibration { + speed: 0.2 + acceleration: 1.58 + command: 30.0 + } + calibration { + speed: 0.2 + acceleration: 1.67 + command: 35.0 + } + calibration { + speed: 0.2 + acceleration: 1.77 + command: 40.0 + } + calibration { + speed: 0.2 + acceleration: 1.82 + command: 45.0 + } + calibration { + speed: 0.2 + acceleration: 1.99 + command: 50.0 + } + calibration { + speed: 0.2 + acceleration: 2.08 + command: 55.0 + } + calibration { + speed: 0.2 + acceleration: 2.09 + command: 60.0 + } + calibration { + speed: 0.2 + acceleration: 2.11 + command: 70.0 + } + calibration { + speed: 0.2 + acceleration: 2.18 + command: 65.0 + } + calibration { + speed: 0.2 + acceleration: 2.23 + command: 75.0 + } + calibration { + speed: 0.2 + acceleration: 2.25 + command: 80.0 + } + calibration { + speed: 0.4 + acceleration: -6.23 + command: -35.0 + } + calibration { + speed: 0.4 + acceleration: -4.63 + command: -33.0 + } + calibration { + speed: 0.4 + acceleration: -4.18 + command: -32.0 + } + calibration { + speed: 0.4 + acceleration: -3.79 + command: -31.0 + } + calibration { + speed: 0.4 + acceleration: -3.28 + command: -30.0 + } + calibration { + speed: 0.4 + acceleration: -2.87 + command: -29.0 + } + calibration { + speed: 0.4 + acceleration: -2.35 + command: -28.0 + } + calibration { + speed: 0.4 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 0.4 + acceleration: -1.22 + command: -26.0 + } + calibration { + speed: 0.4 + acceleration: -0.64 + command: -25.0 + } + calibration { + speed: 0.4 + acceleration: -0.34 + command: -24.0 + } + calibration { + speed: 0.4 + acceleration: -0.08 + command: -23.0 + } + calibration { + speed: 0.4 + acceleration: 0.11 + command: -22.0 + } + calibration { + speed: 0.4 + acceleration: 0.32 + command: -13.0 + } + calibration { + speed: 0.4 + acceleration: 0.34 + command: -17.5 + } + calibration { + speed: 0.4 + acceleration: 0.38 + command: -17.0 + } + calibration { + speed: 0.4 + acceleration: 0.91 + command: 20.0 + } + calibration { + speed: 0.4 + acceleration: 1.05 + command: 22.0 + } + calibration { + speed: 0.4 + acceleration: 1.51 + command: 25.0 + } + calibration { + speed: 0.4 + acceleration: 1.67 + command: 27.0 + } + calibration { + speed: 0.4 + acceleration: 1.75 + command: 30.0 + } + calibration { + speed: 0.4 + acceleration: 1.86 + command: 35.0 + } + calibration { + speed: 0.4 + acceleration: 2.0 + command: 40.0 + } + calibration { + speed: 0.4 + acceleration: 2.08 + command: 45.0 + } + calibration { + speed: 0.4 + acceleration: 2.28 + command: 50.0 + } + calibration { + speed: 0.4 + acceleration: 2.35 + command: 55.0 + } + calibration { + speed: 0.4 + acceleration: 2.38 + command: 70.0 + } + calibration { + speed: 0.4 + acceleration: 2.42 + command: 60.0 + } + calibration { + speed: 0.4 + acceleration: 2.44 + command: 65.0 + } + calibration { + speed: 0.4 + acceleration: 2.63 + command: 77.5 + } + calibration { + speed: 0.6 + acceleration: -7.72 + command: -35.0 + } + calibration { + speed: 0.6 + acceleration: -5.35 + command: -33.0 + } + calibration { + speed: 0.6 + acceleration: -4.89 + command: -32.0 + } + calibration { + speed: 0.6 + acceleration: -4.29 + command: -31.0 + } + calibration { + speed: 0.6 + acceleration: -3.59 + command: -30.0 + } + calibration { + speed: 0.6 + acceleration: -3.05 + command: -29.0 + } + calibration { + speed: 0.6 + acceleration: -2.4 + command: -28.0 + } + calibration { + speed: 0.6 + acceleration: -1.83 + command: -27.0 + } + calibration { + speed: 0.6 + acceleration: -1.26 + command: -26.0 + } + calibration { + speed: 0.6 + acceleration: -0.66 + command: -25.0 + } + calibration { + speed: 0.6 + acceleration: -0.39 + command: -24.0 + } + calibration { + speed: 0.6 + acceleration: -0.13 + command: -23.0 + } + calibration { + speed: 0.6 + acceleration: 0.08 + command: -22.0 + } + calibration { + speed: 0.6 + acceleration: 0.27 + command: -13.0 + } + calibration { + speed: 0.6 + acceleration: 0.32 + command: -15.0 + } + calibration { + speed: 0.6 + acceleration: 0.33 + command: -17.0 + } + calibration { + speed: 0.6 + acceleration: 0.34 + command: -20.0 + } + calibration { + speed: 0.6 + acceleration: 0.96 + command: 20.0 + } + calibration { + speed: 0.6 + acceleration: 1.14 + command: 22.0 + } + calibration { + speed: 0.6 + acceleration: 1.65 + command: 25.0 + } + calibration { + speed: 0.6 + acceleration: 1.85 + command: 27.0 + } + calibration { + speed: 0.6 + acceleration: 1.94 + command: 30.0 + } + calibration { + speed: 0.6 + acceleration: 2.08 + command: 35.0 + } + calibration { + speed: 0.6 + acceleration: 2.21 + command: 40.0 + } + calibration { + speed: 0.6 + acceleration: 2.3 + command: 45.0 + } + calibration { + speed: 0.6 + acceleration: 2.48 + command: 50.0 + } + calibration { + speed: 0.6 + acceleration: 2.57 + command: 55.0 + } + calibration { + speed: 0.6 + acceleration: 2.61 + command: 60.0 + } + calibration { + speed: 0.6 + acceleration: 2.62 + command: 65.0 + } + calibration { + speed: 0.6 + acceleration: 2.64 + command: 70.0 + } + calibration { + speed: 0.6 + acceleration: 2.83 + command: 80.0 + } + calibration { + speed: 0.6 + acceleration: 2.84 + command: 75.0 + } + calibration { + speed: 0.8 + acceleration: -8.33 + command: -35.0 + } + calibration { + speed: 0.8 + acceleration: -5.59 + command: -33.0 + } + calibration { + speed: 0.8 + acceleration: -5.03 + command: -32.0 + } + calibration { + speed: 0.8 + acceleration: -4.33 + command: -31.0 + } + calibration { + speed: 0.8 + acceleration: -3.58 + command: -30.0 + } + calibration { + speed: 0.8 + acceleration: -2.98 + command: -29.0 + } + calibration { + speed: 0.8 + acceleration: -2.35 + command: -28.0 + } + calibration { + speed: 0.8 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 0.8 + acceleration: -1.25 + command: -26.0 + } + calibration { + speed: 0.8 + acceleration: -0.68 + command: -25.0 + } + calibration { + speed: 0.8 + acceleration: -0.43 + command: -24.0 + } + calibration { + speed: 0.8 + acceleration: -0.09 + command: -23.0 + } + calibration { + speed: 0.8 + acceleration: 0.03 + command: -22.0 + } + calibration { + speed: 0.8 + acceleration: 0.22 + command: -13.0 + } + calibration { + speed: 0.8 + acceleration: 0.25 + command: -20.0 + } + calibration { + speed: 0.8 + acceleration: 0.29 + command: -15.0 + } + calibration { + speed: 0.8 + acceleration: 0.31 + command: -17.0 + } + calibration { + speed: 0.8 + acceleration: 0.98 + command: 20.0 + } + calibration { + speed: 0.8 + acceleration: 1.18 + command: 22.0 + } + calibration { + speed: 0.8 + acceleration: 1.77 + command: 25.0 + } + calibration { + speed: 0.8 + acceleration: 2.04 + command: 27.0 + } + calibration { + speed: 0.8 + acceleration: 2.13 + command: 30.0 + } + calibration { + speed: 0.8 + acceleration: 2.26 + command: 35.0 + } + calibration { + speed: 0.8 + acceleration: 2.41 + command: 40.0 + } + calibration { + speed: 0.8 + acceleration: 2.48 + command: 45.0 + } + calibration { + speed: 0.8 + acceleration: 2.62 + command: 50.0 + } + calibration { + speed: 0.8 + acceleration: 2.67 + command: 60.0 + } + calibration { + speed: 0.8 + acceleration: 2.69 + command: 60.0 + } + calibration { + speed: 0.8 + acceleration: 2.71 + command: 70.0 + } + calibration { + speed: 0.8 + acceleration: 2.88 + command: 80.0 + } + calibration { + speed: 0.8 + acceleration: 2.9 + command: 75.0 + } + calibration { + speed: 1.0 + acceleration: -8.54 + command: -35.0 + } + calibration { + speed: 1.0 + acceleration: -5.49 + command: -33.0 + } + calibration { + speed: 1.0 + acceleration: -4.92 + command: -32.0 + } + calibration { + speed: 1.0 + acceleration: -4.17 + command: -31.0 + } + calibration { + speed: 1.0 + acceleration: -3.49 + command: -30.0 + } + calibration { + speed: 1.0 + acceleration: -2.9 + command: -29.0 + } + calibration { + speed: 1.0 + acceleration: -2.33 + command: -28.0 + } + calibration { + speed: 1.0 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 1.0 + acceleration: -1.25 + command: -26.0 + } + calibration { + speed: 1.0 + acceleration: -0.71 + command: -25.0 + } + calibration { + speed: 1.0 + acceleration: -0.44 + command: -24.0 + } + calibration { + speed: 1.0 + acceleration: -0.12 + command: -23.0 + } + calibration { + speed: 1.0 + acceleration: 0.17 + command: -13.0 + } + calibration { + speed: 1.0 + acceleration: 0.21 + command: -20.0 + } + calibration { + speed: 1.0 + acceleration: 0.25 + command: -16.0 + } + calibration { + speed: 1.0 + acceleration: 0.99 + command: 20.0 + } + calibration { + speed: 1.0 + acceleration: 1.22 + command: 22.0 + } + calibration { + speed: 1.0 + acceleration: 1.86 + command: 25.0 + } + calibration { + speed: 1.0 + acceleration: 2.21 + command: 27.0 + } + calibration { + speed: 1.0 + acceleration: 2.27 + command: 30.0 + } + calibration { + speed: 1.0 + acceleration: 2.45 + command: 35.0 + } + calibration { + speed: 1.0 + acceleration: 2.6 + command: 40.0 + } + calibration { + speed: 1.0 + acceleration: 2.64 + command: 45.0 + } + calibration { + speed: 1.0 + acceleration: 2.67 + command: 65.0 + } + calibration { + speed: 1.0 + acceleration: 2.73 + command: 70.0 + } + calibration { + speed: 1.0 + acceleration: 2.74 + command: 55.0 + } + calibration { + speed: 1.0 + acceleration: 2.75 + command: 55.0 + } + calibration { + speed: 1.0 + acceleration: 2.88 + command: 80.0 + } + calibration { + speed: 1.0 + acceleration: 2.9 + command: 75.0 + } + calibration { + speed: 1.2 + acceleration: -8.52 + command: -35.0 + } + calibration { + speed: 1.2 + acceleration: -5.31 + command: -33.0 + } + calibration { + speed: 1.2 + acceleration: -4.7 + command: -32.0 + } + calibration { + speed: 1.2 + acceleration: -4.01 + command: -31.0 + } + calibration { + speed: 1.2 + acceleration: -3.43 + command: -30.0 + } + calibration { + speed: 1.2 + acceleration: -2.87 + command: -29.0 + } + calibration { + speed: 1.2 + acceleration: -2.32 + command: -28.0 + } + calibration { + speed: 1.2 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 1.2 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 1.2 + acceleration: -0.71 + command: -25.0 + } + calibration { + speed: 1.2 + acceleration: -0.45 + command: -24.0 + } + calibration { + speed: 1.2 + acceleration: -0.17 + command: -23.0 + } + calibration { + speed: 1.2 + acceleration: 0.13 + command: -20.0 + } + calibration { + speed: 1.2 + acceleration: 0.14 + command: -13.0 + } + calibration { + speed: 1.2 + acceleration: 0.17 + command: -15.0 + } + calibration { + speed: 1.2 + acceleration: 0.18 + command: -17.0 + } + calibration { + speed: 1.2 + acceleration: 0.98 + command: 20.0 + } + calibration { + speed: 1.2 + acceleration: 1.25 + command: 22.0 + } + calibration { + speed: 1.2 + acceleration: 1.92 + command: 25.0 + } + calibration { + speed: 1.2 + acceleration: 2.29 + command: 27.0 + } + calibration { + speed: 1.2 + acceleration: 2.39 + command: 30.0 + } + calibration { + speed: 1.2 + acceleration: 2.62 + command: 35.0 + } + calibration { + speed: 1.2 + acceleration: 2.7 + command: 65.0 + } + calibration { + speed: 1.2 + acceleration: 2.74 + command: 70.0 + } + calibration { + speed: 1.2 + acceleration: 2.76 + command: 40.0 + } + calibration { + speed: 1.2 + acceleration: 2.79 + command: 45.0 + } + calibration { + speed: 1.2 + acceleration: 2.81 + command: 60.0 + } + calibration { + speed: 1.2 + acceleration: 2.84 + command: 52.5 + } + calibration { + speed: 1.2 + acceleration: 2.9 + command: 80.0 + } + calibration { + speed: 1.2 + acceleration: 2.93 + command: 75.0 + } + calibration { + speed: 1.4 + acceleration: -8.35 + command: -35.0 + } + calibration { + speed: 1.4 + acceleration: -5.14 + command: -33.0 + } + calibration { + speed: 1.4 + acceleration: -4.55 + command: -32.0 + } + calibration { + speed: 1.4 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 1.4 + acceleration: -3.42 + command: -30.0 + } + calibration { + speed: 1.4 + acceleration: -2.88 + command: -29.0 + } + calibration { + speed: 1.4 + acceleration: -2.29 + command: -28.0 + } + calibration { + speed: 1.4 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 1.4 + acceleration: -1.23 + command: -26.0 + } + calibration { + speed: 1.4 + acceleration: -0.69 + command: -25.0 + } + calibration { + speed: 1.4 + acceleration: -0.48 + command: -24.0 + } + calibration { + speed: 1.4 + acceleration: -0.23 + command: -23.0 + } + calibration { + speed: 1.4 + acceleration: 0.08 + command: -13.0 + } + calibration { + speed: 1.4 + acceleration: 0.11 + command: -17.0 + } + calibration { + speed: 1.4 + acceleration: 0.12 + command: -17.5 + } + calibration { + speed: 1.4 + acceleration: 0.96 + command: 20.0 + } + calibration { + speed: 1.4 + acceleration: 1.24 + command: 22.0 + } + calibration { + speed: 1.4 + acceleration: 1.96 + command: 25.0 + } + calibration { + speed: 1.4 + acceleration: 2.37 + command: 27.0 + } + calibration { + speed: 1.4 + acceleration: 2.48 + command: 30.0 + } + calibration { + speed: 1.4 + acceleration: 2.74 + command: 67.5 + } + calibration { + speed: 1.4 + acceleration: 2.75 + command: 35.0 + } + calibration { + speed: 1.4 + acceleration: 2.9 + command: 40.0 + } + calibration { + speed: 1.4 + acceleration: 2.92 + command: 60.0 + } + calibration { + speed: 1.4 + acceleration: 2.93 + command: 45.0 + } + calibration { + speed: 1.4 + acceleration: 2.95 + command: 55.0 + } + calibration { + speed: 1.4 + acceleration: 2.96 + command: 50.0 + } + calibration { + speed: 1.4 + acceleration: 2.98 + command: 80.0 + } + calibration { + speed: 1.4 + acceleration: 3.02 + command: 75.0 + } + calibration { + speed: 1.6 + acceleration: -8.12 + command: -35.0 + } + calibration { + speed: 1.6 + acceleration: -5.03 + command: -33.0 + } + calibration { + speed: 1.6 + acceleration: -4.47 + command: -32.0 + } + calibration { + speed: 1.6 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 1.6 + acceleration: -3.43 + command: -30.0 + } + calibration { + speed: 1.6 + acceleration: -2.88 + command: -29.0 + } + calibration { + speed: 1.6 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 1.6 + acceleration: -1.79 + command: -27.0 + } + calibration { + speed: 1.6 + acceleration: -1.19 + command: -26.0 + } + calibration { + speed: 1.6 + acceleration: -0.68 + command: -25.0 + } + calibration { + speed: 1.6 + acceleration: -0.55 + command: -24.0 + } + calibration { + speed: 1.6 + acceleration: -0.26 + command: -23.0 + } + calibration { + speed: 1.6 + acceleration: -0.13 + command: -22.0 + } + calibration { + speed: 1.6 + acceleration: -0.02 + command: 15.0 + } + calibration { + speed: 1.6 + acceleration: 0.0 + command: -20.0 + } + calibration { + speed: 1.6 + acceleration: 0.02 + command: -15.0 + } + calibration { + speed: 1.6 + acceleration: 0.04 + command: -13.0 + } + calibration { + speed: 1.6 + acceleration: 0.07 + command: -17.0 + } + calibration { + speed: 1.6 + acceleration: 0.93 + command: 20.0 + } + calibration { + speed: 1.6 + acceleration: 1.22 + command: 22.0 + } + calibration { + speed: 1.6 + acceleration: 2.0 + command: 25.0 + } + calibration { + speed: 1.6 + acceleration: 2.42 + command: 27.0 + } + calibration { + speed: 1.6 + acceleration: 2.56 + command: 30.0 + } + calibration { + speed: 1.6 + acceleration: 2.66 + command: 70.0 + } + calibration { + speed: 1.6 + acceleration: 2.71 + command: 65.0 + } + calibration { + speed: 1.6 + acceleration: 2.81 + command: 35.0 + } + calibration { + speed: 1.6 + acceleration: 3.01 + command: 40.0 + } + calibration { + speed: 1.6 + acceleration: 3.03 + command: 52.5 + } + calibration { + speed: 1.6 + acceleration: 3.06 + command: 55.0 + } + calibration { + speed: 1.6 + acceleration: 3.07 + command: 50.0 + } + calibration { + speed: 1.6 + acceleration: 3.11 + command: 80.0 + } + calibration { + speed: 1.6 + acceleration: 3.14 + command: 75.0 + } + calibration { + speed: 1.8 + acceleration: -7.96 + command: -35.0 + } + calibration { + speed: 1.8 + acceleration: -4.99 + command: -33.0 + } + calibration { + speed: 1.8 + acceleration: -4.48 + command: -32.0 + } + calibration { + speed: 1.8 + acceleration: -3.96 + command: -31.0 + } + calibration { + speed: 1.8 + acceleration: -3.42 + command: -30.0 + } + calibration { + speed: 1.8 + acceleration: -2.85 + command: -29.0 + } + calibration { + speed: 1.8 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 1.8 + acceleration: -1.75 + command: -27.0 + } + calibration { + speed: 1.8 + acceleration: -1.19 + command: -26.0 + } + calibration { + speed: 1.8 + acceleration: -0.74 + command: -25.0 + } + calibration { + speed: 1.8 + acceleration: -0.55 + command: -24.0 + } + calibration { + speed: 1.8 + acceleration: -0.28 + command: -23.0 + } + calibration { + speed: 1.8 + acceleration: -0.17 + command: -22.0 + } + calibration { + speed: 1.8 + acceleration: -0.03 + command: -17.0 + } + calibration { + speed: 1.8 + acceleration: -0.01 + command: -6.66666666667 + } + calibration { + speed: 1.8 + acceleration: 0.0 + command: -13.0 + } + calibration { + speed: 1.8 + acceleration: 0.88 + command: 20.0 + } + calibration { + speed: 1.8 + acceleration: 1.19 + command: 22.0 + } + calibration { + speed: 1.8 + acceleration: 2.01 + command: 25.0 + } + calibration { + speed: 1.8 + acceleration: 2.4 + command: 70.0 + } + calibration { + speed: 1.8 + acceleration: 2.46 + command: 27.0 + } + calibration { + speed: 1.8 + acceleration: 2.58 + command: 65.0 + } + calibration { + speed: 1.8 + acceleration: 2.62 + command: 30.0 + } + calibration { + speed: 1.8 + acceleration: 2.87 + command: 35.0 + } + calibration { + speed: 1.8 + acceleration: 3.09 + command: 40.0 + } + calibration { + speed: 1.8 + acceleration: 3.12 + command: 45.0 + } + calibration { + speed: 1.8 + acceleration: 3.14 + command: 60.0 + } + calibration { + speed: 1.8 + acceleration: 3.16 + command: 50.0 + } + calibration { + speed: 1.8 + acceleration: 3.17 + command: 55.0 + } + calibration { + speed: 1.8 + acceleration: 3.24 + command: 80.0 + } + calibration { + speed: 1.8 + acceleration: 3.26 + command: 75.0 + } + calibration { + speed: 2.0 + acceleration: -7.78 + command: -35.0 + } + calibration { + speed: 2.0 + acceleration: -5.03 + command: -33.0 + } + calibration { + speed: 2.0 + acceleration: -4.53 + command: -32.0 + } + calibration { + speed: 2.0 + acceleration: -4.0 + command: -31.0 + } + calibration { + speed: 2.0 + acceleration: -3.4 + command: -30.0 + } + calibration { + speed: 2.0 + acceleration: -2.81 + command: -29.0 + } + calibration { + speed: 2.0 + acceleration: -2.28 + command: -28.0 + } + calibration { + speed: 2.0 + acceleration: -1.69 + command: -27.0 + } + calibration { + speed: 2.0 + acceleration: -1.14 + command: -26.0 + } + calibration { + speed: 2.0 + acceleration: -0.79 + command: -25.0 + } + calibration { + speed: 2.0 + acceleration: -0.53 + command: -24.0 + } + calibration { + speed: 2.0 + acceleration: -0.3 + command: -23.0 + } + calibration { + speed: 2.0 + acceleration: -0.2 + command: -22.0 + } + calibration { + speed: 2.0 + acceleration: -0.1 + command: -17.0 + } + calibration { + speed: 2.0 + acceleration: -0.09 + command: -20.0 + } + calibration { + speed: 2.0 + acceleration: -0.08 + command: -15.0 + } + calibration { + speed: 2.0 + acceleration: -0.07 + command: 1.0 + } + calibration { + speed: 2.0 + acceleration: 0.8 + command: 20.0 + } + calibration { + speed: 2.0 + acceleration: 1.13 + command: 22.0 + } + calibration { + speed: 2.0 + acceleration: 2.0 + command: 25.0 + } + calibration { + speed: 2.0 + acceleration: 2.05 + command: 70.0 + } + calibration { + speed: 2.0 + acceleration: 2.35 + command: 65.0 + } + calibration { + speed: 2.0 + acceleration: 2.46 + command: 27.0 + } + calibration { + speed: 2.0 + acceleration: 2.66 + command: 30.0 + } + calibration { + speed: 2.0 + acceleration: 2.93 + command: 35.0 + } + calibration { + speed: 2.0 + acceleration: 3.16 + command: 40.0 + } + calibration { + speed: 2.0 + acceleration: 3.18 + command: 45.0 + } + calibration { + speed: 2.0 + acceleration: 3.22 + command: 60.0 + } + calibration { + speed: 2.0 + acceleration: 3.23 + command: 50.0 + } + calibration { + speed: 2.0 + acceleration: 3.25 + command: 55.0 + } + calibration { + speed: 2.0 + acceleration: 3.32 + command: 80.0 + } + calibration { + speed: 2.0 + acceleration: 3.35 + command: 75.0 + } + calibration { + speed: 2.2 + acceleration: -7.7 + command: -35.0 + } + calibration { + speed: 2.2 + acceleration: -5.11 + command: -33.0 + } + calibration { + speed: 2.2 + acceleration: -4.61 + command: -32.0 + } + calibration { + speed: 2.2 + acceleration: -4.03 + command: -31.0 + } + calibration { + speed: 2.2 + acceleration: -3.37 + command: -30.0 + } + calibration { + speed: 2.2 + acceleration: -2.79 + command: -29.0 + } + calibration { + speed: 2.2 + acceleration: -2.29 + command: -28.0 + } + calibration { + speed: 2.2 + acceleration: -1.68 + command: -27.0 + } + calibration { + speed: 2.2 + acceleration: -1.11 + command: -26.0 + } + calibration { + speed: 2.2 + acceleration: -0.81 + command: -25.0 + } + calibration { + speed: 2.2 + acceleration: -0.52 + command: -24.0 + } + calibration { + speed: 2.2 + acceleration: -0.31 + command: -23.0 + } + calibration { + speed: 2.2 + acceleration: -0.23 + command: -22.0 + } + calibration { + speed: 2.2 + acceleration: -0.15 + command: -15.0 + } + calibration { + speed: 2.2 + acceleration: -0.13 + command: -16.6666666667 + } + calibration { + speed: 2.2 + acceleration: -0.12 + command: 15.0 + } + calibration { + speed: 2.2 + acceleration: 0.71 + command: 20.0 + } + calibration { + speed: 2.2 + acceleration: 1.05 + command: 22.0 + } + calibration { + speed: 2.2 + acceleration: 1.74 + command: 70.0 + } + calibration { + speed: 2.2 + acceleration: 1.94 + command: 25.0 + } + calibration { + speed: 2.2 + acceleration: 2.17 + command: 65.0 + } + calibration { + speed: 2.2 + acceleration: 2.44 + command: 27.0 + } + calibration { + speed: 2.2 + acceleration: 2.68 + command: 30.0 + } + calibration { + speed: 2.2 + acceleration: 2.98 + command: 35.0 + } + calibration { + speed: 2.2 + acceleration: 3.22 + command: 40.0 + } + calibration { + speed: 2.2 + acceleration: 3.23 + command: 45.0 + } + calibration { + speed: 2.2 + acceleration: 3.27 + command: 55.0 + } + calibration { + speed: 2.2 + acceleration: 3.29 + command: 55.0 + } + calibration { + speed: 2.2 + acceleration: 3.39 + command: 80.0 + } + calibration { + speed: 2.2 + acceleration: 3.42 + command: 75.0 + } + calibration { + speed: 2.4 + acceleration: -7.66 + command: -35.0 + } + calibration { + speed: 2.4 + acceleration: -5.18 + command: -33.0 + } + calibration { + speed: 2.4 + acceleration: -4.65 + command: -32.0 + } + calibration { + speed: 2.4 + acceleration: -4.02 + command: -31.0 + } + calibration { + speed: 2.4 + acceleration: -3.35 + command: -30.0 + } + calibration { + speed: 2.4 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 2.4 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 2.4 + acceleration: -1.69 + command: -27.0 + } + calibration { + speed: 2.4 + acceleration: -1.21 + command: -26.0 + } + calibration { + speed: 2.4 + acceleration: -0.78 + command: -25.0 + } + calibration { + speed: 2.4 + acceleration: -0.52 + command: -24.0 + } + calibration { + speed: 2.4 + acceleration: -0.31 + command: -23.0 + } + calibration { + speed: 2.4 + acceleration: -0.23 + command: -22.0 + } + calibration { + speed: 2.4 + acceleration: -0.16 + command: 1.0 + } + calibration { + speed: 2.4 + acceleration: -0.15 + command: -16.0 + } + calibration { + speed: 2.4 + acceleration: -0.14 + command: -20.0 + } + calibration { + speed: 2.4 + acceleration: 0.62 + command: 20.0 + } + calibration { + speed: 2.4 + acceleration: 0.95 + command: 22.0 + } + calibration { + speed: 2.4 + acceleration: 1.63 + command: 70.0 + } + calibration { + speed: 2.4 + acceleration: 1.84 + command: 25.0 + } + calibration { + speed: 2.4 + acceleration: 2.16 + command: 65.0 + } + calibration { + speed: 2.4 + acceleration: 2.38 + command: 27.0 + } + calibration { + speed: 2.4 + acceleration: 2.69 + command: 30.0 + } + calibration { + speed: 2.4 + acceleration: 3.02 + command: 35.0 + } + calibration { + speed: 2.4 + acceleration: 3.25 + command: 40.0 + } + calibration { + speed: 2.4 + acceleration: 3.27 + command: 45.0 + } + calibration { + speed: 2.4 + acceleration: 3.3 + command: 50.0 + } + calibration { + speed: 2.4 + acceleration: 3.31 + command: 57.5 + } + calibration { + speed: 2.4 + acceleration: 3.44 + command: 80.0 + } + calibration { + speed: 2.4 + acceleration: 3.47 + command: 75.0 + } + calibration { + speed: 2.6 + acceleration: -7.65 + command: -35.0 + } + calibration { + speed: 2.6 + acceleration: -5.23 + command: -33.0 + } + calibration { + speed: 2.6 + acceleration: -4.66 + command: -32.0 + } + calibration { + speed: 2.6 + acceleration: -4.0 + command: -31.0 + } + calibration { + speed: 2.6 + acceleration: -3.35 + command: -30.0 + } + calibration { + speed: 2.6 + acceleration: -2.81 + command: -29.0 + } + calibration { + speed: 2.6 + acceleration: -2.2 + command: -28.0 + } + calibration { + speed: 2.6 + acceleration: -1.66 + command: -27.0 + } + calibration { + speed: 2.6 + acceleration: -1.25 + command: -26.0 + } + calibration { + speed: 2.6 + acceleration: -0.8 + command: -25.0 + } + calibration { + speed: 2.6 + acceleration: -0.51 + command: -24.0 + } + calibration { + speed: 2.6 + acceleration: -0.31 + command: -23.0 + } + calibration { + speed: 2.6 + acceleration: -0.22 + command: -22.0 + } + calibration { + speed: 2.6 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 2.6 + acceleration: -0.15 + command: -18.5 + } + calibration { + speed: 2.6 + acceleration: -0.14 + command: -15.0 + } + calibration { + speed: 2.6 + acceleration: -0.13 + command: 15.0 + } + calibration { + speed: 2.6 + acceleration: 0.51 + command: 20.0 + } + calibration { + speed: 2.6 + acceleration: 0.84 + command: 22.0 + } + calibration { + speed: 2.6 + acceleration: 1.73 + command: 47.5 + } + calibration { + speed: 2.6 + acceleration: 2.27 + command: 65.0 + } + calibration { + speed: 2.6 + acceleration: 2.32 + command: 27.0 + } + calibration { + speed: 2.6 + acceleration: 2.69 + command: 30.0 + } + calibration { + speed: 2.6 + acceleration: 3.06 + command: 35.0 + } + calibration { + speed: 2.6 + acceleration: 3.27 + command: 40.0 + } + calibration { + speed: 2.6 + acceleration: 3.3 + command: 45.0 + } + calibration { + speed: 2.6 + acceleration: 3.31 + command: 55.0 + } + calibration { + speed: 2.6 + acceleration: 3.32 + command: 50.0 + } + calibration { + speed: 2.6 + acceleration: 3.33 + command: 60.0 + } + calibration { + speed: 2.6 + acceleration: 3.48 + command: 80.0 + } + calibration { + speed: 2.6 + acceleration: 3.52 + command: 75.0 + } + calibration { + speed: 2.8 + acceleration: -7.68 + command: -35.0 + } + calibration { + speed: 2.8 + acceleration: -5.25 + command: -33.0 + } + calibration { + speed: 2.8 + acceleration: -4.63 + command: -32.0 + } + calibration { + speed: 2.8 + acceleration: -4.0 + command: -31.0 + } + calibration { + speed: 2.8 + acceleration: -3.36 + command: -30.0 + } + calibration { + speed: 2.8 + acceleration: -2.85 + command: -29.0 + } + calibration { + speed: 2.8 + acceleration: -2.14 + command: -28.0 + } + calibration { + speed: 2.8 + acceleration: -1.66 + command: -27.0 + } + calibration { + speed: 2.8 + acceleration: -1.23 + command: -26.0 + } + calibration { + speed: 2.8 + acceleration: -0.8 + command: -25.0 + } + calibration { + speed: 2.8 + acceleration: -0.53 + command: -24.0 + } + calibration { + speed: 2.8 + acceleration: -0.31 + command: -23.0 + } + calibration { + speed: 2.8 + acceleration: -0.23 + command: -22.0 + } + calibration { + speed: 2.8 + acceleration: -0.15 + command: -1.0 + } + calibration { + speed: 2.8 + acceleration: -0.14 + command: -17.5 + } + calibration { + speed: 2.8 + acceleration: -0.12 + command: -13.0 + } + calibration { + speed: 2.8 + acceleration: 0.46 + command: 20.0 + } + calibration { + speed: 2.8 + acceleration: 0.76 + command: 22.0 + } + calibration { + speed: 2.8 + acceleration: 1.65 + command: 25.0 + } + calibration { + speed: 2.8 + acceleration: 1.95 + command: 70.0 + } + calibration { + speed: 2.8 + acceleration: 2.26 + command: 27.0 + } + calibration { + speed: 2.8 + acceleration: 2.41 + command: 65.0 + } + calibration { + speed: 2.8 + acceleration: 2.7 + command: 30.0 + } + calibration { + speed: 2.8 + acceleration: 3.09 + command: 35.0 + } + calibration { + speed: 2.8 + acceleration: 3.29 + command: 40.0 + } + calibration { + speed: 2.8 + acceleration: 3.31 + command: 50.0 + } + calibration { + speed: 2.8 + acceleration: 3.33 + command: 50.0 + } + calibration { + speed: 2.8 + acceleration: 3.34 + command: 60.0 + } + calibration { + speed: 2.8 + acceleration: 3.51 + command: 80.0 + } + calibration { + speed: 2.8 + acceleration: 3.56 + command: 75.0 + } + calibration { + speed: 3.0 + acceleration: -7.71 + command: -35.0 + } + calibration { + speed: 3.0 + acceleration: -5.23 + command: -33.0 + } + calibration { + speed: 3.0 + acceleration: -4.6 + command: -32.0 + } + calibration { + speed: 3.0 + acceleration: -4.02 + command: -31.0 + } + calibration { + speed: 3.0 + acceleration: -3.39 + command: -30.0 + } + calibration { + speed: 3.0 + acceleration: -2.88 + command: -29.0 + } + calibration { + speed: 3.0 + acceleration: -2.14 + command: -28.0 + } + calibration { + speed: 3.0 + acceleration: -1.73 + command: -27.0 + } + calibration { + speed: 3.0 + acceleration: -1.23 + command: -26.0 + } + calibration { + speed: 3.0 + acceleration: -0.81 + command: -25.0 + } + calibration { + speed: 3.0 + acceleration: -0.53 + command: -24.0 + } + calibration { + speed: 3.0 + acceleration: -0.32 + command: -23.0 + } + calibration { + speed: 3.0 + acceleration: -0.23 + command: -22.0 + } + calibration { + speed: 3.0 + acceleration: -0.16 + command: 1.0 + } + calibration { + speed: 3.0 + acceleration: -0.15 + command: -15.0 + } + calibration { + speed: 3.0 + acceleration: -0.14 + command: -18.5 + } + calibration { + speed: 3.0 + acceleration: 0.42 + command: 20.0 + } + calibration { + speed: 3.0 + acceleration: 0.7 + command: 22.0 + } + calibration { + speed: 3.0 + acceleration: 1.57 + command: 25.0 + } + calibration { + speed: 3.0 + acceleration: 2.13 + command: 70.0 + } + calibration { + speed: 3.0 + acceleration: 2.2 + command: 27.0 + } + calibration { + speed: 3.0 + acceleration: 2.54 + command: 65.0 + } + calibration { + speed: 3.0 + acceleration: 2.71 + command: 30.0 + } + calibration { + speed: 3.0 + acceleration: 3.12 + command: 35.0 + } + calibration { + speed: 3.0 + acceleration: 3.3 + command: 55.0 + } + calibration { + speed: 3.0 + acceleration: 3.31 + command: 42.5 + } + calibration { + speed: 3.0 + acceleration: 3.33 + command: 60.0 + } + calibration { + speed: 3.0 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 3.0 + acceleration: 3.55 + command: 80.0 + } + calibration { + speed: 3.0 + acceleration: 3.6 + command: 75.0 + } + calibration { + speed: 3.2 + acceleration: -7.75 + command: -35.0 + } + calibration { + speed: 3.2 + acceleration: -5.2 + command: -33.0 + } + calibration { + speed: 3.2 + acceleration: -4.57 + command: -32.0 + } + calibration { + speed: 3.2 + acceleration: -4.04 + command: -31.0 + } + calibration { + speed: 3.2 + acceleration: -3.41 + command: -30.0 + } + calibration { + speed: 3.2 + acceleration: -2.86 + command: -29.0 + } + calibration { + speed: 3.2 + acceleration: -2.18 + command: -28.0 + } + calibration { + speed: 3.2 + acceleration: -1.78 + command: -27.0 + } + calibration { + speed: 3.2 + acceleration: -1.23 + command: -26.0 + } + calibration { + speed: 3.2 + acceleration: -0.8 + command: -25.0 + } + calibration { + speed: 3.2 + acceleration: -0.52 + command: -24.0 + } + calibration { + speed: 3.2 + acceleration: -0.29 + command: -23.0 + } + calibration { + speed: 3.2 + acceleration: -0.21 + command: -22.0 + } + calibration { + speed: 3.2 + acceleration: -0.17 + command: -13.0 + } + calibration { + speed: 3.2 + acceleration: -0.16 + command: -15.0 + } + calibration { + speed: 3.2 + acceleration: -0.15 + command: -1.0 + } + calibration { + speed: 3.2 + acceleration: -0.13 + command: -20.0 + } + calibration { + speed: 3.2 + acceleration: 0.37 + command: 20.0 + } + calibration { + speed: 3.2 + acceleration: 0.63 + command: 22.0 + } + calibration { + speed: 3.2 + acceleration: 1.5 + command: 25.0 + } + calibration { + speed: 3.2 + acceleration: 2.13 + command: 27.0 + } + calibration { + speed: 3.2 + acceleration: 2.2 + command: 70.0 + } + calibration { + speed: 3.2 + acceleration: 2.6 + command: 65.0 + } + calibration { + speed: 3.2 + acceleration: 2.7 + command: 30.0 + } + calibration { + speed: 3.2 + acceleration: 3.13 + command: 35.0 + } + calibration { + speed: 3.2 + acceleration: 3.3 + command: 57.5 + } + calibration { + speed: 3.2 + acceleration: 3.31 + command: 45.0 + } + calibration { + speed: 3.2 + acceleration: 3.33 + command: 40.0 + } + calibration { + speed: 3.2 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 3.2 + acceleration: 3.59 + command: 80.0 + } + calibration { + speed: 3.2 + acceleration: 3.62 + command: 75.0 + } + calibration { + speed: 3.4 + acceleration: -7.78 + command: -35.0 + } + calibration { + speed: 3.4 + acceleration: -5.15 + command: -33.0 + } + calibration { + speed: 3.4 + acceleration: -4.55 + command: -32.0 + } + calibration { + speed: 3.4 + acceleration: -4.06 + command: -31.0 + } + calibration { + speed: 3.4 + acceleration: -3.42 + command: -30.0 + } + calibration { + speed: 3.4 + acceleration: -2.81 + command: -29.0 + } + calibration { + speed: 3.4 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 3.4 + acceleration: -1.79 + command: -27.0 + } + calibration { + speed: 3.4 + acceleration: -1.24 + command: -26.0 + } + calibration { + speed: 3.4 + acceleration: -0.81 + command: -25.0 + } + calibration { + speed: 3.4 + acceleration: -0.52 + command: -24.0 + } + calibration { + speed: 3.4 + acceleration: -0.32 + command: -23.0 + } + calibration { + speed: 3.4 + acceleration: -0.22 + command: -22.0 + } + calibration { + speed: 3.4 + acceleration: -0.16 + command: -2.5 + } + calibration { + speed: 3.4 + acceleration: -0.15 + command: -15.0 + } + calibration { + speed: 3.4 + acceleration: 0.34 + command: 20.0 + } + calibration { + speed: 3.4 + acceleration: 0.57 + command: 22.0 + } + calibration { + speed: 3.4 + acceleration: 1.42 + command: 25.0 + } + calibration { + speed: 3.4 + acceleration: 2.03 + command: 27.0 + } + calibration { + speed: 3.4 + acceleration: 2.22 + command: 70.0 + } + calibration { + speed: 3.4 + acceleration: 2.64 + command: 65.0 + } + calibration { + speed: 3.4 + acceleration: 2.67 + command: 30.0 + } + calibration { + speed: 3.4 + acceleration: 3.14 + command: 35.0 + } + calibration { + speed: 3.4 + acceleration: 3.27 + command: 60.0 + } + calibration { + speed: 3.4 + acceleration: 3.29 + command: 50.0 + } + calibration { + speed: 3.4 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 3.4 + acceleration: 3.36 + command: 40.0 + } + calibration { + speed: 3.4 + acceleration: 3.61 + command: 80.0 + } + calibration { + speed: 3.4 + acceleration: 3.63 + command: 75.0 + } + calibration { + speed: 3.6 + acceleration: -7.78 + command: -35.0 + } + calibration { + speed: 3.6 + acceleration: -5.11 + command: -33.0 + } + calibration { + speed: 3.6 + acceleration: -4.54 + command: -32.0 + } + calibration { + speed: 3.6 + acceleration: -4.08 + command: -31.0 + } + calibration { + speed: 3.6 + acceleration: -3.41 + command: -30.0 + } + calibration { + speed: 3.6 + acceleration: -2.74 + command: -29.0 + } + calibration { + speed: 3.6 + acceleration: -2.23 + command: -28.0 + } + calibration { + speed: 3.6 + acceleration: -1.78 + command: -27.0 + } + calibration { + speed: 3.6 + acceleration: -1.25 + command: -26.0 + } + calibration { + speed: 3.6 + acceleration: -0.82 + command: -25.0 + } + calibration { + speed: 3.6 + acceleration: -0.53 + command: -24.0 + } + calibration { + speed: 3.6 + acceleration: -0.3 + command: -23.0 + } + calibration { + speed: 3.6 + acceleration: -0.23 + command: -22.0 + } + calibration { + speed: 3.6 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 3.6 + acceleration: -0.16 + command: -1.0 + } + calibration { + speed: 3.6 + acceleration: -0.15 + command: -16.5 + } + calibration { + speed: 3.6 + acceleration: 0.31 + command: 20.0 + } + calibration { + speed: 3.6 + acceleration: 0.52 + command: 22.0 + } + calibration { + speed: 3.6 + acceleration: 1.32 + command: 25.0 + } + calibration { + speed: 3.6 + acceleration: 1.92 + command: 27.0 + } + calibration { + speed: 3.6 + acceleration: 2.27 + command: 70.0 + } + calibration { + speed: 3.6 + acceleration: 2.58 + command: 30.0 + } + calibration { + speed: 3.6 + acceleration: 2.68 + command: 65.0 + } + calibration { + speed: 3.6 + acceleration: 3.12 + command: 35.0 + } + calibration { + speed: 3.6 + acceleration: 3.22 + command: 60.0 + } + calibration { + speed: 3.6 + acceleration: 3.28 + command: 45.0 + } + calibration { + speed: 3.6 + acceleration: 3.29 + command: 55.0 + } + calibration { + speed: 3.6 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 3.6 + acceleration: 3.37 + command: 40.0 + } + calibration { + speed: 3.6 + acceleration: 3.62 + command: 80.0 + } + calibration { + speed: 3.6 + acceleration: 3.63 + command: 75.0 + } + calibration { + speed: 3.8 + acceleration: -7.77 + command: -35.0 + } + calibration { + speed: 3.8 + acceleration: -5.09 + command: -33.0 + } + calibration { + speed: 3.8 + acceleration: -4.56 + command: -32.0 + } + calibration { + speed: 3.8 + acceleration: -4.06 + command: -31.0 + } + calibration { + speed: 3.8 + acceleration: -3.39 + command: -30.0 + } + calibration { + speed: 3.8 + acceleration: -2.71 + command: -29.0 + } + calibration { + speed: 3.8 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 3.8 + acceleration: -1.78 + command: -27.0 + } + calibration { + speed: 3.8 + acceleration: -1.27 + command: -26.0 + } + calibration { + speed: 3.8 + acceleration: -0.82 + command: -25.0 + } + calibration { + speed: 3.8 + acceleration: -0.54 + command: -24.0 + } + calibration { + speed: 3.8 + acceleration: -0.31 + command: -23.0 + } + calibration { + speed: 3.8 + acceleration: -0.26 + command: -22.0 + } + calibration { + speed: 3.8 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 3.8 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 3.8 + acceleration: -0.15 + command: -17.5 + } + calibration { + speed: 3.8 + acceleration: 0.28 + command: 20.0 + } + calibration { + speed: 3.8 + acceleration: 0.5 + command: 22.0 + } + calibration { + speed: 3.8 + acceleration: 1.23 + command: 25.0 + } + calibration { + speed: 3.8 + acceleration: 1.83 + command: 27.0 + } + calibration { + speed: 3.8 + acceleration: 2.36 + command: 70.0 + } + calibration { + speed: 3.8 + acceleration: 2.47 + command: 30.0 + } + calibration { + speed: 3.8 + acceleration: 2.71 + command: 65.0 + } + calibration { + speed: 3.8 + acceleration: 3.09 + command: 35.0 + } + calibration { + speed: 3.8 + acceleration: 3.19 + command: 60.0 + } + calibration { + speed: 3.8 + acceleration: 3.28 + command: 45.0 + } + calibration { + speed: 3.8 + acceleration: 3.29 + command: 55.0 + } + calibration { + speed: 3.8 + acceleration: 3.34 + command: 50.0 + } + calibration { + speed: 3.8 + acceleration: 3.37 + command: 40.0 + } + calibration { + speed: 3.8 + acceleration: 3.62 + command: 77.5 + } + calibration { + speed: 4.0 + acceleration: -7.75 + command: -35.0 + } + calibration { + speed: 4.0 + acceleration: -5.08 + command: -33.0 + } + calibration { + speed: 4.0 + acceleration: -4.59 + command: -32.0 + } + calibration { + speed: 4.0 + acceleration: -4.01 + command: -31.0 + } + calibration { + speed: 4.0 + acceleration: -3.35 + command: -30.0 + } + calibration { + speed: 4.0 + acceleration: -2.72 + command: -29.0 + } + calibration { + speed: 4.0 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 4.0 + acceleration: -1.79 + command: -27.0 + } + calibration { + speed: 4.0 + acceleration: -1.25 + command: -26.0 + } + calibration { + speed: 4.0 + acceleration: -0.85 + command: -25.0 + } + calibration { + speed: 4.0 + acceleration: -0.54 + command: -24.0 + } + calibration { + speed: 4.0 + acceleration: -0.31 + command: -23.0 + } + calibration { + speed: 4.0 + acceleration: -0.24 + command: -22.0 + } + calibration { + speed: 4.0 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 4.0 + acceleration: -0.17 + command: -1.0 + } + calibration { + speed: 4.0 + acceleration: -0.15 + command: -20.0 + } + calibration { + speed: 4.0 + acceleration: -0.13 + command: -13.0 + } + calibration { + speed: 4.0 + acceleration: 0.22 + command: 20.0 + } + calibration { + speed: 4.0 + acceleration: 0.46 + command: 22.0 + } + calibration { + speed: 4.0 + acceleration: 1.16 + command: 25.0 + } + calibration { + speed: 4.0 + acceleration: 1.73 + command: 27.0 + } + calibration { + speed: 4.0 + acceleration: 2.35 + command: 30.0 + } + calibration { + speed: 4.0 + acceleration: 2.43 + command: 70.0 + } + calibration { + speed: 4.0 + acceleration: 2.72 + command: 65.0 + } + calibration { + speed: 4.0 + acceleration: 3.04 + command: 35.0 + } + calibration { + speed: 4.0 + acceleration: 3.19 + command: 60.0 + } + calibration { + speed: 4.0 + acceleration: 3.29 + command: 55.0 + } + calibration { + speed: 4.0 + acceleration: 3.3 + command: 45.0 + } + calibration { + speed: 4.0 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 4.0 + acceleration: 3.36 + command: 40.0 + } + calibration { + speed: 4.0 + acceleration: 3.61 + command: 80.0 + } + calibration { + speed: 4.0 + acceleration: 3.62 + command: 75.0 + } + calibration { + speed: 4.2 + acceleration: -7.7 + command: -35.0 + } + calibration { + speed: 4.2 + acceleration: -5.09 + command: -33.0 + } + calibration { + speed: 4.2 + acceleration: -4.63 + command: -32.0 + } + calibration { + speed: 4.2 + acceleration: -3.98 + command: -31.0 + } + calibration { + speed: 4.2 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 4.2 + acceleration: -2.75 + command: -29.0 + } + calibration { + speed: 4.2 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 4.2 + acceleration: -1.79 + command: -27.0 + } + calibration { + speed: 4.2 + acceleration: -1.26 + command: -26.0 + } + calibration { + speed: 4.2 + acceleration: -0.81 + command: -25.0 + } + calibration { + speed: 4.2 + acceleration: -0.55 + command: -24.0 + } + calibration { + speed: 4.2 + acceleration: -0.33 + command: -23.0 + } + calibration { + speed: 4.2 + acceleration: -0.21 + command: -22.0 + } + calibration { + speed: 4.2 + acceleration: -0.19 + command: 15.0 + } + calibration { + speed: 4.2 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 4.2 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 4.2 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 4.2 + acceleration: -0.15 + command: -20.0 + } + calibration { + speed: 4.2 + acceleration: 0.21 + command: 20.0 + } + calibration { + speed: 4.2 + acceleration: 0.42 + command: 22.0 + } + calibration { + speed: 4.2 + acceleration: 1.06 + command: 25.0 + } + calibration { + speed: 4.2 + acceleration: 1.62 + command: 27.0 + } + calibration { + speed: 4.2 + acceleration: 2.23 + command: 30.0 + } + calibration { + speed: 4.2 + acceleration: 2.43 + command: 70.0 + } + calibration { + speed: 4.2 + acceleration: 2.69 + command: 65.0 + } + calibration { + speed: 4.2 + acceleration: 2.97 + command: 35.0 + } + calibration { + speed: 4.2 + acceleration: 3.22 + command: 60.0 + } + calibration { + speed: 4.2 + acceleration: 3.32 + command: 47.5 + } + calibration { + speed: 4.2 + acceleration: 3.34 + command: 45.0 + } + calibration { + speed: 4.2 + acceleration: 3.36 + command: 50.0 + } + calibration { + speed: 4.2 + acceleration: 3.62 + command: 77.5 + } + calibration { + speed: 4.4 + acceleration: -7.65 + command: -35.0 + } + calibration { + speed: 4.4 + acceleration: -5.12 + command: -33.0 + } + calibration { + speed: 4.4 + acceleration: -4.65 + command: -32.0 + } + calibration { + speed: 4.4 + acceleration: -3.94 + command: -31.0 + } + calibration { + speed: 4.4 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 4.4 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 4.4 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 4.4 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 4.4 + acceleration: -1.29 + command: -26.0 + } + calibration { + speed: 4.4 + acceleration: -0.84 + command: -25.0 + } + calibration { + speed: 4.4 + acceleration: -0.53 + command: -24.0 + } + calibration { + speed: 4.4 + acceleration: -0.32 + command: -23.0 + } + calibration { + speed: 4.4 + acceleration: -0.23 + command: -22.0 + } + calibration { + speed: 4.4 + acceleration: -0.19 + command: -15.0 + } + calibration { + speed: 4.4 + acceleration: -0.17 + command: -1.0 + } + calibration { + speed: 4.4 + acceleration: -0.16 + command: -20.0 + } + calibration { + speed: 4.4 + acceleration: -0.14 + command: -13.0 + } + calibration { + speed: 4.4 + acceleration: 0.19 + command: 20.0 + } + calibration { + speed: 4.4 + acceleration: 0.38 + command: 22.0 + } + calibration { + speed: 4.4 + acceleration: 0.98 + command: 25.0 + } + calibration { + speed: 4.4 + acceleration: 1.5 + command: 27.0 + } + calibration { + speed: 4.4 + acceleration: 2.11 + command: 30.0 + } + calibration { + speed: 4.4 + acceleration: 2.36 + command: 70.0 + } + calibration { + speed: 4.4 + acceleration: 2.64 + command: 65.0 + } + calibration { + speed: 4.4 + acceleration: 2.88 + command: 35.0 + } + calibration { + speed: 4.4 + acceleration: 3.29 + command: 50.0 + } + calibration { + speed: 4.4 + acceleration: 3.35 + command: 55.0 + } + calibration { + speed: 4.4 + acceleration: 3.38 + command: 45.0 + } + calibration { + speed: 4.4 + acceleration: 3.39 + command: 50.0 + } + calibration { + speed: 4.4 + acceleration: 3.64 + command: 75.0 + } + calibration { + speed: 4.4 + acceleration: 3.65 + command: 80.0 + } + calibration { + speed: 4.6 + acceleration: -7.62 + command: -35.0 + } + calibration { + speed: 4.6 + acceleration: -5.16 + command: -33.0 + } + calibration { + speed: 4.6 + acceleration: -4.65 + command: -32.0 + } + calibration { + speed: 4.6 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 4.6 + acceleration: -3.35 + command: -30.0 + } + calibration { + speed: 4.6 + acceleration: -2.79 + command: -29.0 + } + calibration { + speed: 4.6 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 4.6 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 4.6 + acceleration: -1.29 + command: -26.0 + } + calibration { + speed: 4.6 + acceleration: -0.85 + command: -25.0 + } + calibration { + speed: 4.6 + acceleration: -0.55 + command: -24.0 + } + calibration { + speed: 4.6 + acceleration: -0.33 + command: -23.0 + } + calibration { + speed: 4.6 + acceleration: -0.26 + command: -22.0 + } + calibration { + speed: 4.6 + acceleration: -0.17 + command: -8.25 + } + calibration { + speed: 4.6 + acceleration: -0.16 + command: -17.0 + } + calibration { + speed: 4.6 + acceleration: -0.01 + command: 17.0 + } + calibration { + speed: 4.6 + acceleration: 0.15 + command: 20.0 + } + calibration { + speed: 4.6 + acceleration: 0.34 + command: 22.0 + } + calibration { + speed: 4.6 + acceleration: 0.88 + command: 25.0 + } + calibration { + speed: 4.6 + acceleration: 1.4 + command: 27.0 + } + calibration { + speed: 4.6 + acceleration: 1.98 + command: 30.0 + } + calibration { + speed: 4.6 + acceleration: 2.3 + command: 70.0 + } + calibration { + speed: 4.6 + acceleration: 2.62 + command: 65.0 + } + calibration { + speed: 4.6 + acceleration: 2.82 + command: 35.0 + } + calibration { + speed: 4.6 + acceleration: 3.24 + command: 40.0 + } + calibration { + speed: 4.6 + acceleration: 3.38 + command: 60.0 + } + calibration { + speed: 4.6 + acceleration: 3.4 + command: 50.0 + } + calibration { + speed: 4.6 + acceleration: 3.42 + command: 50.0 + } + calibration { + speed: 4.6 + acceleration: 3.66 + command: 75.0 + } + calibration { + speed: 4.6 + acceleration: 3.67 + command: 80.0 + } + calibration { + speed: 4.8 + acceleration: -7.6 + command: -35.0 + } + calibration { + speed: 4.8 + acceleration: -5.19 + command: -33.0 + } + calibration { + speed: 4.8 + acceleration: -4.64 + command: -32.0 + } + calibration { + speed: 4.8 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 4.8 + acceleration: -3.37 + command: -30.0 + } + calibration { + speed: 4.8 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 4.8 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 4.8 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 4.8 + acceleration: -1.27 + command: -26.0 + } + calibration { + speed: 4.8 + acceleration: -0.83 + command: -25.0 + } + calibration { + speed: 4.8 + acceleration: -0.55 + command: -24.0 + } + calibration { + speed: 4.8 + acceleration: -0.33 + command: -23.0 + } + calibration { + speed: 4.8 + acceleration: -0.26 + command: -22.0 + } + calibration { + speed: 4.8 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 4.8 + acceleration: -0.18 + command: -6.66666666667 + } + calibration { + speed: 4.8 + acceleration: -0.16 + command: -17.0 + } + calibration { + speed: 4.8 + acceleration: -0.06 + command: 17.0 + } + calibration { + speed: 4.8 + acceleration: 0.16 + command: 20.0 + } + calibration { + speed: 4.8 + acceleration: 0.33 + command: 22.0 + } + calibration { + speed: 4.8 + acceleration: 0.79 + command: 25.0 + } + calibration { + speed: 4.8 + acceleration: 1.29 + command: 27.0 + } + calibration { + speed: 4.8 + acceleration: 1.84 + command: 30.0 + } + calibration { + speed: 4.8 + acceleration: 2.31 + command: 70.0 + } + calibration { + speed: 4.8 + acceleration: 2.64 + command: 65.0 + } + calibration { + speed: 4.8 + acceleration: 2.73 + command: 35.0 + } + calibration { + speed: 4.8 + acceleration: 3.2 + command: 40.0 + } + calibration { + speed: 4.8 + acceleration: 3.39 + command: 45.0 + } + calibration { + speed: 4.8 + acceleration: 3.44 + command: 50.0 + } + calibration { + speed: 4.8 + acceleration: 3.45 + command: 57.5 + } + calibration { + speed: 4.8 + acceleration: 3.68 + command: 75.0 + } + calibration { + speed: 4.8 + acceleration: 3.71 + command: 80.0 + } + calibration { + speed: 5.0 + acceleration: -7.59 + command: -35.0 + } + calibration { + speed: 5.0 + acceleration: -5.2 + command: -33.0 + } + calibration { + speed: 5.0 + acceleration: -4.61 + command: -32.0 + } + calibration { + speed: 5.0 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 5.0 + acceleration: -3.37 + command: -30.0 + } + calibration { + speed: 5.0 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 5.0 + acceleration: -2.23 + command: -28.0 + } + calibration { + speed: 5.0 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 5.0 + acceleration: -1.29 + command: -26.0 + } + calibration { + speed: 5.0 + acceleration: -0.84 + command: -25.0 + } + calibration { + speed: 5.0 + acceleration: -0.55 + command: -24.0 + } + calibration { + speed: 5.0 + acceleration: -0.32 + command: -23.0 + } + calibration { + speed: 5.0 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 5.0 + acceleration: -0.2 + command: 15.0 + } + calibration { + speed: 5.0 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 5.0 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 5.0 + acceleration: -0.16 + command: -20.0 + } + calibration { + speed: 5.0 + acceleration: -0.07 + command: 17.0 + } + calibration { + speed: 5.0 + acceleration: 0.17 + command: 20.0 + } + calibration { + speed: 5.0 + acceleration: 0.32 + command: 22.0 + } + calibration { + speed: 5.0 + acceleration: 0.73 + command: 25.0 + } + calibration { + speed: 5.0 + acceleration: 1.17 + command: 27.0 + } + calibration { + speed: 5.0 + acceleration: 1.7 + command: 30.0 + } + calibration { + speed: 5.0 + acceleration: 2.37 + command: 70.0 + } + calibration { + speed: 5.0 + acceleration: 2.64 + command: 35.0 + } + calibration { + speed: 5.0 + acceleration: 2.69 + command: 65.0 + } + calibration { + speed: 5.0 + acceleration: 3.15 + command: 40.0 + } + calibration { + speed: 5.0 + acceleration: 3.36 + command: 45.0 + } + calibration { + speed: 5.0 + acceleration: 3.46 + command: 50.0 + } + calibration { + speed: 5.0 + acceleration: 3.48 + command: 55.0 + } + calibration { + speed: 5.0 + acceleration: 3.51 + command: 60.0 + } + calibration { + speed: 5.0 + acceleration: 3.71 + command: 75.0 + } + calibration { + speed: 5.0 + acceleration: 3.74 + command: 80.0 + } + calibration { + speed: 5.2 + acceleration: -7.59 + command: -35.0 + } + calibration { + speed: 5.2 + acceleration: -5.2 + command: -33.0 + } + calibration { + speed: 5.2 + acceleration: -4.57 + command: -32.0 + } + calibration { + speed: 5.2 + acceleration: -3.94 + command: -31.0 + } + calibration { + speed: 5.2 + acceleration: -3.37 + command: -30.0 + } + calibration { + speed: 5.2 + acceleration: -2.77 + command: -29.0 + } + calibration { + speed: 5.2 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 5.2 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 5.2 + acceleration: -1.29 + command: -26.0 + } + calibration { + speed: 5.2 + acceleration: -0.84 + command: -25.0 + } + calibration { + speed: 5.2 + acceleration: -0.57 + command: -24.0 + } + calibration { + speed: 5.2 + acceleration: -0.33 + command: -23.0 + } + calibration { + speed: 5.2 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 5.2 + acceleration: -0.21 + command: 0.0 + } + calibration { + speed: 5.2 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 5.2 + acceleration: -0.17 + command: -18.5 + } + calibration { + speed: 5.2 + acceleration: -0.06 + command: 17.0 + } + calibration { + speed: 5.2 + acceleration: 0.17 + command: 20.0 + } + calibration { + speed: 5.2 + acceleration: 0.31 + command: 22.0 + } + calibration { + speed: 5.2 + acceleration: 0.69 + command: 25.0 + } + calibration { + speed: 5.2 + acceleration: 1.12 + command: 27.0 + } + calibration { + speed: 5.2 + acceleration: 1.57 + command: 30.0 + } + calibration { + speed: 5.2 + acceleration: 2.43 + command: 70.0 + } + calibration { + speed: 5.2 + acceleration: 2.54 + command: 35.0 + } + calibration { + speed: 5.2 + acceleration: 2.76 + command: 65.0 + } + calibration { + speed: 5.2 + acceleration: 3.11 + command: 40.0 + } + calibration { + speed: 5.2 + acceleration: 3.31 + command: 45.0 + } + calibration { + speed: 5.2 + acceleration: 3.45 + command: 50.0 + } + calibration { + speed: 5.2 + acceleration: 3.52 + command: 55.0 + } + calibration { + speed: 5.2 + acceleration: 3.55 + command: 60.0 + } + calibration { + speed: 5.2 + acceleration: 3.73 + command: 75.0 + } + calibration { + speed: 5.2 + acceleration: 3.77 + command: 80.0 + } + calibration { + speed: 5.4 + acceleration: -7.61 + command: -35.0 + } + calibration { + speed: 5.4 + acceleration: -5.18 + command: -33.0 + } + calibration { + speed: 5.4 + acceleration: -4.55 + command: -32.0 + } + calibration { + speed: 5.4 + acceleration: -3.94 + command: -31.0 + } + calibration { + speed: 5.4 + acceleration: -3.36 + command: -30.0 + } + calibration { + speed: 5.4 + acceleration: -2.77 + command: -29.0 + } + calibration { + speed: 5.4 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 5.4 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 5.4 + acceleration: -1.27 + command: -26.0 + } + calibration { + speed: 5.4 + acceleration: -0.84 + command: -25.0 + } + calibration { + speed: 5.4 + acceleration: -0.56 + command: -24.0 + } + calibration { + speed: 5.4 + acceleration: -0.33 + command: -23.0 + } + calibration { + speed: 5.4 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 5.4 + acceleration: -0.23 + command: 15.0 + } + calibration { + speed: 5.4 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 5.4 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 5.4 + acceleration: -0.16 + command: -20.0 + } + calibration { + speed: 5.4 + acceleration: -0.14 + command: -13.0 + } + calibration { + speed: 5.4 + acceleration: -0.06 + command: 17.0 + } + calibration { + speed: 5.4 + acceleration: 0.15 + command: 20.0 + } + calibration { + speed: 5.4 + acceleration: 0.29 + command: 22.0 + } + calibration { + speed: 5.4 + acceleration: 0.66 + command: 25.0 + } + calibration { + speed: 5.4 + acceleration: 1.04 + command: 27.0 + } + calibration { + speed: 5.4 + acceleration: 1.5 + command: 30.0 + } + calibration { + speed: 5.4 + acceleration: 2.45 + command: 35.0 + } + calibration { + speed: 5.4 + acceleration: 2.48 + command: 70.0 + } + calibration { + speed: 5.4 + acceleration: 2.82 + command: 65.0 + } + calibration { + speed: 5.4 + acceleration: 3.05 + command: 40.0 + } + calibration { + speed: 5.4 + acceleration: 3.26 + command: 45.0 + } + calibration { + speed: 5.4 + acceleration: 3.42 + command: 50.0 + } + calibration { + speed: 5.4 + acceleration: 3.52 + command: 55.0 + } + calibration { + speed: 5.4 + acceleration: 3.57 + command: 60.0 + } + calibration { + speed: 5.4 + acceleration: 3.75 + command: 75.0 + } + calibration { + speed: 5.4 + acceleration: 3.78 + command: 80.0 + } + calibration { + speed: 5.6 + acceleration: -7.64 + command: -35.0 + } + calibration { + speed: 5.6 + acceleration: -5.16 + command: -33.0 + } + calibration { + speed: 5.6 + acceleration: -4.53 + command: -32.0 + } + calibration { + speed: 5.6 + acceleration: -3.93 + command: -31.0 + } + calibration { + speed: 5.6 + acceleration: -3.35 + command: -30.0 + } + calibration { + speed: 5.6 + acceleration: -2.79 + command: -29.0 + } + calibration { + speed: 5.6 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 5.6 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 5.6 + acceleration: -1.29 + command: -26.0 + } + calibration { + speed: 5.6 + acceleration: -0.85 + command: -25.0 + } + calibration { + speed: 5.6 + acceleration: -0.58 + command: -24.0 + } + calibration { + speed: 5.6 + acceleration: -0.34 + command: -23.0 + } + calibration { + speed: 5.6 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 5.6 + acceleration: -0.21 + command: 15.0 + } + calibration { + speed: 5.6 + acceleration: -0.2 + command: -16.0 + } + calibration { + speed: 5.6 + acceleration: -0.18 + command: -17.0 + } + calibration { + speed: 5.6 + acceleration: -0.08 + command: 17.0 + } + calibration { + speed: 5.6 + acceleration: 0.18 + command: 20.0 + } + calibration { + speed: 5.6 + acceleration: 0.27 + command: 22.0 + } + calibration { + speed: 5.6 + acceleration: 0.61 + command: 25.0 + } + calibration { + speed: 5.6 + acceleration: 0.98 + command: 27.0 + } + calibration { + speed: 5.6 + acceleration: 1.44 + command: 30.0 + } + calibration { + speed: 5.6 + acceleration: 2.37 + command: 35.0 + } + calibration { + speed: 5.6 + acceleration: 2.51 + command: 70.0 + } + calibration { + speed: 5.6 + acceleration: 2.84 + command: 65.0 + } + calibration { + speed: 5.6 + acceleration: 3.0 + command: 40.0 + } + calibration { + speed: 5.6 + acceleration: 3.21 + command: 45.0 + } + calibration { + speed: 5.6 + acceleration: 3.38 + command: 50.0 + } + calibration { + speed: 5.6 + acceleration: 3.51 + command: 55.0 + } + calibration { + speed: 5.6 + acceleration: 3.57 + command: 60.0 + } + calibration { + speed: 5.6 + acceleration: 3.77 + command: 75.0 + } + calibration { + speed: 5.6 + acceleration: 3.78 + command: 80.0 + } + calibration { + speed: 5.8 + acceleration: -7.67 + command: -35.0 + } + calibration { + speed: 5.8 + acceleration: -5.12 + command: -33.0 + } + calibration { + speed: 5.8 + acceleration: -4.52 + command: -32.0 + } + calibration { + speed: 5.8 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 5.8 + acceleration: -3.34 + command: -30.0 + } + calibration { + speed: 5.8 + acceleration: -2.82 + command: -29.0 + } + calibration { + speed: 5.8 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 5.8 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 5.8 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 5.8 + acceleration: -0.86 + command: -25.0 + } + calibration { + speed: 5.8 + acceleration: -0.58 + command: -24.0 + } + calibration { + speed: 5.8 + acceleration: -0.35 + command: -23.0 + } + calibration { + speed: 5.8 + acceleration: -0.29 + command: -22.0 + } + calibration { + speed: 5.8 + acceleration: -0.2 + command: -2.5 + } + calibration { + speed: 5.8 + acceleration: -0.17 + command: -16.0 + } + calibration { + speed: 5.8 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 5.8 + acceleration: -0.13 + command: 17.0 + } + calibration { + speed: 5.8 + acceleration: 0.12 + command: 20.0 + } + calibration { + speed: 5.8 + acceleration: 0.29 + command: 22.0 + } + calibration { + speed: 5.8 + acceleration: 0.59 + command: 25.0 + } + calibration { + speed: 5.8 + acceleration: 0.95 + command: 27.0 + } + calibration { + speed: 5.8 + acceleration: 1.39 + command: 30.0 + } + calibration { + speed: 5.8 + acceleration: 2.3 + command: 35.0 + } + calibration { + speed: 5.8 + acceleration: 2.51 + command: 70.0 + } + calibration { + speed: 5.8 + acceleration: 2.82 + command: 65.0 + } + calibration { + speed: 5.8 + acceleration: 2.94 + command: 40.0 + } + calibration { + speed: 5.8 + acceleration: 3.16 + command: 45.0 + } + calibration { + speed: 5.8 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 5.8 + acceleration: 3.5 + command: 55.0 + } + calibration { + speed: 5.8 + acceleration: 3.56 + command: 60.0 + } + calibration { + speed: 5.8 + acceleration: 3.79 + command: 77.5 + } + calibration { + speed: 6.0 + acceleration: -7.69 + command: -35.0 + } + calibration { + speed: 6.0 + acceleration: -5.1 + command: -33.0 + } + calibration { + speed: 6.0 + acceleration: -4.52 + command: -32.0 + } + calibration { + speed: 6.0 + acceleration: -3.91 + command: -31.0 + } + calibration { + speed: 6.0 + acceleration: -3.34 + command: -30.0 + } + calibration { + speed: 6.0 + acceleration: -2.84 + command: -29.0 + } + calibration { + speed: 6.0 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 6.0 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 6.0 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 6.0 + acceleration: -0.84 + command: -25.0 + } + calibration { + speed: 6.0 + acceleration: -0.58 + command: -24.0 + } + calibration { + speed: 6.0 + acceleration: -0.36 + command: -23.0 + } + calibration { + speed: 6.0 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 6.0 + acceleration: -0.21 + command: -2.5 + } + calibration { + speed: 6.0 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 6.0 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 6.0 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 6.0 + acceleration: -0.11 + command: 17.0 + } + calibration { + speed: 6.0 + acceleration: 0.18 + command: 20.0 + } + calibration { + speed: 6.0 + acceleration: 0.28 + command: 22.0 + } + calibration { + speed: 6.0 + acceleration: 0.56 + command: 25.0 + } + calibration { + speed: 6.0 + acceleration: 0.92 + command: 27.0 + } + calibration { + speed: 6.0 + acceleration: 1.32 + command: 30.0 + } + calibration { + speed: 6.0 + acceleration: 2.23 + command: 35.0 + } + calibration { + speed: 6.0 + acceleration: 2.49 + command: 70.0 + } + calibration { + speed: 6.0 + acceleration: 2.8 + command: 65.0 + } + calibration { + speed: 6.0 + acceleration: 2.87 + command: 40.0 + } + calibration { + speed: 6.0 + acceleration: 3.12 + command: 45.0 + } + calibration { + speed: 6.0 + acceleration: 3.31 + command: 50.0 + } + calibration { + speed: 6.0 + acceleration: 3.46 + command: 55.0 + } + calibration { + speed: 6.0 + acceleration: 3.55 + command: 60.0 + } + calibration { + speed: 6.0 + acceleration: 3.79 + command: 80.0 + } + calibration { + speed: 6.0 + acceleration: 3.8 + command: 75.0 + } + calibration { + speed: 6.2 + acceleration: -7.73 + command: -35.0 + } + calibration { + speed: 6.2 + acceleration: -5.08 + command: -33.0 + } + calibration { + speed: 6.2 + acceleration: -4.53 + command: -32.0 + } + calibration { + speed: 6.2 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 6.2 + acceleration: -3.34 + command: -30.0 + } + calibration { + speed: 6.2 + acceleration: -2.84 + command: -29.0 + } + calibration { + speed: 6.2 + acceleration: -2.23 + command: -28.0 + } + calibration { + speed: 6.2 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 6.2 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 6.2 + acceleration: -0.85 + command: -25.0 + } + calibration { + speed: 6.2 + acceleration: -0.59 + command: -24.0 + } + calibration { + speed: 6.2 + acceleration: -0.38 + command: -23.0 + } + calibration { + speed: 6.2 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 6.2 + acceleration: -0.22 + command: 15.0 + } + calibration { + speed: 6.2 + acceleration: -0.21 + command: -16.5 + } + calibration { + speed: 6.2 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 6.2 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 6.2 + acceleration: -0.12 + command: 17.0 + } + calibration { + speed: 6.2 + acceleration: 0.17 + command: 20.0 + } + calibration { + speed: 6.2 + acceleration: 0.28 + command: 22.0 + } + calibration { + speed: 6.2 + acceleration: 0.55 + command: 25.0 + } + calibration { + speed: 6.2 + acceleration: 0.87 + command: 27.0 + } + calibration { + speed: 6.2 + acceleration: 1.25 + command: 30.0 + } + calibration { + speed: 6.2 + acceleration: 2.16 + command: 35.0 + } + calibration { + speed: 6.2 + acceleration: 2.49 + command: 70.0 + } + calibration { + speed: 6.2 + acceleration: 2.8 + command: 65.0 + } + calibration { + speed: 6.2 + acceleration: 2.81 + command: 40.0 + } + calibration { + speed: 6.2 + acceleration: 3.07 + command: 45.0 + } + calibration { + speed: 6.2 + acceleration: 3.27 + command: 50.0 + } + calibration { + speed: 6.2 + acceleration: 3.42 + command: 55.0 + } + calibration { + speed: 6.2 + acceleration: 3.53 + command: 60.0 + } + calibration { + speed: 6.2 + acceleration: 3.79 + command: 80.0 + } + calibration { + speed: 6.2 + acceleration: 3.8 + command: 75.0 + } + calibration { + speed: 6.4 + acceleration: -7.75 + command: -35.0 + } + calibration { + speed: 6.4 + acceleration: -5.07 + command: -33.0 + } + calibration { + speed: 6.4 + acceleration: -4.54 + command: -32.0 + } + calibration { + speed: 6.4 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 6.4 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 6.4 + acceleration: -2.84 + command: -29.0 + } + calibration { + speed: 6.4 + acceleration: -2.23 + command: -28.0 + } + calibration { + speed: 6.4 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 6.4 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 6.4 + acceleration: -0.86 + command: -25.0 + } + calibration { + speed: 6.4 + acceleration: -0.6 + command: -24.0 + } + calibration { + speed: 6.4 + acceleration: -0.38 + command: -23.0 + } + calibration { + speed: 6.4 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 6.4 + acceleration: -0.25 + command: 15.0 + } + calibration { + speed: 6.4 + acceleration: -0.2 + command: -17.5 + } + calibration { + speed: 6.4 + acceleration: -0.19 + command: -17.0 + } + calibration { + speed: 6.4 + acceleration: -0.17 + command: -13.0 + } + calibration { + speed: 6.4 + acceleration: -0.11 + command: 17.0 + } + calibration { + speed: 6.4 + acceleration: 0.15 + command: 20.0 + } + calibration { + speed: 6.4 + acceleration: 0.26 + command: 22.0 + } + calibration { + speed: 6.4 + acceleration: 0.52 + command: 25.0 + } + calibration { + speed: 6.4 + acceleration: 0.82 + command: 27.0 + } + calibration { + speed: 6.4 + acceleration: 1.2 + command: 30.0 + } + calibration { + speed: 6.4 + acceleration: 2.09 + command: 35.0 + } + calibration { + speed: 6.4 + acceleration: 2.51 + command: 70.0 + } + calibration { + speed: 6.4 + acceleration: 2.74 + command: 40.0 + } + calibration { + speed: 6.4 + acceleration: 2.81 + command: 65.0 + } + calibration { + speed: 6.4 + acceleration: 3.01 + command: 45.0 + } + calibration { + speed: 6.4 + acceleration: 3.23 + command: 50.0 + } + calibration { + speed: 6.4 + acceleration: 3.36 + command: 55.0 + } + calibration { + speed: 6.4 + acceleration: 3.52 + command: 60.0 + } + calibration { + speed: 6.4 + acceleration: 3.79 + command: 77.5 + } + calibration { + speed: 6.6 + acceleration: -7.76 + command: -35.0 + } + calibration { + speed: 6.6 + acceleration: -5.06 + command: -33.0 + } + calibration { + speed: 6.6 + acceleration: -4.55 + command: -32.0 + } + calibration { + speed: 6.6 + acceleration: -3.93 + command: -31.0 + } + calibration { + speed: 6.6 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 6.6 + acceleration: -2.83 + command: -29.0 + } + calibration { + speed: 6.6 + acceleration: -2.23 + command: -28.0 + } + calibration { + speed: 6.6 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 6.6 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 6.6 + acceleration: -0.87 + command: -25.0 + } + calibration { + speed: 6.6 + acceleration: -0.6 + command: -24.0 + } + calibration { + speed: 6.6 + acceleration: -0.38 + command: -23.0 + } + calibration { + speed: 6.6 + acceleration: -0.3 + command: -22.0 + } + calibration { + speed: 6.6 + acceleration: -0.27 + command: 15.0 + } + calibration { + speed: 6.6 + acceleration: -0.21 + command: -18.5 + } + calibration { + speed: 6.6 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 6.6 + acceleration: -0.19 + command: -15.0 + } + calibration { + speed: 6.6 + acceleration: -0.12 + command: 17.0 + } + calibration { + speed: 6.6 + acceleration: 0.11 + command: 20.0 + } + calibration { + speed: 6.6 + acceleration: 0.25 + command: 22.0 + } + calibration { + speed: 6.6 + acceleration: 0.51 + command: 25.0 + } + calibration { + speed: 6.6 + acceleration: 0.81 + command: 27.0 + } + calibration { + speed: 6.6 + acceleration: 1.15 + command: 30.0 + } + calibration { + speed: 6.6 + acceleration: 2.01 + command: 35.0 + } + calibration { + speed: 6.6 + acceleration: 2.55 + command: 70.0 + } + calibration { + speed: 6.6 + acceleration: 2.67 + command: 40.0 + } + calibration { + speed: 6.6 + acceleration: 2.84 + command: 65.0 + } + calibration { + speed: 6.6 + acceleration: 2.95 + command: 45.0 + } + calibration { + speed: 6.6 + acceleration: 3.17 + command: 50.0 + } + calibration { + speed: 6.6 + acceleration: 3.3 + command: 55.0 + } + calibration { + speed: 6.6 + acceleration: 3.49 + command: 60.0 + } + calibration { + speed: 6.6 + acceleration: 3.77 + command: 75.0 + } + calibration { + speed: 6.6 + acceleration: 3.79 + command: 80.0 + } + calibration { + speed: 6.8 + acceleration: -7.76 + command: -35.0 + } + calibration { + speed: 6.8 + acceleration: -5.06 + command: -33.0 + } + calibration { + speed: 6.8 + acceleration: -4.56 + command: -32.0 + } + calibration { + speed: 6.8 + acceleration: -3.94 + command: -31.0 + } + calibration { + speed: 6.8 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 6.8 + acceleration: -2.83 + command: -29.0 + } + calibration { + speed: 6.8 + acceleration: -2.23 + command: -28.0 + } + calibration { + speed: 6.8 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 6.8 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 6.8 + acceleration: -0.87 + command: -25.0 + } + calibration { + speed: 6.8 + acceleration: -0.62 + command: -24.0 + } + calibration { + speed: 6.8 + acceleration: -0.38 + command: -23.0 + } + calibration { + speed: 6.8 + acceleration: -0.31 + command: -22.0 + } + calibration { + speed: 6.8 + acceleration: -0.23 + command: 15.0 + } + calibration { + speed: 6.8 + acceleration: -0.22 + command: -20.0 + } + calibration { + speed: 6.8 + acceleration: -0.21 + command: -14.0 + } + calibration { + speed: 6.8 + acceleration: -0.2 + command: -17.0 + } + calibration { + speed: 6.8 + acceleration: -0.13 + command: 17.0 + } + calibration { + speed: 6.8 + acceleration: 0.12 + command: 20.0 + } + calibration { + speed: 6.8 + acceleration: 0.25 + command: 22.0 + } + calibration { + speed: 6.8 + acceleration: 0.5 + command: 25.0 + } + calibration { + speed: 6.8 + acceleration: 0.77 + command: 27.0 + } + calibration { + speed: 6.8 + acceleration: 1.13 + command: 30.0 + } + calibration { + speed: 6.8 + acceleration: 1.94 + command: 35.0 + } + calibration { + speed: 6.8 + acceleration: 2.59 + command: 70.0 + } + calibration { + speed: 6.8 + acceleration: 2.6 + command: 40.0 + } + calibration { + speed: 6.8 + acceleration: 2.85 + command: 65.0 + } + calibration { + speed: 6.8 + acceleration: 2.88 + command: 45.0 + } + calibration { + speed: 6.8 + acceleration: 3.13 + command: 50.0 + } + calibration { + speed: 6.8 + acceleration: 3.23 + command: 55.0 + } + calibration { + speed: 6.8 + acceleration: 3.46 + command: 60.0 + } + calibration { + speed: 6.8 + acceleration: 3.75 + command: 75.0 + } + calibration { + speed: 6.8 + acceleration: 3.79 + command: 80.0 + } + calibration { + speed: 7.0 + acceleration: -7.75 + command: -35.0 + } + calibration { + speed: 7.0 + acceleration: -5.05 + command: -33.0 + } + calibration { + speed: 7.0 + acceleration: -4.56 + command: -32.0 + } + calibration { + speed: 7.0 + acceleration: -3.96 + command: -31.0 + } + calibration { + speed: 7.0 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 7.0 + acceleration: -2.83 + command: -29.0 + } + calibration { + speed: 7.0 + acceleration: -2.24 + command: -28.0 + } + calibration { + speed: 7.0 + acceleration: -1.82 + command: -27.0 + } + calibration { + speed: 7.0 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 7.0 + acceleration: -0.87 + command: -25.0 + } + calibration { + speed: 7.0 + acceleration: -0.64 + command: -24.0 + } + calibration { + speed: 7.0 + acceleration: -0.38 + command: -23.0 + } + calibration { + speed: 7.0 + acceleration: -0.31 + command: -22.0 + } + calibration { + speed: 7.0 + acceleration: -0.25 + command: 15.0 + } + calibration { + speed: 7.0 + acceleration: -0.24 + command: -20.0 + } + calibration { + speed: 7.0 + acceleration: -0.2 + command: -16.0 + } + calibration { + speed: 7.0 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 7.0 + acceleration: -0.13 + command: 17.0 + } + calibration { + speed: 7.0 + acceleration: 0.09 + command: 20.0 + } + calibration { + speed: 7.0 + acceleration: 0.23 + command: 22.0 + } + calibration { + speed: 7.0 + acceleration: 0.47 + command: 25.0 + } + calibration { + speed: 7.0 + acceleration: 0.77 + command: 27.0 + } + calibration { + speed: 7.0 + acceleration: 1.08 + command: 30.0 + } + calibration { + speed: 7.0 + acceleration: 1.87 + command: 35.0 + } + calibration { + speed: 7.0 + acceleration: 2.53 + command: 40.0 + } + calibration { + speed: 7.0 + acceleration: 2.6 + command: 70.0 + } + calibration { + speed: 7.0 + acceleration: 2.83 + command: 45.0 + } + calibration { + speed: 7.0 + acceleration: 2.86 + command: 65.0 + } + calibration { + speed: 7.0 + acceleration: 3.07 + command: 50.0 + } + calibration { + speed: 7.0 + acceleration: 3.17 + command: 55.0 + } + calibration { + speed: 7.0 + acceleration: 3.42 + command: 60.0 + } + calibration { + speed: 7.0 + acceleration: 3.74 + command: 75.0 + } + calibration { + speed: 7.0 + acceleration: 3.8 + command: 80.0 + } + calibration { + speed: 7.2 + acceleration: -7.73 + command: -35.0 + } + calibration { + speed: 7.2 + acceleration: -5.03 + command: -33.0 + } + calibration { + speed: 7.2 + acceleration: -4.56 + command: -32.0 + } + calibration { + speed: 7.2 + acceleration: -3.96 + command: -31.0 + } + calibration { + speed: 7.2 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 7.2 + acceleration: -2.83 + command: -29.0 + } + calibration { + speed: 7.2 + acceleration: -2.24 + command: -28.0 + } + calibration { + speed: 7.2 + acceleration: -1.83 + command: -27.0 + } + calibration { + speed: 7.2 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 7.2 + acceleration: -0.86 + command: -25.0 + } + calibration { + speed: 7.2 + acceleration: -0.66 + command: -24.0 + } + calibration { + speed: 7.2 + acceleration: -0.36 + command: -23.0 + } + calibration { + speed: 7.2 + acceleration: -0.32 + command: -22.0 + } + calibration { + speed: 7.2 + acceleration: -0.26 + command: -20.0 + } + calibration { + speed: 7.2 + acceleration: -0.22 + command: 1.0 + } + calibration { + speed: 7.2 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 7.2 + acceleration: -0.2 + command: -15.0 + } + calibration { + speed: 7.2 + acceleration: -0.13 + command: 17.0 + } + calibration { + speed: 7.2 + acceleration: 0.11 + command: 20.0 + } + calibration { + speed: 7.2 + acceleration: 0.22 + command: 22.0 + } + calibration { + speed: 7.2 + acceleration: 0.47 + command: 25.0 + } + calibration { + speed: 7.2 + acceleration: 0.74 + command: 27.0 + } + calibration { + speed: 7.2 + acceleration: 1.05 + command: 30.0 + } + calibration { + speed: 7.2 + acceleration: 1.82 + command: 35.0 + } + calibration { + speed: 7.2 + acceleration: 2.46 + command: 40.0 + } + calibration { + speed: 7.2 + acceleration: 2.57 + command: 70.0 + } + calibration { + speed: 7.2 + acceleration: 2.77 + command: 45.0 + } + calibration { + speed: 7.2 + acceleration: 2.87 + command: 65.0 + } + calibration { + speed: 7.2 + acceleration: 3.02 + command: 50.0 + } + calibration { + speed: 7.2 + acceleration: 3.11 + command: 55.0 + } + calibration { + speed: 7.2 + acceleration: 3.37 + command: 60.0 + } + calibration { + speed: 7.2 + acceleration: 3.75 + command: 75.0 + } + calibration { + speed: 7.2 + acceleration: 3.81 + command: 80.0 + } + calibration { + speed: 7.4 + acceleration: -7.7 + command: -35.0 + } + calibration { + speed: 7.4 + acceleration: -5.0 + command: -33.0 + } + calibration { + speed: 7.4 + acceleration: -4.55 + command: -32.0 + } + calibration { + speed: 7.4 + acceleration: -3.97 + command: -31.0 + } + calibration { + speed: 7.4 + acceleration: -3.34 + command: -30.0 + } + calibration { + speed: 7.4 + acceleration: -2.83 + command: -29.0 + } + calibration { + speed: 7.4 + acceleration: -2.24 + command: -28.0 + } + calibration { + speed: 7.4 + acceleration: -1.83 + command: -27.0 + } + calibration { + speed: 7.4 + acceleration: -1.32 + command: -26.0 + } + calibration { + speed: 7.4 + acceleration: -0.86 + command: -25.0 + } + calibration { + speed: 7.4 + acceleration: -0.63 + command: -24.0 + } + calibration { + speed: 7.4 + acceleration: -0.38 + command: -23.0 + } + calibration { + speed: 7.4 + acceleration: -0.32 + command: -22.0 + } + calibration { + speed: 7.4 + acceleration: -0.23 + command: -18.5 + } + calibration { + speed: 7.4 + acceleration: -0.22 + command: 0.0 + } + calibration { + speed: 7.4 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 7.4 + acceleration: -0.15 + command: 17.0 + } + calibration { + speed: 7.4 + acceleration: 0.12 + command: 20.0 + } + calibration { + speed: 7.4 + acceleration: 0.2 + command: 22.0 + } + calibration { + speed: 7.4 + acceleration: 0.45 + command: 25.0 + } + calibration { + speed: 7.4 + acceleration: 0.72 + command: 27.0 + } + calibration { + speed: 7.4 + acceleration: 1.01 + command: 30.0 + } + calibration { + speed: 7.4 + acceleration: 1.77 + command: 35.0 + } + calibration { + speed: 7.4 + acceleration: 2.38 + command: 40.0 + } + calibration { + speed: 7.4 + acceleration: 2.54 + command: 70.0 + } + calibration { + speed: 7.4 + acceleration: 2.7 + command: 45.0 + } + calibration { + speed: 7.4 + acceleration: 2.87 + command: 65.0 + } + calibration { + speed: 7.4 + acceleration: 2.97 + command: 50.0 + } + calibration { + speed: 7.4 + acceleration: 3.04 + command: 55.0 + } + calibration { + speed: 7.4 + acceleration: 3.33 + command: 60.0 + } + calibration { + speed: 7.4 + acceleration: 3.76 + command: 75.0 + } + calibration { + speed: 7.4 + acceleration: 3.81 + command: 80.0 + } + calibration { + speed: 7.6 + acceleration: -7.67 + command: -35.0 + } + calibration { + speed: 7.6 + acceleration: -4.97 + command: -33.0 + } + calibration { + speed: 7.6 + acceleration: -4.52 + command: -32.0 + } + calibration { + speed: 7.6 + acceleration: -3.98 + command: -31.0 + } + calibration { + speed: 7.6 + acceleration: -3.34 + command: -30.0 + } + calibration { + speed: 7.6 + acceleration: -2.82 + command: -29.0 + } + calibration { + speed: 7.6 + acceleration: -2.24 + command: -28.0 + } + calibration { + speed: 7.6 + acceleration: -1.83 + command: -27.0 + } + calibration { + speed: 7.6 + acceleration: -1.33 + command: -26.0 + } + calibration { + speed: 7.6 + acceleration: -0.91 + command: -25.0 + } + calibration { + speed: 7.6 + acceleration: -0.64 + command: -24.0 + } + calibration { + speed: 7.6 + acceleration: -0.36 + command: -23.0 + } + calibration { + speed: 7.6 + acceleration: -0.31 + command: -22.0 + } + calibration { + speed: 7.6 + acceleration: -0.29 + command: 15.0 + } + calibration { + speed: 7.6 + acceleration: -0.24 + command: -16.5 + } + calibration { + speed: 7.6 + acceleration: -0.23 + command: -16.0 + } + calibration { + speed: 7.6 + acceleration: -0.14 + command: 17.0 + } + calibration { + speed: 7.6 + acceleration: 0.07 + command: 20.0 + } + calibration { + speed: 7.6 + acceleration: 0.21 + command: 22.0 + } + calibration { + speed: 7.6 + acceleration: 0.43 + command: 25.0 + } + calibration { + speed: 7.6 + acceleration: 0.7 + command: 27.0 + } + calibration { + speed: 7.6 + acceleration: 0.97 + command: 30.0 + } + calibration { + speed: 7.6 + acceleration: 1.72 + command: 35.0 + } + calibration { + speed: 7.6 + acceleration: 2.32 + command: 40.0 + } + calibration { + speed: 7.6 + acceleration: 2.53 + command: 70.0 + } + calibration { + speed: 7.6 + acceleration: 2.64 + command: 45.0 + } + calibration { + speed: 7.6 + acceleration: 2.9 + command: 65.0 + } + calibration { + speed: 7.6 + acceleration: 2.92 + command: 50.0 + } + calibration { + speed: 7.6 + acceleration: 2.99 + command: 55.0 + } + calibration { + speed: 7.6 + acceleration: 3.29 + command: 60.0 + } + calibration { + speed: 7.6 + acceleration: 3.79 + command: 75.0 + } + calibration { + speed: 7.6 + acceleration: 3.83 + command: 80.0 + } + calibration { + speed: 7.8 + acceleration: -7.64 + command: -35.0 + } + calibration { + speed: 7.8 + acceleration: -4.96 + command: -33.0 + } + calibration { + speed: 7.8 + acceleration: -4.49 + command: -32.0 + } + calibration { + speed: 7.8 + acceleration: -3.97 + command: -31.0 + } + calibration { + speed: 7.8 + acceleration: -3.34 + command: -30.0 + } + calibration { + speed: 7.8 + acceleration: -2.81 + command: -29.0 + } + calibration { + speed: 7.8 + acceleration: -2.25 + command: -28.0 + } + calibration { + speed: 7.8 + acceleration: -1.83 + command: -27.0 + } + calibration { + speed: 7.8 + acceleration: -1.33 + command: -26.0 + } + calibration { + speed: 7.8 + acceleration: -0.9 + command: -25.0 + } + calibration { + speed: 7.8 + acceleration: -0.64 + command: -24.0 + } + calibration { + speed: 7.8 + acceleration: -0.4 + command: -23.0 + } + calibration { + speed: 7.8 + acceleration: -0.32 + command: -22.0 + } + calibration { + speed: 7.8 + acceleration: -0.24 + command: -14.0 + } + calibration { + speed: 7.8 + acceleration: -0.22 + command: -2.5 + } + calibration { + speed: 7.8 + acceleration: -0.2 + command: -17.0 + } + calibration { + speed: 7.8 + acceleration: -0.15 + command: 17.0 + } + calibration { + speed: 7.8 + acceleration: 0.07 + command: 20.0 + } + calibration { + speed: 7.8 + acceleration: 0.17 + command: 22.0 + } + calibration { + speed: 7.8 + acceleration: 0.42 + command: 25.0 + } + calibration { + speed: 7.8 + acceleration: 0.66 + command: 27.0 + } + calibration { + speed: 7.8 + acceleration: 0.95 + command: 30.0 + } + calibration { + speed: 7.8 + acceleration: 1.66 + command: 35.0 + } + calibration { + speed: 7.8 + acceleration: 2.26 + command: 40.0 + } + calibration { + speed: 7.8 + acceleration: 2.56 + command: 70.0 + } + calibration { + speed: 7.8 + acceleration: 2.58 + command: 45.0 + } + calibration { + speed: 7.8 + acceleration: 2.86 + command: 50.0 + } + calibration { + speed: 7.8 + acceleration: 2.91 + command: 65.0 + } + calibration { + speed: 7.8 + acceleration: 2.92 + command: 55.0 + } + calibration { + speed: 7.8 + acceleration: 3.25 + command: 60.0 + } + calibration { + speed: 7.8 + acceleration: 3.81 + command: 75.0 + } + calibration { + speed: 7.8 + acceleration: 3.83 + command: 80.0 + } + calibration { + speed: 8.0 + acceleration: -7.63 + command: -35.0 + } + calibration { + speed: 8.0 + acceleration: -4.96 + command: -33.0 + } + calibration { + speed: 8.0 + acceleration: -4.46 + command: -32.0 + } + calibration { + speed: 8.0 + acceleration: -3.96 + command: -31.0 + } + calibration { + speed: 8.0 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 8.0 + acceleration: -2.79 + command: -29.0 + } + calibration { + speed: 8.0 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 8.0 + acceleration: -1.84 + command: -27.0 + } + calibration { + speed: 8.0 + acceleration: -1.33 + command: -26.0 + } + calibration { + speed: 8.0 + acceleration: -0.9 + command: -25.0 + } + calibration { + speed: 8.0 + acceleration: -0.64 + command: -24.0 + } + calibration { + speed: 8.0 + acceleration: -0.4 + command: -23.0 + } + calibration { + speed: 8.0 + acceleration: -0.34 + command: -22.0 + } + calibration { + speed: 8.0 + acceleration: -0.24 + command: 15.0 + } + calibration { + speed: 8.0 + acceleration: -0.23 + command: -20.0 + } + calibration { + speed: 8.0 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 8.0 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 8.0 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 8.0 + acceleration: -0.14 + command: 17.0 + } + calibration { + speed: 8.0 + acceleration: 0.03 + command: 20.0 + } + calibration { + speed: 8.0 + acceleration: 0.16 + command: 22.0 + } + calibration { + speed: 8.0 + acceleration: 0.39 + command: 25.0 + } + calibration { + speed: 8.0 + acceleration: 0.64 + command: 27.0 + } + calibration { + speed: 8.0 + acceleration: 0.9 + command: 30.0 + } + calibration { + speed: 8.0 + acceleration: 1.61 + command: 35.0 + } + calibration { + speed: 8.0 + acceleration: 2.21 + command: 40.0 + } + calibration { + speed: 8.0 + acceleration: 2.53 + command: 45.0 + } + calibration { + speed: 8.0 + acceleration: 2.6 + command: 70.0 + } + calibration { + speed: 8.0 + acceleration: 2.81 + command: 50.0 + } + calibration { + speed: 8.0 + acceleration: 2.88 + command: 55.0 + } + calibration { + speed: 8.0 + acceleration: 2.92 + command: 65.0 + } + calibration { + speed: 8.0 + acceleration: 3.22 + command: 60.0 + } + calibration { + speed: 8.0 + acceleration: 3.84 + command: 77.5 + } + calibration { + speed: 8.2 + acceleration: -7.64 + command: -35.0 + } + calibration { + speed: 8.2 + acceleration: -4.99 + command: -33.0 + } + calibration { + speed: 8.2 + acceleration: -4.44 + command: -32.0 + } + calibration { + speed: 8.2 + acceleration: -3.94 + command: -31.0 + } + calibration { + speed: 8.2 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 8.2 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 8.2 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 8.2 + acceleration: -1.85 + command: -27.0 + } + calibration { + speed: 8.2 + acceleration: -1.34 + command: -26.0 + } + calibration { + speed: 8.2 + acceleration: -0.89 + command: -25.0 + } + calibration { + speed: 8.2 + acceleration: -0.63 + command: -24.0 + } + calibration { + speed: 8.2 + acceleration: -0.4 + command: -23.0 + } + calibration { + speed: 8.2 + acceleration: -0.33 + command: -22.0 + } + calibration { + speed: 8.2 + acceleration: -0.27 + command: 15.0 + } + calibration { + speed: 8.2 + acceleration: -0.24 + command: -20.0 + } + calibration { + speed: 8.2 + acceleration: -0.23 + command: -13.0 + } + calibration { + speed: 8.2 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 8.2 + acceleration: -0.2 + command: -17.0 + } + calibration { + speed: 8.2 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 8.2 + acceleration: 0.05 + command: 20.0 + } + calibration { + speed: 8.2 + acceleration: 0.12 + command: 22.0 + } + calibration { + speed: 8.2 + acceleration: 0.4 + command: 25.0 + } + calibration { + speed: 8.2 + acceleration: 0.64 + command: 27.0 + } + calibration { + speed: 8.2 + acceleration: 0.9 + command: 30.0 + } + calibration { + speed: 8.2 + acceleration: 1.56 + command: 35.0 + } + calibration { + speed: 8.2 + acceleration: 2.15 + command: 40.0 + } + calibration { + speed: 8.2 + acceleration: 2.48 + command: 45.0 + } + calibration { + speed: 8.2 + acceleration: 2.64 + command: 70.0 + } + calibration { + speed: 8.2 + acceleration: 2.76 + command: 50.0 + } + calibration { + speed: 8.2 + acceleration: 2.83 + command: 55.0 + } + calibration { + speed: 8.2 + acceleration: 2.92 + command: 65.0 + } + calibration { + speed: 8.2 + acceleration: 3.2 + command: 60.0 + } + calibration { + speed: 8.2 + acceleration: 3.84 + command: 80.0 + } + calibration { + speed: 8.2 + acceleration: 3.85 + command: 75.0 + } + calibration { + speed: 8.4 + acceleration: -7.66 + command: -35.0 + } + calibration { + speed: 8.4 + acceleration: -5.05 + command: -33.0 + } + calibration { + speed: 8.4 + acceleration: -4.43 + command: -32.0 + } + calibration { + speed: 8.4 + acceleration: -3.9 + command: -31.0 + } + calibration { + speed: 8.4 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 8.4 + acceleration: -2.79 + command: -29.0 + } + calibration { + speed: 8.4 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 8.4 + acceleration: -1.85 + command: -27.0 + } + calibration { + speed: 8.4 + acceleration: -1.37 + command: -26.0 + } + calibration { + speed: 8.4 + acceleration: -0.89 + command: -25.0 + } + calibration { + speed: 8.4 + acceleration: -0.68 + command: -24.0 + } + calibration { + speed: 8.4 + acceleration: -0.42 + command: -23.0 + } + calibration { + speed: 8.4 + acceleration: -0.34 + command: -22.0 + } + calibration { + speed: 8.4 + acceleration: -0.26 + command: -20.0 + } + calibration { + speed: 8.4 + acceleration: -0.24 + command: 1.0 + } + calibration { + speed: 8.4 + acceleration: -0.22 + command: -16.0 + } + calibration { + speed: 8.4 + acceleration: -0.16 + command: 17.0 + } + calibration { + speed: 8.4 + acceleration: 0.04 + command: 20.0 + } + calibration { + speed: 8.4 + acceleration: 0.16 + command: 22.0 + } + calibration { + speed: 8.4 + acceleration: 0.4 + command: 25.0 + } + calibration { + speed: 8.4 + acceleration: 0.59 + command: 27.0 + } + calibration { + speed: 8.4 + acceleration: 0.87 + command: 30.0 + } + calibration { + speed: 8.4 + acceleration: 1.51 + command: 35.0 + } + calibration { + speed: 8.4 + acceleration: 2.09 + command: 40.0 + } + calibration { + speed: 8.4 + acceleration: 2.44 + command: 45.0 + } + calibration { + speed: 8.4 + acceleration: 2.65 + command: 70.0 + } + calibration { + speed: 8.4 + acceleration: 2.71 + command: 50.0 + } + calibration { + speed: 8.4 + acceleration: 2.79 + command: 55.0 + } + calibration { + speed: 8.4 + acceleration: 2.92 + command: 65.0 + } + calibration { + speed: 8.4 + acceleration: 3.17 + command: 60.0 + } + calibration { + speed: 8.4 + acceleration: 3.84 + command: 80.0 + } + calibration { + speed: 8.4 + acceleration: 3.85 + command: 75.0 + } + calibration { + speed: 8.6 + acceleration: -7.7 + command: -35.0 + } + calibration { + speed: 8.6 + acceleration: -5.08 + command: -33.0 + } + calibration { + speed: 8.6 + acceleration: -4.45 + command: -32.0 + } + calibration { + speed: 8.6 + acceleration: -3.87 + command: -31.0 + } + calibration { + speed: 8.6 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 8.6 + acceleration: -2.82 + command: -29.0 + } + calibration { + speed: 8.6 + acceleration: -2.25 + command: -28.0 + } + calibration { + speed: 8.6 + acceleration: -1.85 + command: -27.0 + } + calibration { + speed: 8.6 + acceleration: -1.35 + command: -26.0 + } + calibration { + speed: 8.6 + acceleration: -0.93 + command: -25.0 + } + calibration { + speed: 8.6 + acceleration: -0.66 + command: -24.0 + } + calibration { + speed: 8.6 + acceleration: -0.4 + command: -23.0 + } + calibration { + speed: 8.6 + acceleration: -0.33 + command: -22.0 + } + calibration { + speed: 8.6 + acceleration: -0.28 + command: 15.0 + } + calibration { + speed: 8.6 + acceleration: -0.27 + command: -15.0 + } + calibration { + speed: 8.6 + acceleration: -0.26 + command: -16.5 + } + calibration { + speed: 8.6 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 8.6 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 8.6 + acceleration: 0.1 + command: 22.0 + } + calibration { + speed: 8.6 + acceleration: 0.36 + command: 25.0 + } + calibration { + speed: 8.6 + acceleration: 0.58 + command: 27.0 + } + calibration { + speed: 8.6 + acceleration: 0.82 + command: 30.0 + } + calibration { + speed: 8.6 + acceleration: 1.47 + command: 35.0 + } + calibration { + speed: 8.6 + acceleration: 2.04 + command: 40.0 + } + calibration { + speed: 8.6 + acceleration: 2.38 + command: 45.0 + } + calibration { + speed: 8.6 + acceleration: 2.62 + command: 70.0 + } + calibration { + speed: 8.6 + acceleration: 2.66 + command: 50.0 + } + calibration { + speed: 8.6 + acceleration: 2.74 + command: 55.0 + } + calibration { + speed: 8.6 + acceleration: 2.9 + command: 65.0 + } + calibration { + speed: 8.6 + acceleration: 3.16 + command: 60.0 + } + calibration { + speed: 8.6 + acceleration: 3.85 + command: 77.5 + } + calibration { + speed: 8.8 + acceleration: -7.78 + command: -35.0 + } + calibration { + speed: 8.8 + acceleration: -5.11 + command: -33.0 + } + calibration { + speed: 8.8 + acceleration: -4.49 + command: -32.0 + } + calibration { + speed: 8.8 + acceleration: -3.85 + command: -31.0 + } + calibration { + speed: 8.8 + acceleration: -3.34 + command: -30.0 + } + calibration { + speed: 8.8 + acceleration: -2.86 + command: -29.0 + } + calibration { + speed: 8.8 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 8.8 + acceleration: -1.86 + command: -27.0 + } + calibration { + speed: 8.8 + acceleration: -1.34 + command: -26.0 + } + calibration { + speed: 8.8 + acceleration: -0.91 + command: -25.0 + } + calibration { + speed: 8.8 + acceleration: -0.7 + command: -24.0 + } + calibration { + speed: 8.8 + acceleration: -0.41 + command: -23.0 + } + calibration { + speed: 8.8 + acceleration: -0.31 + command: -22.0 + } + calibration { + speed: 8.8 + acceleration: -0.29 + command: 15.0 + } + calibration { + speed: 8.8 + acceleration: -0.27 + command: -20.0 + } + calibration { + speed: 8.8 + acceleration: -0.24 + command: -15.0 + } + calibration { + speed: 8.8 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 8.8 + acceleration: -0.16 + command: 17.0 + } + calibration { + speed: 8.8 + acceleration: 0.09 + command: 22.0 + } + calibration { + speed: 8.8 + acceleration: 0.38 + command: 25.0 + } + calibration { + speed: 8.8 + acceleration: 0.55 + command: 27.0 + } + calibration { + speed: 8.8 + acceleration: 0.8 + command: 30.0 + } + calibration { + speed: 8.8 + acceleration: 1.44 + command: 35.0 + } + calibration { + speed: 8.8 + acceleration: 1.98 + command: 40.0 + } + calibration { + speed: 8.8 + acceleration: 2.31 + command: 45.0 + } + calibration { + speed: 8.8 + acceleration: 2.56 + command: 70.0 + } + calibration { + speed: 8.8 + acceleration: 2.61 + command: 50.0 + } + calibration { + speed: 8.8 + acceleration: 2.69 + command: 55.0 + } + calibration { + speed: 8.8 + acceleration: 2.87 + command: 65.0 + } + calibration { + speed: 8.8 + acceleration: 3.13 + command: 60.0 + } + calibration { + speed: 8.8 + acceleration: 3.84 + command: 75.0 + } + calibration { + speed: 8.8 + acceleration: 3.85 + command: 80.0 + } + calibration { + speed: 9.0 + acceleration: -7.84 + command: -35.0 + } + calibration { + speed: 9.0 + acceleration: -5.08 + command: -33.0 + } + calibration { + speed: 9.0 + acceleration: -4.53 + command: -32.0 + } + calibration { + speed: 9.0 + acceleration: -3.86 + command: -31.0 + } + calibration { + speed: 9.0 + acceleration: -3.35 + command: -30.0 + } + calibration { + speed: 9.0 + acceleration: -2.88 + command: -29.0 + } + calibration { + speed: 9.0 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 9.0 + acceleration: -1.87 + command: -27.0 + } + calibration { + speed: 9.0 + acceleration: -1.39 + command: -26.0 + } + calibration { + speed: 9.0 + acceleration: -0.92 + command: -25.0 + } + calibration { + speed: 9.0 + acceleration: -0.67 + command: -24.0 + } + calibration { + speed: 9.0 + acceleration: -0.45 + command: -23.0 + } + calibration { + speed: 9.0 + acceleration: -0.36 + command: -22.0 + } + calibration { + speed: 9.0 + acceleration: -0.34 + command: 15.0 + } + calibration { + speed: 9.0 + acceleration: -0.27 + command: -20.0 + } + calibration { + speed: 9.0 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 9.0 + acceleration: -0.25 + command: -15.0 + } + calibration { + speed: 9.0 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 9.0 + acceleration: 0.08 + command: 22.0 + } + calibration { + speed: 9.0 + acceleration: 0.32 + command: 25.0 + } + calibration { + speed: 9.0 + acceleration: 0.51 + command: 27.0 + } + calibration { + speed: 9.0 + acceleration: 0.76 + command: 30.0 + } + calibration { + speed: 9.0 + acceleration: 1.38 + command: 35.0 + } + calibration { + speed: 9.0 + acceleration: 1.93 + command: 40.0 + } + calibration { + speed: 9.0 + acceleration: 2.26 + command: 45.0 + } + calibration { + speed: 9.0 + acceleration: 2.51 + command: 70.0 + } + calibration { + speed: 9.0 + acceleration: 2.56 + command: 50.0 + } + calibration { + speed: 9.0 + acceleration: 2.63 + command: 55.0 + } + calibration { + speed: 9.0 + acceleration: 2.83 + command: 65.0 + } + calibration { + speed: 9.0 + acceleration: 3.11 + command: 60.0 + } + calibration { + speed: 9.0 + acceleration: 3.84 + command: 75.0 + } + calibration { + speed: 9.0 + acceleration: 3.86 + command: 80.0 + } + calibration { + speed: 9.2 + acceleration: -7.9 + command: -35.0 + } + calibration { + speed: 9.2 + acceleration: -5.01 + command: -33.0 + } + calibration { + speed: 9.2 + acceleration: -4.54 + command: -32.0 + } + calibration { + speed: 9.2 + acceleration: -3.89 + command: -31.0 + } + calibration { + speed: 9.2 + acceleration: -3.31 + command: -30.0 + } + calibration { + speed: 9.2 + acceleration: -2.86 + command: -29.0 + } + calibration { + speed: 9.2 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 9.2 + acceleration: -1.88 + command: -27.0 + } + calibration { + speed: 9.2 + acceleration: -1.37 + command: -26.0 + } + calibration { + speed: 9.2 + acceleration: -0.91 + command: -25.0 + } + calibration { + speed: 9.2 + acceleration: -0.64 + command: -24.0 + } + calibration { + speed: 9.2 + acceleration: -0.42 + command: -23.0 + } + calibration { + speed: 9.2 + acceleration: -0.36 + command: -22.0 + } + calibration { + speed: 9.2 + acceleration: -0.28 + command: -20.0 + } + calibration { + speed: 9.2 + acceleration: -0.27 + command: -1.0 + } + calibration { + speed: 9.2 + acceleration: -0.26 + command: -13.0 + } + calibration { + speed: 9.2 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 9.2 + acceleration: -0.18 + command: 17.0 + } + calibration { + speed: 9.2 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 9.2 + acceleration: 0.34 + command: 25.0 + } + calibration { + speed: 9.2 + acceleration: 0.52 + command: 27.0 + } + calibration { + speed: 9.2 + acceleration: 0.75 + command: 30.0 + } + calibration { + speed: 9.2 + acceleration: 1.33 + command: 35.0 + } + calibration { + speed: 9.2 + acceleration: 1.88 + command: 40.0 + } + calibration { + speed: 9.2 + acceleration: 2.21 + command: 45.0 + } + calibration { + speed: 9.2 + acceleration: 2.48 + command: 70.0 + } + calibration { + speed: 9.2 + acceleration: 2.51 + command: 50.0 + } + calibration { + speed: 9.2 + acceleration: 2.56 + command: 55.0 + } + calibration { + speed: 9.2 + acceleration: 2.78 + command: 65.0 + } + calibration { + speed: 9.2 + acceleration: 3.08 + command: 60.0 + } + calibration { + speed: 9.2 + acceleration: 3.84 + command: 75.0 + } + calibration { + speed: 9.2 + acceleration: 3.86 + command: 80.0 + } + calibration { + speed: 9.4 + acceleration: -7.95 + command: -35.0 + } + calibration { + speed: 9.4 + acceleration: -4.89 + command: -33.0 + } + calibration { + speed: 9.4 + acceleration: -4.52 + command: -32.0 + } + calibration { + speed: 9.4 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 9.4 + acceleration: -3.27 + command: -30.0 + } + calibration { + speed: 9.4 + acceleration: -2.82 + command: -29.0 + } + calibration { + speed: 9.4 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 9.4 + acceleration: -1.87 + command: -27.0 + } + calibration { + speed: 9.4 + acceleration: -1.38 + command: -26.0 + } + calibration { + speed: 9.4 + acceleration: -0.92 + command: -25.0 + } + calibration { + speed: 9.4 + acceleration: -0.66 + command: -24.0 + } + calibration { + speed: 9.4 + acceleration: -0.43 + command: -23.0 + } + calibration { + speed: 9.4 + acceleration: -0.38 + command: -22.0 + } + calibration { + speed: 9.4 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 9.4 + acceleration: -0.29 + command: 15.0 + } + calibration { + speed: 9.4 + acceleration: -0.28 + command: -13.0 + } + calibration { + speed: 9.4 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 9.4 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 9.4 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 9.4 + acceleration: 0.06 + command: 22.0 + } + calibration { + speed: 9.4 + acceleration: 0.32 + command: 25.0 + } + calibration { + speed: 9.4 + acceleration: 0.49 + command: 27.0 + } + calibration { + speed: 9.4 + acceleration: 0.72 + command: 30.0 + } + calibration { + speed: 9.4 + acceleration: 1.29 + command: 35.0 + } + calibration { + speed: 9.4 + acceleration: 1.83 + command: 40.0 + } + calibration { + speed: 9.4 + acceleration: 2.17 + command: 45.0 + } + calibration { + speed: 9.4 + acceleration: 2.46 + command: 60.0 + } + calibration { + speed: 9.4 + acceleration: 2.5 + command: 55.0 + } + calibration { + speed: 9.4 + acceleration: 2.72 + command: 65.0 + } + calibration { + speed: 9.4 + acceleration: 3.05 + command: 60.0 + } + calibration { + speed: 9.4 + acceleration: 3.84 + command: 75.0 + } + calibration { + speed: 9.4 + acceleration: 3.85 + command: 80.0 + } + calibration { + speed: 9.6 + acceleration: -8.0 + command: -35.0 + } + calibration { + speed: 9.6 + acceleration: -4.78 + command: -33.0 + } + calibration { + speed: 9.6 + acceleration: -4.4 + command: -32.0 + } + calibration { + speed: 9.6 + acceleration: -3.95 + command: -31.0 + } + calibration { + speed: 9.6 + acceleration: -3.19 + command: -30.0 + } + calibration { + speed: 9.6 + acceleration: -2.79 + command: -29.0 + } + calibration { + speed: 9.6 + acceleration: -2.27 + command: -28.0 + } + calibration { + speed: 9.6 + acceleration: -1.87 + command: -27.0 + } + calibration { + speed: 9.6 + acceleration: -1.41 + command: -26.0 + } + calibration { + speed: 9.6 + acceleration: -0.93 + command: -25.0 + } + calibration { + speed: 9.6 + acceleration: -0.69 + command: -24.0 + } + calibration { + speed: 9.6 + acceleration: -0.45 + command: -23.0 + } + calibration { + speed: 9.6 + acceleration: -0.37 + command: -22.0 + } + calibration { + speed: 9.6 + acceleration: -0.28 + command: 15.0 + } + calibration { + speed: 9.6 + acceleration: -0.27 + command: -18.5 + } + calibration { + speed: 9.6 + acceleration: -0.25 + command: -13.0 + } + calibration { + speed: 9.6 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 9.6 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 9.6 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 9.6 + acceleration: 0.29 + command: 25.0 + } + calibration { + speed: 9.6 + acceleration: 0.46 + command: 27.0 + } + calibration { + speed: 9.6 + acceleration: 0.66 + command: 30.0 + } + calibration { + speed: 9.6 + acceleration: 1.23 + command: 35.0 + } + calibration { + speed: 9.6 + acceleration: 1.79 + command: 40.0 + } + calibration { + speed: 9.6 + acceleration: 2.13 + command: 45.0 + } + calibration { + speed: 9.6 + acceleration: 2.42 + command: 50.0 + } + calibration { + speed: 9.6 + acceleration: 2.43 + command: 70.0 + } + calibration { + speed: 9.6 + acceleration: 2.44 + command: 55.0 + } + calibration { + speed: 9.6 + acceleration: 2.68 + command: 65.0 + } + calibration { + speed: 9.6 + acceleration: 3.01 + command: 60.0 + } + calibration { + speed: 9.6 + acceleration: 3.81 + command: 80.0 + } + calibration { + speed: 9.6 + acceleration: 3.85 + command: 75.0 + } + calibration { + speed: 9.8 + acceleration: -7.98 + command: -35.0 + } + calibration { + speed: 9.8 + acceleration: -4.71 + command: -33.0 + } + calibration { + speed: 9.8 + acceleration: -4.32 + command: -32.0 + } + calibration { + speed: 9.8 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 9.8 + acceleration: -3.13 + command: -30.0 + } + calibration { + speed: 9.8 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 9.8 + acceleration: -2.28 + command: -28.0 + } + calibration { + speed: 9.8 + acceleration: -1.88 + command: -27.0 + } + calibration { + speed: 9.8 + acceleration: -1.41 + command: -26.0 + } + calibration { + speed: 9.8 + acceleration: -0.95 + command: -25.0 + } + calibration { + speed: 9.8 + acceleration: -0.68 + command: -24.0 + } + calibration { + speed: 9.8 + acceleration: -0.56 + command: 20.0 + } + calibration { + speed: 9.8 + acceleration: -0.45 + command: -23.0 + } + calibration { + speed: 9.8 + acceleration: -0.36 + command: -22.0 + } + calibration { + speed: 9.8 + acceleration: -0.31 + command: -17.0 + } + calibration { + speed: 9.8 + acceleration: -0.28 + command: 15.0 + } + calibration { + speed: 9.8 + acceleration: -0.27 + command: -16.5 + } + calibration { + speed: 9.8 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 9.8 + acceleration: -0.15 + command: 17.0 + } + calibration { + speed: 9.8 + acceleration: 0.09 + command: 22.0 + } + calibration { + speed: 9.8 + acceleration: 0.27 + command: 25.0 + } + calibration { + speed: 9.8 + acceleration: 0.44 + command: 27.0 + } + calibration { + speed: 9.8 + acceleration: 0.68 + command: 30.0 + } + calibration { + speed: 9.8 + acceleration: 1.22 + command: 35.0 + } + calibration { + speed: 9.8 + acceleration: 1.75 + command: 40.0 + } + calibration { + speed: 9.8 + acceleration: 2.08 + command: 45.0 + } + calibration { + speed: 9.8 + acceleration: 2.37 + command: 50.0 + } + calibration { + speed: 9.8 + acceleration: 2.4 + command: 55.0 + } + calibration { + speed: 9.8 + acceleration: 2.41 + command: 70.0 + } + calibration { + speed: 9.8 + acceleration: 2.66 + command: 65.0 + } + calibration { + speed: 9.8 + acceleration: 2.96 + command: 60.0 + } + calibration { + speed: 9.8 + acceleration: 3.76 + command: 80.0 + } + calibration { + speed: 9.8 + acceleration: 3.85 + command: 75.0 + } + calibration { + speed: 10.0 + acceleration: -7.91 + command: -35.0 + } + calibration { + speed: 10.0 + acceleration: -4.71 + command: -33.0 + } + calibration { + speed: 10.0 + acceleration: -4.25 + command: -32.0 + } + calibration { + speed: 10.0 + acceleration: -3.83 + command: -31.0 + } + calibration { + speed: 10.0 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 10.0 + acceleration: -2.82 + command: -29.0 + } + calibration { + speed: 10.0 + acceleration: -2.28 + command: -28.0 + } + calibration { + speed: 10.0 + acceleration: -1.89 + command: -27.0 + } + calibration { + speed: 10.0 + acceleration: -1.39 + command: -26.0 + } + calibration { + speed: 10.0 + acceleration: -0.95 + command: -25.0 + } + calibration { + speed: 10.0 + acceleration: -0.69 + command: -24.0 + } + calibration { + speed: 10.0 + acceleration: -0.46 + command: -23.0 + } + calibration { + speed: 10.0 + acceleration: -0.36 + command: -22.0 + } + calibration { + speed: 10.0 + acceleration: -0.3 + command: -14.0 + } + calibration { + speed: 10.0 + acceleration: -0.29 + command: -2.5 + } + calibration { + speed: 10.0 + acceleration: -0.28 + command: -17.0 + } + calibration { + speed: 10.0 + acceleration: -0.16 + command: 17.0 + } + calibration { + speed: 10.0 + acceleration: -0.04 + command: 20.0 + } + calibration { + speed: 10.0 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 10.0 + acceleration: 0.26 + command: 25.0 + } + calibration { + speed: 10.0 + acceleration: 0.42 + command: 27.0 + } + calibration { + speed: 10.0 + acceleration: 0.64 + command: 30.0 + } + calibration { + speed: 10.0 + acceleration: 1.2 + command: 35.0 + } + calibration { + speed: 10.0 + acceleration: 1.71 + command: 40.0 + } + calibration { + speed: 10.0 + acceleration: 2.03 + command: 45.0 + } + calibration { + speed: 10.0 + acceleration: 2.33 + command: 50.0 + } + calibration { + speed: 10.0 + acceleration: 2.36 + command: 55.0 + } + calibration { + speed: 10.0 + acceleration: 2.37 + command: 70.0 + } + calibration { + speed: 10.0 + acceleration: 2.65 + command: 65.0 + } + calibration { + speed: 10.0 + acceleration: 2.92 + command: 60.0 + } + calibration { + speed: 10.0 + acceleration: 3.7 + command: 80.0 + } + calibration { + speed: 10.0 + acceleration: 3.84 + command: 75.0 + } + } +} +trajectory_period: 0.1 +chassis_period: 0.01 +localization_period: 0.01 diff --git a/apollo_control/conf/lincoln_062146.pb.txt b/apollo_control/conf/lincoln_062146.pb.txt new file mode 100644 index 0000000..010f12a --- /dev/null +++ b/apollo_control/conf/lincoln_062146.pb.txt @@ -0,0 +1,7780 @@ +control_period: 0.01 +max_planning_interval_sec: 0.2 +max_planning_delay_threshold: 4.0 +action: STOP +soft_estop_brake: 50.0 +active_controllers: LAT_CONTROLLER +active_controllers: LON_CONTROLLER +max_steering_percentage_allowed: 100 +max_status_interval_sec: 0.1 +lat_controller_conf { + ts: 0.01 + preview_window: 0 + cf: 155494.663 + cr: 155494.663 + wheelbase: 2.85 + mass_fl: 520 + mass_fr: 520 + mass_rl: 520 + mass_rr: 520 + eps: 0.01 + matrix_q: 0.05 + matrix_q: 0.0 + matrix_q: 1.0 + matrix_q: 0.0 + cutoff_freq: 10 + mean_filter_window_size: 10 + steer_transmission_ratio: 16 + steer_single_direction_max_degree: 470 + max_iteration: 150 +} +lon_controller_conf { + ts: 0.01 + brake_deadzone: 15.5 + throttle_deadzone: 18.0 + speed_controller_input_limit: 2.0 + station_error_limit: 2.0 + preview_window: 20.0 + standstill_acceleration: -3.0 + station_pid_conf { + integrator_enable: false + integrator_saturation_level: 0.3 + kp: 0.2 + ki: 0.0 + kd: 0.0 + } + low_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 0.5 + ki: 0.3 + kd: 0.0 + } + high_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 1.0 + ki: 0.3 + kd: 0.0 + } + switch_speed: 2.0 + throttle_filter_conf { + cutoff_freq: 10 + } + brake_filter_conf { + cutoff_freq: 10 + } + acceleration_filter_conf { + cutoff_freq: 5 + } + calibration_table { + calibration { + speed: 0.0 + acceleration: -5.11 + command: -35.0 + } + calibration { + speed: 0.0 + acceleration: -4.02 + command: -33.0 + } + calibration { + speed: 0.0 + acceleration: -3.41 + command: -31.0 + } + calibration { + speed: 0.0 + acceleration: -3.39 + command: -32.0 + } + calibration { + speed: 0.0 + acceleration: -3.17 + command: -30.0 + } + calibration { + speed: 0.0 + acceleration: -2.93 + command: -29.0 + } + calibration { + speed: 0.0 + acceleration: -2.61 + command: -28.0 + } + calibration { + speed: 0.0 + acceleration: -2.19 + command: -27.0 + } + calibration { + speed: 0.0 + acceleration: -1.69 + command: -26.0 + } + calibration { + speed: 0.0 + acceleration: -1.17 + command: -25.0 + } + calibration { + speed: 0.0 + acceleration: -0.73 + command: -24.0 + } + calibration { + speed: 0.0 + acceleration: -0.46 + command: -23.0 + } + calibration { + speed: 0.0 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 0.0 + acceleration: -0.02 + command: -20.0 + } + calibration { + speed: 0.0 + acceleration: 0.21 + command: -13.0 + } + calibration { + speed: 0.0 + acceleration: 0.34 + command: -17.0 + } + calibration { + speed: 0.0 + acceleration: 0.36 + command: 0.0 + } + calibration { + speed: 0.0 + acceleration: 0.39 + command: 17.0 + } + calibration { + speed: 0.0 + acceleration: 0.8 + command: 20.0 + } + calibration { + speed: 0.0 + acceleration: 1.31 + command: 30.0 + } + calibration { + speed: 0.0 + acceleration: 1.35 + command: 25.0 + } + calibration { + speed: 0.0 + acceleration: 1.4 + command: 27.0 + } + calibration { + speed: 0.0 + acceleration: 1.55 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 1.71 + command: 40.0 + } + calibration { + speed: 0.0 + acceleration: 1.76 + command: 60.0 + } + calibration { + speed: 0.0 + acceleration: 1.79 + command: 45.0 + } + calibration { + speed: 0.0 + acceleration: 1.88 + command: 52.5 + } + calibration { + speed: 0.0 + acceleration: 2.08 + command: 70.0 + } + calibration { + speed: 0.0 + acceleration: 2.09 + command: 65.0 + } + calibration { + speed: 0.0 + acceleration: 2.1 + command: 80.0 + } + calibration { + speed: 0.0 + acceleration: 2.11 + command: 75.0 + } + calibration { + speed: 0.2 + acceleration: -5.43 + command: -35.0 + } + calibration { + speed: 0.2 + acceleration: -4.28 + command: -33.0 + } + calibration { + speed: 0.2 + acceleration: -3.6 + command: -32.0 + } + calibration { + speed: 0.2 + acceleration: -3.58 + command: -31.0 + } + calibration { + speed: 0.2 + acceleration: -3.27 + command: -30.0 + } + calibration { + speed: 0.2 + acceleration: -3.01 + command: -29.0 + } + calibration { + speed: 0.2 + acceleration: -2.65 + command: -28.0 + } + calibration { + speed: 0.2 + acceleration: -2.22 + command: -27.0 + } + calibration { + speed: 0.2 + acceleration: -1.7 + command: -26.0 + } + calibration { + speed: 0.2 + acceleration: -1.17 + command: -25.0 + } + calibration { + speed: 0.2 + acceleration: -0.73 + command: -24.0 + } + calibration { + speed: 0.2 + acceleration: -0.46 + command: -23.0 + } + calibration { + speed: 0.2 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 0.2 + acceleration: -0.02 + command: -20.0 + } + calibration { + speed: 0.2 + acceleration: 0.21 + command: -13.0 + } + calibration { + speed: 0.2 + acceleration: 0.34 + command: -17.0 + } + calibration { + speed: 0.2 + acceleration: 0.36 + command: -15.0 + } + calibration { + speed: 0.2 + acceleration: 0.37 + command: 15.0 + } + calibration { + speed: 0.2 + acceleration: 0.39 + command: 17.0 + } + calibration { + speed: 0.2 + acceleration: 0.81 + command: 20.0 + } + calibration { + speed: 0.2 + acceleration: 1.36 + command: 27.5 + } + calibration { + speed: 0.2 + acceleration: 1.44 + command: 27.0 + } + calibration { + speed: 0.2 + acceleration: 1.62 + command: 35.0 + } + calibration { + speed: 0.2 + acceleration: 1.79 + command: 40.0 + } + calibration { + speed: 0.2 + acceleration: 1.87 + command: 60.0 + } + calibration { + speed: 0.2 + acceleration: 1.9 + command: 45.0 + } + calibration { + speed: 0.2 + acceleration: 2.0 + command: 50.0 + } + calibration { + speed: 0.2 + acceleration: 2.01 + command: 55.0 + } + calibration { + speed: 0.2 + acceleration: 2.21 + command: 70.0 + } + calibration { + speed: 0.2 + acceleration: 2.22 + command: 65.0 + } + calibration { + speed: 0.2 + acceleration: 2.23 + command: 80.0 + } + calibration { + speed: 0.2 + acceleration: 2.26 + command: 75.0 + } + calibration { + speed: 0.4 + acceleration: -6.7 + command: -35.0 + } + calibration { + speed: 0.4 + acceleration: -5.53 + command: -33.0 + } + calibration { + speed: 0.4 + acceleration: -4.68 + command: -32.0 + } + calibration { + speed: 0.4 + acceleration: -4.44 + command: -31.0 + } + calibration { + speed: 0.4 + acceleration: -3.82 + command: -30.0 + } + calibration { + speed: 0.4 + acceleration: -3.48 + command: -29.0 + } + calibration { + speed: 0.4 + acceleration: -2.92 + command: -28.0 + } + calibration { + speed: 0.4 + acceleration: -2.43 + command: -27.0 + } + calibration { + speed: 0.4 + acceleration: -1.75 + command: -26.0 + } + calibration { + speed: 0.4 + acceleration: -1.18 + command: -25.0 + } + calibration { + speed: 0.4 + acceleration: -0.74 + command: -24.0 + } + calibration { + speed: 0.4 + acceleration: -0.51 + command: -23.0 + } + calibration { + speed: 0.4 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 0.4 + acceleration: 0.01 + command: -20.0 + } + calibration { + speed: 0.4 + acceleration: 0.21 + command: -13.0 + } + calibration { + speed: 0.4 + acceleration: 0.34 + command: -17.0 + } + calibration { + speed: 0.4 + acceleration: 0.35 + command: 15.0 + } + calibration { + speed: 0.4 + acceleration: 0.36 + command: -15.0 + } + calibration { + speed: 0.4 + acceleration: 0.39 + command: 17.0 + } + calibration { + speed: 0.4 + acceleration: 0.88 + command: 20.0 + } + calibration { + speed: 0.4 + acceleration: 1.46 + command: 25.0 + } + calibration { + speed: 0.4 + acceleration: 1.49 + command: 30.0 + } + calibration { + speed: 0.4 + acceleration: 1.61 + command: 27.0 + } + calibration { + speed: 0.4 + acceleration: 1.83 + command: 35.0 + } + calibration { + speed: 0.4 + acceleration: 1.99 + command: 40.0 + } + calibration { + speed: 0.4 + acceleration: 2.11 + command: 60.0 + } + calibration { + speed: 0.4 + acceleration: 2.14 + command: 45.0 + } + calibration { + speed: 0.4 + acceleration: 2.29 + command: 50.0 + } + calibration { + speed: 0.4 + acceleration: 2.31 + command: 55.0 + } + calibration { + speed: 0.4 + acceleration: 2.48 + command: 65.0 + } + calibration { + speed: 0.4 + acceleration: 2.49 + command: 80.0 + } + calibration { + speed: 0.4 + acceleration: 2.51 + command: 70.0 + } + calibration { + speed: 0.4 + acceleration: 2.55 + command: 75.0 + } + calibration { + speed: 0.6 + acceleration: -7.95 + command: -35.0 + } + calibration { + speed: 0.6 + acceleration: -7.13 + command: -33.0 + } + calibration { + speed: 0.6 + acceleration: -5.64 + command: -32.0 + } + calibration { + speed: 0.6 + acceleration: -5.08 + command: -31.0 + } + calibration { + speed: 0.6 + acceleration: -4.34 + command: -30.0 + } + calibration { + speed: 0.6 + acceleration: -3.84 + command: -29.0 + } + calibration { + speed: 0.6 + acceleration: -3.13 + command: -28.0 + } + calibration { + speed: 0.6 + acceleration: -2.54 + command: -27.0 + } + calibration { + speed: 0.6 + acceleration: -1.78 + command: -26.0 + } + calibration { + speed: 0.6 + acceleration: -1.2 + command: -25.0 + } + calibration { + speed: 0.6 + acceleration: -0.75 + command: -24.0 + } + calibration { + speed: 0.6 + acceleration: -0.53 + command: -23.0 + } + calibration { + speed: 0.6 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 0.6 + acceleration: 0.01 + command: -20.0 + } + calibration { + speed: 0.6 + acceleration: 0.19 + command: -13.0 + } + calibration { + speed: 0.6 + acceleration: 0.32 + command: -16.0 + } + calibration { + speed: 0.6 + acceleration: 0.33 + command: 15.0 + } + calibration { + speed: 0.6 + acceleration: 0.36 + command: 17.0 + } + calibration { + speed: 0.6 + acceleration: 0.93 + command: 20.0 + } + calibration { + speed: 0.6 + acceleration: 1.58 + command: 25.0 + } + calibration { + speed: 0.6 + acceleration: 1.66 + command: 30.0 + } + calibration { + speed: 0.6 + acceleration: 1.81 + command: 27.0 + } + calibration { + speed: 0.6 + acceleration: 2.06 + command: 35.0 + } + calibration { + speed: 0.6 + acceleration: 2.22 + command: 40.0 + } + calibration { + speed: 0.6 + acceleration: 2.28 + command: 60.0 + } + calibration { + speed: 0.6 + acceleration: 2.38 + command: 45.0 + } + calibration { + speed: 0.6 + acceleration: 2.52 + command: 50.0 + } + calibration { + speed: 0.6 + acceleration: 2.54 + command: 55.0 + } + calibration { + speed: 0.6 + acceleration: 2.64 + command: 80.0 + } + calibration { + speed: 0.6 + acceleration: 2.7 + command: 65.0 + } + calibration { + speed: 0.6 + acceleration: 2.71 + command: 70.0 + } + calibration { + speed: 0.6 + acceleration: 2.75 + command: 75.0 + } + calibration { + speed: 0.8 + acceleration: -8.89 + command: -35.0 + } + calibration { + speed: 0.8 + acceleration: -7.89 + command: -33.0 + } + calibration { + speed: 0.8 + acceleration: -5.88 + command: -32.0 + } + calibration { + speed: 0.8 + acceleration: -5.21 + command: -31.0 + } + calibration { + speed: 0.8 + acceleration: -4.41 + command: -30.0 + } + calibration { + speed: 0.8 + acceleration: -3.83 + command: -29.0 + } + calibration { + speed: 0.8 + acceleration: -3.08 + command: -28.0 + } + calibration { + speed: 0.8 + acceleration: -2.48 + command: -27.0 + } + calibration { + speed: 0.8 + acceleration: -1.76 + command: -26.0 + } + calibration { + speed: 0.8 + acceleration: -1.21 + command: -25.0 + } + calibration { + speed: 0.8 + acceleration: -0.75 + command: -24.0 + } + calibration { + speed: 0.8 + acceleration: -0.51 + command: -23.0 + } + calibration { + speed: 0.8 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 0.8 + acceleration: 0.01 + command: -20.0 + } + calibration { + speed: 0.8 + acceleration: 0.18 + command: -13.0 + } + calibration { + speed: 0.8 + acceleration: 0.26 + command: -1.0 + } + calibration { + speed: 0.8 + acceleration: 0.28 + command: -15.0 + } + calibration { + speed: 0.8 + acceleration: 0.31 + command: 17.0 + } + calibration { + speed: 0.8 + acceleration: 0.95 + command: 20.0 + } + calibration { + speed: 0.8 + acceleration: 1.69 + command: 25.0 + } + calibration { + speed: 0.8 + acceleration: 1.8 + command: 30.0 + } + calibration { + speed: 0.8 + acceleration: 2.02 + command: 27.0 + } + calibration { + speed: 0.8 + acceleration: 2.27 + command: 35.0 + } + calibration { + speed: 0.8 + acceleration: 2.36 + command: 60.0 + } + calibration { + speed: 0.8 + acceleration: 2.43 + command: 40.0 + } + calibration { + speed: 0.8 + acceleration: 2.56 + command: 45.0 + } + calibration { + speed: 0.8 + acceleration: 2.67 + command: 55.0 + } + calibration { + speed: 0.8 + acceleration: 2.68 + command: 50.0 + } + calibration { + speed: 0.8 + acceleration: 2.69 + command: 80.0 + } + calibration { + speed: 0.8 + acceleration: 2.77 + command: 70.0 + } + calibration { + speed: 0.8 + acceleration: 2.78 + command: 65.0 + } + calibration { + speed: 0.8 + acceleration: 2.82 + command: 75.0 + } + calibration { + speed: 1.0 + acceleration: -9.22 + command: -35.0 + } + calibration { + speed: 1.0 + acceleration: -8.03 + command: -33.0 + } + calibration { + speed: 1.0 + acceleration: -5.8 + command: -32.0 + } + calibration { + speed: 1.0 + acceleration: -5.04 + command: -31.0 + } + calibration { + speed: 1.0 + acceleration: -4.29 + command: -30.0 + } + calibration { + speed: 1.0 + acceleration: -3.7 + command: -29.0 + } + calibration { + speed: 1.0 + acceleration: -3.0 + command: -28.0 + } + calibration { + speed: 1.0 + acceleration: -2.45 + command: -27.0 + } + calibration { + speed: 1.0 + acceleration: -1.76 + command: -26.0 + } + calibration { + speed: 1.0 + acceleration: -1.2 + command: -25.0 + } + calibration { + speed: 1.0 + acceleration: -0.77 + command: -24.0 + } + calibration { + speed: 1.0 + acceleration: -0.54 + command: -23.0 + } + calibration { + speed: 1.0 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 1.0 + acceleration: 0.04 + command: -20.0 + } + calibration { + speed: 1.0 + acceleration: 0.13 + command: -13.0 + } + calibration { + speed: 1.0 + acceleration: 0.2 + command: -16.0 + } + calibration { + speed: 1.0 + acceleration: 0.24 + command: 17.0 + } + calibration { + speed: 1.0 + acceleration: 0.25 + command: 15.0 + } + calibration { + speed: 1.0 + acceleration: 0.94 + command: 20.0 + } + calibration { + speed: 1.0 + acceleration: 1.75 + command: 25.0 + } + calibration { + speed: 1.0 + acceleration: 1.92 + command: 30.0 + } + calibration { + speed: 1.0 + acceleration: 2.16 + command: 27.0 + } + calibration { + speed: 1.0 + acceleration: 2.4 + command: 60.0 + } + calibration { + speed: 1.0 + acceleration: 2.47 + command: 35.0 + } + calibration { + speed: 1.0 + acceleration: 2.62 + command: 40.0 + } + calibration { + speed: 1.0 + acceleration: 2.7 + command: 45.0 + } + calibration { + speed: 1.0 + acceleration: 2.72 + command: 80.0 + } + calibration { + speed: 1.0 + acceleration: 2.77 + command: 55.0 + } + calibration { + speed: 1.0 + acceleration: 2.79 + command: 70.0 + } + calibration { + speed: 1.0 + acceleration: 2.8 + command: 50.0 + } + calibration { + speed: 1.0 + acceleration: 2.83 + command: 70.0 + } + calibration { + speed: 1.2 + acceleration: -9.23 + command: -35.0 + } + calibration { + speed: 1.2 + acceleration: -7.99 + command: -33.0 + } + calibration { + speed: 1.2 + acceleration: -5.61 + command: -32.0 + } + calibration { + speed: 1.2 + acceleration: -4.85 + command: -31.0 + } + calibration { + speed: 1.2 + acceleration: -4.13 + command: -30.0 + } + calibration { + speed: 1.2 + acceleration: -3.58 + command: -29.0 + } + calibration { + speed: 1.2 + acceleration: -2.96 + command: -28.0 + } + calibration { + speed: 1.2 + acceleration: -2.45 + command: -27.0 + } + calibration { + speed: 1.2 + acceleration: -1.75 + command: -26.0 + } + calibration { + speed: 1.2 + acceleration: -1.24 + command: -25.0 + } + calibration { + speed: 1.2 + acceleration: -0.78 + command: -24.0 + } + calibration { + speed: 1.2 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 1.2 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 1.2 + acceleration: 0.1 + command: -13.0 + } + calibration { + speed: 1.2 + acceleration: 0.14 + command: -1.0 + } + calibration { + speed: 1.2 + acceleration: 0.15 + command: -15.0 + } + calibration { + speed: 1.2 + acceleration: 0.2 + command: 17.0 + } + calibration { + speed: 1.2 + acceleration: 0.94 + command: 20.0 + } + calibration { + speed: 1.2 + acceleration: 1.79 + command: 25.0 + } + calibration { + speed: 1.2 + acceleration: 2.01 + command: 30.0 + } + calibration { + speed: 1.2 + acceleration: 2.24 + command: 27.0 + } + calibration { + speed: 1.2 + acceleration: 2.46 + command: 60.0 + } + calibration { + speed: 1.2 + acceleration: 2.64 + command: 35.0 + } + calibration { + speed: 1.2 + acceleration: 2.78 + command: 40.0 + } + calibration { + speed: 1.2 + acceleration: 2.79 + command: 80.0 + } + calibration { + speed: 1.2 + acceleration: 2.83 + command: 45.0 + } + calibration { + speed: 1.2 + acceleration: 2.84 + command: 70.0 + } + calibration { + speed: 1.2 + acceleration: 2.87 + command: 65.0 + } + calibration { + speed: 1.2 + acceleration: 2.89 + command: 65.0 + } + calibration { + speed: 1.2 + acceleration: 2.91 + command: 50.0 + } + calibration { + speed: 1.4 + acceleration: -9.29 + command: -35.0 + } + calibration { + speed: 1.4 + acceleration: -7.82 + command: -33.0 + } + calibration { + speed: 1.4 + acceleration: -5.37 + command: -32.0 + } + calibration { + speed: 1.4 + acceleration: -4.68 + command: -31.0 + } + calibration { + speed: 1.4 + acceleration: -4.04 + command: -30.0 + } + calibration { + speed: 1.4 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 1.4 + acceleration: -2.95 + command: -28.0 + } + calibration { + speed: 1.4 + acceleration: -2.42 + command: -27.0 + } + calibration { + speed: 1.4 + acceleration: -1.74 + command: -26.0 + } + calibration { + speed: 1.4 + acceleration: -1.24 + command: -25.0 + } + calibration { + speed: 1.4 + acceleration: -0.76 + command: -24.0 + } + calibration { + speed: 1.4 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 1.4 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 1.4 + acceleration: 0.07 + command: -13.0 + } + calibration { + speed: 1.4 + acceleration: 0.08 + command: -17.0 + } + calibration { + speed: 1.4 + acceleration: 0.09 + command: -15.0 + } + calibration { + speed: 1.4 + acceleration: 0.11 + command: 17.0 + } + calibration { + speed: 1.4 + acceleration: 0.12 + command: 15.0 + } + calibration { + speed: 1.4 + acceleration: 0.93 + command: 20.0 + } + calibration { + speed: 1.4 + acceleration: 1.83 + command: 25.0 + } + calibration { + speed: 1.4 + acceleration: 2.07 + command: 30.0 + } + calibration { + speed: 1.4 + acceleration: 2.29 + command: 27.0 + } + calibration { + speed: 1.4 + acceleration: 2.52 + command: 60.0 + } + calibration { + speed: 1.4 + acceleration: 2.77 + command: 35.0 + } + calibration { + speed: 1.4 + acceleration: 2.91 + command: 80.0 + } + calibration { + speed: 1.4 + acceleration: 2.92 + command: 40.0 + } + calibration { + speed: 1.4 + acceleration: 2.95 + command: 57.5 + } + calibration { + speed: 1.4 + acceleration: 2.97 + command: 65.0 + } + calibration { + speed: 1.4 + acceleration: 2.99 + command: 65.0 + } + calibration { + speed: 1.4 + acceleration: 3.02 + command: 50.0 + } + calibration { + speed: 1.6 + acceleration: -9.37 + command: -35.0 + } + calibration { + speed: 1.6 + acceleration: -7.6 + command: -33.0 + } + calibration { + speed: 1.6 + acceleration: -5.25 + command: -32.0 + } + calibration { + speed: 1.6 + acceleration: -4.63 + command: -31.0 + } + calibration { + speed: 1.6 + acceleration: -4.02 + command: -30.0 + } + calibration { + speed: 1.6 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 1.6 + acceleration: -2.94 + command: -28.0 + } + calibration { + speed: 1.6 + acceleration: -2.37 + command: -27.0 + } + calibration { + speed: 1.6 + acceleration: -1.73 + command: -26.0 + } + calibration { + speed: 1.6 + acceleration: -1.19 + command: -25.0 + } + calibration { + speed: 1.6 + acceleration: -0.77 + command: -24.0 + } + calibration { + speed: 1.6 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 1.6 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 1.6 + acceleration: 0.03 + command: -15.0 + } + calibration { + speed: 1.6 + acceleration: 0.04 + command: -4.33333333333 + } + calibration { + speed: 1.6 + acceleration: 0.06 + command: 15.0 + } + calibration { + speed: 1.6 + acceleration: 0.88 + command: 20.0 + } + calibration { + speed: 1.6 + acceleration: 1.85 + command: 25.0 + } + calibration { + speed: 1.6 + acceleration: 2.12 + command: 30.0 + } + calibration { + speed: 1.6 + acceleration: 2.33 + command: 27.0 + } + calibration { + speed: 1.6 + acceleration: 2.51 + command: 60.0 + } + calibration { + speed: 1.6 + acceleration: 2.87 + command: 35.0 + } + calibration { + speed: 1.6 + acceleration: 3.01 + command: 45.0 + } + calibration { + speed: 1.6 + acceleration: 3.02 + command: 60.0 + } + calibration { + speed: 1.6 + acceleration: 3.06 + command: 70.0 + } + calibration { + speed: 1.6 + acceleration: 3.09 + command: 60.0 + } + calibration { + speed: 1.6 + acceleration: 3.1 + command: 75.0 + } + calibration { + speed: 1.6 + acceleration: 3.12 + command: 50.0 + } + calibration { + speed: 1.8 + acceleration: -9.46 + command: -35.0 + } + calibration { + speed: 1.8 + acceleration: -7.47 + command: -33.0 + } + calibration { + speed: 1.8 + acceleration: -5.23 + command: -32.0 + } + calibration { + speed: 1.8 + acceleration: -4.66 + command: -31.0 + } + calibration { + speed: 1.8 + acceleration: -4.05 + command: -30.0 + } + calibration { + speed: 1.8 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 1.8 + acceleration: -2.92 + command: -28.0 + } + calibration { + speed: 1.8 + acceleration: -2.32 + command: -27.0 + } + calibration { + speed: 1.8 + acceleration: -1.73 + command: -26.0 + } + calibration { + speed: 1.8 + acceleration: -1.2 + command: -25.0 + } + calibration { + speed: 1.8 + acceleration: -0.78 + command: -24.0 + } + calibration { + speed: 1.8 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 1.8 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 1.8 + acceleration: -0.03 + command: 15.0 + } + calibration { + speed: 1.8 + acceleration: -0.02 + command: 17.0 + } + calibration { + speed: 1.8 + acceleration: 0.03 + command: -13.0 + } + calibration { + speed: 1.8 + acceleration: 0.83 + command: 20.0 + } + calibration { + speed: 1.8 + acceleration: 1.86 + command: 25.0 + } + calibration { + speed: 1.8 + acceleration: 2.17 + command: 30.0 + } + calibration { + speed: 1.8 + acceleration: 2.37 + command: 27.0 + } + calibration { + speed: 1.8 + acceleration: 2.48 + command: 60.0 + } + calibration { + speed: 1.8 + acceleration: 2.95 + command: 35.0 + } + calibration { + speed: 1.8 + acceleration: 3.05 + command: 45.0 + } + calibration { + speed: 1.8 + acceleration: 3.11 + command: 40.0 + } + calibration { + speed: 1.8 + acceleration: 3.12 + command: 80.0 + } + calibration { + speed: 1.8 + acceleration: 3.14 + command: 65.0 + } + calibration { + speed: 1.8 + acceleration: 3.15 + command: 70.0 + } + calibration { + speed: 1.8 + acceleration: 3.18 + command: 55.0 + } + calibration { + speed: 1.8 + acceleration: 3.2 + command: 75.0 + } + calibration { + speed: 1.8 + acceleration: 3.21 + command: 50.0 + } + calibration { + speed: 2.0 + acceleration: -9.6 + command: -35.0 + } + calibration { + speed: 2.0 + acceleration: -7.35 + command: -33.0 + } + calibration { + speed: 2.0 + acceleration: -5.28 + command: -32.0 + } + calibration { + speed: 2.0 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 2.0 + acceleration: -4.09 + command: -30.0 + } + calibration { + speed: 2.0 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 2.0 + acceleration: -2.88 + command: -28.0 + } + calibration { + speed: 2.0 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 2.0 + acceleration: -1.71 + command: -26.0 + } + calibration { + speed: 2.0 + acceleration: -1.22 + command: -25.0 + } + calibration { + speed: 2.0 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 2.0 + acceleration: -0.62 + command: -23.0 + } + calibration { + speed: 2.0 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 2.0 + acceleration: -0.1 + command: -13.0 + } + calibration { + speed: 2.0 + acceleration: -0.09 + command: 5.66666666667 + } + calibration { + speed: 2.0 + acceleration: -0.08 + command: -17.0 + } + calibration { + speed: 2.0 + acceleration: 0.75 + command: 20.0 + } + calibration { + speed: 2.0 + acceleration: 1.85 + command: 25.0 + } + calibration { + speed: 2.0 + acceleration: 2.21 + command: 30.0 + } + calibration { + speed: 2.0 + acceleration: 2.37 + command: 27.0 + } + calibration { + speed: 2.0 + acceleration: 2.46 + command: 60.0 + } + calibration { + speed: 2.0 + acceleration: 3.01 + command: 35.0 + } + calibration { + speed: 2.0 + acceleration: 3.05 + command: 45.0 + } + calibration { + speed: 2.0 + acceleration: 3.09 + command: 65.0 + } + calibration { + speed: 2.0 + acceleration: 3.16 + command: 40.0 + } + calibration { + speed: 2.0 + acceleration: 3.18 + command: 80.0 + } + calibration { + speed: 2.0 + acceleration: 3.2 + command: 70.0 + } + calibration { + speed: 2.0 + acceleration: 3.23 + command: 55.0 + } + calibration { + speed: 2.0 + acceleration: 3.27 + command: 75.0 + } + calibration { + speed: 2.0 + acceleration: 3.28 + command: 50.0 + } + calibration { + speed: 2.2 + acceleration: -9.65 + command: -35.0 + } + calibration { + speed: 2.2 + acceleration: -7.31 + command: -33.0 + } + calibration { + speed: 2.2 + acceleration: -5.37 + command: -32.0 + } + calibration { + speed: 2.2 + acceleration: -4.81 + command: -31.0 + } + calibration { + speed: 2.2 + acceleration: -4.12 + command: -30.0 + } + calibration { + speed: 2.2 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 2.2 + acceleration: -2.85 + command: -28.0 + } + calibration { + speed: 2.2 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 2.2 + acceleration: -1.72 + command: -26.0 + } + calibration { + speed: 2.2 + acceleration: -1.19 + command: -25.0 + } + calibration { + speed: 2.2 + acceleration: -0.89 + command: -24.0 + } + calibration { + speed: 2.2 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 2.2 + acceleration: -0.17 + command: 19.5 + } + calibration { + speed: 2.2 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 2.2 + acceleration: -0.14 + command: 0.0 + } + calibration { + speed: 2.2 + acceleration: -0.13 + command: -17.0 + } + calibration { + speed: 2.2 + acceleration: 0.67 + command: 20.0 + } + calibration { + speed: 2.2 + acceleration: 1.81 + command: 25.0 + } + calibration { + speed: 2.2 + acceleration: 2.22 + command: 30.0 + } + calibration { + speed: 2.2 + acceleration: 2.34 + command: 27.0 + } + calibration { + speed: 2.2 + acceleration: 2.45 + command: 60.0 + } + calibration { + speed: 2.2 + acceleration: 2.95 + command: 65.0 + } + calibration { + speed: 2.2 + acceleration: 3.03 + command: 45.0 + } + calibration { + speed: 2.2 + acceleration: 3.05 + command: 35.0 + } + calibration { + speed: 2.2 + acceleration: 3.19 + command: 55.0 + } + calibration { + speed: 2.2 + acceleration: 3.24 + command: 80.0 + } + calibration { + speed: 2.2 + acceleration: 3.25 + command: 55.0 + } + calibration { + speed: 2.2 + acceleration: 3.3 + command: 75.0 + } + calibration { + speed: 2.2 + acceleration: 3.33 + command: 50.0 + } + calibration { + speed: 2.4 + acceleration: -9.76 + command: -35.0 + } + calibration { + speed: 2.4 + acceleration: -7.33 + command: -33.0 + } + calibration { + speed: 2.4 + acceleration: -5.46 + command: -32.0 + } + calibration { + speed: 2.4 + acceleration: -4.86 + command: -31.0 + } + calibration { + speed: 2.4 + acceleration: -4.12 + command: -30.0 + } + calibration { + speed: 2.4 + acceleration: -3.52 + command: -29.0 + } + calibration { + speed: 2.4 + acceleration: -2.84 + command: -28.0 + } + calibration { + speed: 2.4 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 2.4 + acceleration: -1.74 + command: -26.0 + } + calibration { + speed: 2.4 + acceleration: -1.21 + command: -25.0 + } + calibration { + speed: 2.4 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 2.4 + acceleration: -0.6 + command: -23.0 + } + calibration { + speed: 2.4 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 2.4 + acceleration: -0.15 + command: 6.33333333333 + } + calibration { + speed: 2.4 + acceleration: -0.14 + command: -15.0 + } + calibration { + speed: 2.4 + acceleration: -0.13 + command: -17.0 + } + calibration { + speed: 2.4 + acceleration: 0.56 + command: 20.0 + } + calibration { + speed: 2.4 + acceleration: 1.71 + command: 25.0 + } + calibration { + speed: 2.4 + acceleration: 2.22 + command: 30.0 + } + calibration { + speed: 2.4 + acceleration: 2.27 + command: 27.0 + } + calibration { + speed: 2.4 + acceleration: 2.43 + command: 60.0 + } + calibration { + speed: 2.4 + acceleration: 2.73 + command: 65.0 + } + calibration { + speed: 2.4 + acceleration: 2.98 + command: 45.0 + } + calibration { + speed: 2.4 + acceleration: 3.08 + command: 35.0 + } + calibration { + speed: 2.4 + acceleration: 3.11 + command: 70.0 + } + calibration { + speed: 2.4 + acceleration: 3.2 + command: 40.0 + } + calibration { + speed: 2.4 + acceleration: 3.23 + command: 55.0 + } + calibration { + speed: 2.4 + acceleration: 3.29 + command: 80.0 + } + calibration { + speed: 2.4 + acceleration: 3.3 + command: 75.0 + } + calibration { + speed: 2.4 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 2.6 + acceleration: -9.78 + command: -35.0 + } + calibration { + speed: 2.6 + acceleration: -7.37 + command: -33.0 + } + calibration { + speed: 2.6 + acceleration: -5.52 + command: -32.0 + } + calibration { + speed: 2.6 + acceleration: -4.87 + command: -31.0 + } + calibration { + speed: 2.6 + acceleration: -4.11 + command: -30.0 + } + calibration { + speed: 2.6 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 2.6 + acceleration: -2.86 + command: -28.0 + } + calibration { + speed: 2.6 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 2.6 + acceleration: -1.72 + command: -26.0 + } + calibration { + speed: 2.6 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 2.6 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 2.6 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 2.6 + acceleration: -0.17 + command: 18.5 + } + calibration { + speed: 2.6 + acceleration: -0.16 + command: 17.0 + } + calibration { + speed: 2.6 + acceleration: -0.15 + command: -14.0 + } + calibration { + speed: 2.6 + acceleration: -0.13 + command: -17.0 + } + calibration { + speed: 2.6 + acceleration: 0.49 + command: 20.0 + } + calibration { + speed: 2.6 + acceleration: 1.58 + command: 25.0 + } + calibration { + speed: 2.6 + acceleration: 2.19 + command: 27.0 + } + calibration { + speed: 2.6 + acceleration: 2.22 + command: 30.0 + } + calibration { + speed: 2.6 + acceleration: 2.45 + command: 60.0 + } + calibration { + speed: 2.6 + acceleration: 2.54 + command: 65.0 + } + calibration { + speed: 2.6 + acceleration: 2.9 + command: 45.0 + } + calibration { + speed: 2.6 + acceleration: 3.02 + command: 70.0 + } + calibration { + speed: 2.6 + acceleration: 3.1 + command: 35.0 + } + calibration { + speed: 2.6 + acceleration: 3.16 + command: 55.0 + } + calibration { + speed: 2.6 + acceleration: 3.21 + command: 40.0 + } + calibration { + speed: 2.6 + acceleration: 3.28 + command: 75.0 + } + calibration { + speed: 2.6 + acceleration: 3.34 + command: 80.0 + } + calibration { + speed: 2.6 + acceleration: 3.36 + command: 50.0 + } + calibration { + speed: 2.8 + acceleration: -9.8 + command: -35.0 + } + calibration { + speed: 2.8 + acceleration: -7.47 + command: -33.0 + } + calibration { + speed: 2.8 + acceleration: -5.54 + command: -32.0 + } + calibration { + speed: 2.8 + acceleration: -4.84 + command: -31.0 + } + calibration { + speed: 2.8 + acceleration: -4.09 + command: -30.0 + } + calibration { + speed: 2.8 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 2.8 + acceleration: -2.9 + command: -28.0 + } + calibration { + speed: 2.8 + acceleration: -2.28 + command: -27.0 + } + calibration { + speed: 2.8 + acceleration: -1.74 + command: -26.0 + } + calibration { + speed: 2.8 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 2.8 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 2.8 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 2.8 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 2.8 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 2.8 + acceleration: -0.16 + command: -4.33333333333 + } + calibration { + speed: 2.8 + acceleration: -0.14 + command: -15.0 + } + calibration { + speed: 2.8 + acceleration: 0.43 + command: 20.0 + } + calibration { + speed: 2.8 + acceleration: 1.5 + command: 25.0 + } + calibration { + speed: 2.8 + acceleration: 2.11 + command: 27.0 + } + calibration { + speed: 2.8 + acceleration: 2.22 + command: 30.0 + } + calibration { + speed: 2.8 + acceleration: 2.41 + command: 65.0 + } + calibration { + speed: 2.8 + acceleration: 2.47 + command: 60.0 + } + calibration { + speed: 2.8 + acceleration: 2.81 + command: 45.0 + } + calibration { + speed: 2.8 + acceleration: 2.93 + command: 70.0 + } + calibration { + speed: 2.8 + acceleration: 3.09 + command: 55.0 + } + calibration { + speed: 2.8 + acceleration: 3.12 + command: 35.0 + } + calibration { + speed: 2.8 + acceleration: 3.2 + command: 40.0 + } + calibration { + speed: 2.8 + acceleration: 3.26 + command: 75.0 + } + calibration { + speed: 2.8 + acceleration: 3.36 + command: 50.0 + } + calibration { + speed: 2.8 + acceleration: 3.37 + command: 80.0 + } + calibration { + speed: 3.0 + acceleration: -9.84 + command: -35.0 + } + calibration { + speed: 3.0 + acceleration: -7.54 + command: -33.0 + } + calibration { + speed: 3.0 + acceleration: -5.52 + command: -32.0 + } + calibration { + speed: 3.0 + acceleration: -4.8 + command: -31.0 + } + calibration { + speed: 3.0 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 3.0 + acceleration: -3.58 + command: -29.0 + } + calibration { + speed: 3.0 + acceleration: -2.93 + command: -28.0 + } + calibration { + speed: 3.0 + acceleration: -2.23 + command: -27.0 + } + calibration { + speed: 3.0 + acceleration: -1.83 + command: -26.0 + } + calibration { + speed: 3.0 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 3.0 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 3.0 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 3.0 + acceleration: -0.18 + command: 18.5 + } + calibration { + speed: 3.0 + acceleration: -0.16 + command: -3.66666666667 + } + calibration { + speed: 3.0 + acceleration: -0.14 + command: -17.0 + } + calibration { + speed: 3.0 + acceleration: 0.38 + command: 20.0 + } + calibration { + speed: 3.0 + acceleration: 1.42 + command: 25.0 + } + calibration { + speed: 3.0 + acceleration: 2.02 + command: 27.0 + } + calibration { + speed: 3.0 + acceleration: 2.21 + command: 30.0 + } + calibration { + speed: 3.0 + acceleration: 2.36 + command: 65.0 + } + calibration { + speed: 3.0 + acceleration: 2.47 + command: 60.0 + } + calibration { + speed: 3.0 + acceleration: 2.71 + command: 45.0 + } + calibration { + speed: 3.0 + acceleration: 2.85 + command: 70.0 + } + calibration { + speed: 3.0 + acceleration: 2.99 + command: 55.0 + } + calibration { + speed: 3.0 + acceleration: 3.14 + command: 35.0 + } + calibration { + speed: 3.0 + acceleration: 3.21 + command: 40.0 + } + calibration { + speed: 3.0 + acceleration: 3.23 + command: 75.0 + } + calibration { + speed: 3.0 + acceleration: 3.34 + command: 50.0 + } + calibration { + speed: 3.0 + acceleration: 3.38 + command: 80.0 + } + calibration { + speed: 3.2 + acceleration: -9.86 + command: -35.0 + } + calibration { + speed: 3.2 + acceleration: -7.64 + command: -33.0 + } + calibration { + speed: 3.2 + acceleration: -5.46 + command: -32.0 + } + calibration { + speed: 3.2 + acceleration: -4.75 + command: -31.0 + } + calibration { + speed: 3.2 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 3.2 + acceleration: -3.61 + command: -29.0 + } + calibration { + speed: 3.2 + acceleration: -2.93 + command: -28.0 + } + calibration { + speed: 3.2 + acceleration: -2.21 + command: -27.0 + } + calibration { + speed: 3.2 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 3.2 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 3.2 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 3.2 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 3.2 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 3.2 + acceleration: -0.18 + command: 16.0 + } + calibration { + speed: 3.2 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 3.2 + acceleration: 0.38 + command: 20.0 + } + calibration { + speed: 3.2 + acceleration: 1.35 + command: 25.0 + } + calibration { + speed: 3.2 + acceleration: 1.94 + command: 27.0 + } + calibration { + speed: 3.2 + acceleration: 2.19 + command: 30.0 + } + calibration { + speed: 3.2 + acceleration: 2.38 + command: 65.0 + } + calibration { + speed: 3.2 + acceleration: 2.45 + command: 60.0 + } + calibration { + speed: 3.2 + acceleration: 2.66 + command: 45.0 + } + calibration { + speed: 3.2 + acceleration: 2.83 + command: 70.0 + } + calibration { + speed: 3.2 + acceleration: 2.87 + command: 55.0 + } + calibration { + speed: 3.2 + acceleration: 3.16 + command: 35.0 + } + calibration { + speed: 3.2 + acceleration: 3.18 + command: 75.0 + } + calibration { + speed: 3.2 + acceleration: 3.23 + command: 40.0 + } + calibration { + speed: 3.2 + acceleration: 3.32 + command: 50.0 + } + calibration { + speed: 3.2 + acceleration: 3.35 + command: 80.0 + } + calibration { + speed: 3.4 + acceleration: -9.88 + command: -35.0 + } + calibration { + speed: 3.4 + acceleration: -7.7 + command: -33.0 + } + calibration { + speed: 3.4 + acceleration: -5.41 + command: -32.0 + } + calibration { + speed: 3.4 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 3.4 + acceleration: -4.08 + command: -30.0 + } + calibration { + speed: 3.4 + acceleration: -3.61 + command: -29.0 + } + calibration { + speed: 3.4 + acceleration: -2.91 + command: -28.0 + } + calibration { + speed: 3.4 + acceleration: -2.24 + command: -27.0 + } + calibration { + speed: 3.4 + acceleration: -1.84 + command: -26.0 + } + calibration { + speed: 3.4 + acceleration: -1.28 + command: -25.0 + } + calibration { + speed: 3.4 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 3.4 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 3.4 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 3.4 + acceleration: -0.18 + command: -2.6 + } + calibration { + speed: 3.4 + acceleration: 0.33 + command: 20.0 + } + calibration { + speed: 3.4 + acceleration: 1.29 + command: 25.0 + } + calibration { + speed: 3.4 + acceleration: 1.85 + command: 27.0 + } + calibration { + speed: 3.4 + acceleration: 2.14 + command: 30.0 + } + calibration { + speed: 3.4 + acceleration: 2.44 + command: 60.0 + } + calibration { + speed: 3.4 + acceleration: 2.45 + command: 65.0 + } + calibration { + speed: 3.4 + acceleration: 2.66 + command: 45.0 + } + calibration { + speed: 3.4 + acceleration: 2.76 + command: 55.0 + } + calibration { + speed: 3.4 + acceleration: 2.82 + command: 70.0 + } + calibration { + speed: 3.4 + acceleration: 3.12 + command: 75.0 + } + calibration { + speed: 3.4 + acceleration: 3.16 + command: 35.0 + } + calibration { + speed: 3.4 + acceleration: 3.26 + command: 40.0 + } + calibration { + speed: 3.4 + acceleration: 3.28 + command: 50.0 + } + calibration { + speed: 3.4 + acceleration: 3.29 + command: 80.0 + } + calibration { + speed: 3.6 + acceleration: -9.9 + command: -35.0 + } + calibration { + speed: 3.6 + acceleration: -7.74 + command: -33.0 + } + calibration { + speed: 3.6 + acceleration: -5.36 + command: -32.0 + } + calibration { + speed: 3.6 + acceleration: -4.7 + command: -31.0 + } + calibration { + speed: 3.6 + acceleration: -4.1 + command: -30.0 + } + calibration { + speed: 3.6 + acceleration: -3.58 + command: -29.0 + } + calibration { + speed: 3.6 + acceleration: -2.89 + command: -28.0 + } + calibration { + speed: 3.6 + acceleration: -2.27 + command: -27.0 + } + calibration { + speed: 3.6 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 3.6 + acceleration: -1.29 + command: -25.0 + } + calibration { + speed: 3.6 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 3.6 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 3.6 + acceleration: -0.2 + command: 18.5 + } + calibration { + speed: 3.6 + acceleration: -0.19 + command: 17.0 + } + calibration { + speed: 3.6 + acceleration: -0.17 + command: -13.0 + } + calibration { + speed: 3.6 + acceleration: -0.16 + command: -16.0 + } + calibration { + speed: 3.6 + acceleration: 0.31 + command: 20.0 + } + calibration { + speed: 3.6 + acceleration: 1.19 + command: 25.0 + } + calibration { + speed: 3.6 + acceleration: 1.75 + command: 27.0 + } + calibration { + speed: 3.6 + acceleration: 2.07 + command: 30.0 + } + calibration { + speed: 3.6 + acceleration: 2.44 + command: 60.0 + } + calibration { + speed: 3.6 + acceleration: 2.53 + command: 65.0 + } + calibration { + speed: 3.6 + acceleration: 2.7 + command: 55.0 + } + calibration { + speed: 3.6 + acceleration: 2.75 + command: 45.0 + } + calibration { + speed: 3.6 + acceleration: 2.84 + command: 70.0 + } + calibration { + speed: 3.6 + acceleration: 3.07 + command: 75.0 + } + calibration { + speed: 3.6 + acceleration: 3.14 + command: 35.0 + } + calibration { + speed: 3.6 + acceleration: 3.25 + command: 80.0 + } + calibration { + speed: 3.6 + acceleration: 3.26 + command: 50.0 + } + calibration { + speed: 3.6 + acceleration: 3.29 + command: 40.0 + } + calibration { + speed: 3.8 + acceleration: -9.9 + command: -35.0 + } + calibration { + speed: 3.8 + acceleration: -7.77 + command: -33.0 + } + calibration { + speed: 3.8 + acceleration: -5.33 + command: -32.0 + } + calibration { + speed: 3.8 + acceleration: -4.71 + command: -31.0 + } + calibration { + speed: 3.8 + acceleration: -4.12 + command: -30.0 + } + calibration { + speed: 3.8 + acceleration: -3.54 + command: -29.0 + } + calibration { + speed: 3.8 + acceleration: -2.9 + command: -28.0 + } + calibration { + speed: 3.8 + acceleration: -2.28 + command: -27.0 + } + calibration { + speed: 3.8 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 3.8 + acceleration: -1.29 + command: -25.0 + } + calibration { + speed: 3.8 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 3.8 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 3.8 + acceleration: -0.2 + command: 19.5 + } + calibration { + speed: 3.8 + acceleration: -0.19 + command: 15.0 + } + calibration { + speed: 3.8 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 3.8 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 3.8 + acceleration: 0.31 + command: 20.0 + } + calibration { + speed: 3.8 + acceleration: 1.1 + command: 25.0 + } + calibration { + speed: 3.8 + acceleration: 1.66 + command: 27.0 + } + calibration { + speed: 3.8 + acceleration: 1.99 + command: 30.0 + } + calibration { + speed: 3.8 + acceleration: 2.47 + command: 60.0 + } + calibration { + speed: 3.8 + acceleration: 2.6 + command: 65.0 + } + calibration { + speed: 3.8 + acceleration: 2.74 + command: 55.0 + } + calibration { + speed: 3.8 + acceleration: 2.89 + command: 45.0 + } + calibration { + speed: 3.8 + acceleration: 2.91 + command: 70.0 + } + calibration { + speed: 3.8 + acceleration: 3.05 + command: 75.0 + } + calibration { + speed: 3.8 + acceleration: 3.09 + command: 35.0 + } + calibration { + speed: 3.8 + acceleration: 3.22 + command: 80.0 + } + calibration { + speed: 3.8 + acceleration: 3.26 + command: 50.0 + } + calibration { + speed: 3.8 + acceleration: 3.31 + command: 40.0 + } + calibration { + speed: 4.0 + acceleration: -9.9 + command: -35.0 + } + calibration { + speed: 4.0 + acceleration: -7.78 + command: -33.0 + } + calibration { + speed: 4.0 + acceleration: -5.32 + command: -32.0 + } + calibration { + speed: 4.0 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 4.0 + acceleration: -4.14 + command: -30.0 + } + calibration { + speed: 4.0 + acceleration: -3.51 + command: -29.0 + } + calibration { + speed: 4.0 + acceleration: -2.95 + command: -28.0 + } + calibration { + speed: 4.0 + acceleration: -2.28 + command: -27.0 + } + calibration { + speed: 4.0 + acceleration: -1.87 + command: -26.0 + } + calibration { + speed: 4.0 + acceleration: -1.28 + command: -25.0 + } + calibration { + speed: 4.0 + acceleration: -0.89 + command: -24.0 + } + calibration { + speed: 4.0 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 4.0 + acceleration: -0.21 + command: 17.0 + } + calibration { + speed: 4.0 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 4.0 + acceleration: -0.19 + command: -1.0 + } + calibration { + speed: 4.0 + acceleration: -0.18 + command: -14.0 + } + calibration { + speed: 4.0 + acceleration: 0.28 + command: 20.0 + } + calibration { + speed: 4.0 + acceleration: 1.02 + command: 25.0 + } + calibration { + speed: 4.0 + acceleration: 1.55 + command: 27.0 + } + calibration { + speed: 4.0 + acceleration: 1.9 + command: 30.0 + } + calibration { + speed: 4.0 + acceleration: 2.52 + command: 60.0 + } + calibration { + speed: 4.0 + acceleration: 2.7 + command: 65.0 + } + calibration { + speed: 4.0 + acceleration: 2.86 + command: 55.0 + } + calibration { + speed: 4.0 + acceleration: 2.99 + command: 70.0 + } + calibration { + speed: 4.0 + acceleration: 3.01 + command: 35.0 + } + calibration { + speed: 4.0 + acceleration: 3.03 + command: 45.0 + } + calibration { + speed: 4.0 + acceleration: 3.09 + command: 75.0 + } + calibration { + speed: 4.0 + acceleration: 3.23 + command: 80.0 + } + calibration { + speed: 4.0 + acceleration: 3.29 + command: 50.0 + } + calibration { + speed: 4.0 + acceleration: 3.33 + command: 40.0 + } + calibration { + speed: 4.2 + acceleration: -9.87 + command: -35.0 + } + calibration { + speed: 4.2 + acceleration: -7.79 + command: -33.0 + } + calibration { + speed: 4.2 + acceleration: -5.33 + command: -32.0 + } + calibration { + speed: 4.2 + acceleration: -4.74 + command: -31.0 + } + calibration { + speed: 4.2 + acceleration: -4.14 + command: -30.0 + } + calibration { + speed: 4.2 + acceleration: -3.5 + command: -29.0 + } + calibration { + speed: 4.2 + acceleration: -3.0 + command: -28.0 + } + calibration { + speed: 4.2 + acceleration: -2.28 + command: -27.0 + } + calibration { + speed: 4.2 + acceleration: -1.87 + command: -26.0 + } + calibration { + speed: 4.2 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 4.2 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 4.2 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 4.2 + acceleration: -0.2 + command: 7.33333333333 + } + calibration { + speed: 4.2 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 4.2 + acceleration: -0.17 + command: 0.0 + } + calibration { + speed: 4.2 + acceleration: 0.28 + command: 20.0 + } + calibration { + speed: 4.2 + acceleration: 0.95 + command: 25.0 + } + calibration { + speed: 4.2 + acceleration: 1.43 + command: 27.0 + } + calibration { + speed: 4.2 + acceleration: 1.8 + command: 30.0 + } + calibration { + speed: 4.2 + acceleration: 2.57 + command: 60.0 + } + calibration { + speed: 4.2 + acceleration: 2.78 + command: 65.0 + } + calibration { + speed: 4.2 + acceleration: 2.93 + command: 35.0 + } + calibration { + speed: 4.2 + acceleration: 3.03 + command: 55.0 + } + calibration { + speed: 4.2 + acceleration: 3.12 + command: 70.0 + } + calibration { + speed: 4.2 + acceleration: 3.14 + command: 45.0 + } + calibration { + speed: 4.2 + acceleration: 3.18 + command: 75.0 + } + calibration { + speed: 4.2 + acceleration: 3.29 + command: 80.0 + } + calibration { + speed: 4.2 + acceleration: 3.32 + command: 40.0 + } + calibration { + speed: 4.2 + acceleration: 3.33 + command: 50.0 + } + calibration { + speed: 4.4 + acceleration: -9.86 + command: -35.0 + } + calibration { + speed: 4.4 + acceleration: -7.79 + command: -33.0 + } + calibration { + speed: 4.4 + acceleration: -5.36 + command: -32.0 + } + calibration { + speed: 4.4 + acceleration: -4.75 + command: -31.0 + } + calibration { + speed: 4.4 + acceleration: -4.13 + command: -30.0 + } + calibration { + speed: 4.4 + acceleration: -3.51 + command: -29.0 + } + calibration { + speed: 4.4 + acceleration: -3.04 + command: -28.0 + } + calibration { + speed: 4.4 + acceleration: -2.29 + command: -27.0 + } + calibration { + speed: 4.4 + acceleration: -1.87 + command: -26.0 + } + calibration { + speed: 4.4 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 4.4 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 4.4 + acceleration: -0.58 + command: -23.0 + } + calibration { + speed: 4.4 + acceleration: -0.22 + command: 17.0 + } + calibration { + speed: 4.4 + acceleration: -0.21 + command: 15.0 + } + calibration { + speed: 4.4 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 4.4 + acceleration: -0.19 + command: -17.0 + } + calibration { + speed: 4.4 + acceleration: -0.18 + command: -14.0 + } + calibration { + speed: 4.4 + acceleration: 0.26 + command: 20.0 + } + calibration { + speed: 4.4 + acceleration: 0.86 + command: 25.0 + } + calibration { + speed: 4.4 + acceleration: 1.33 + command: 27.0 + } + calibration { + speed: 4.4 + acceleration: 1.71 + command: 30.0 + } + calibration { + speed: 4.4 + acceleration: 2.62 + command: 60.0 + } + calibration { + speed: 4.4 + acceleration: 2.81 + command: 65.0 + } + calibration { + speed: 4.4 + acceleration: 2.84 + command: 35.0 + } + calibration { + speed: 4.4 + acceleration: 3.19 + command: 70.0 + } + calibration { + speed: 4.4 + acceleration: 3.2 + command: 45.0 + } + calibration { + speed: 4.4 + acceleration: 3.21 + command: 55.0 + } + calibration { + speed: 4.4 + acceleration: 3.27 + command: 75.0 + } + calibration { + speed: 4.4 + acceleration: 3.3 + command: 40.0 + } + calibration { + speed: 4.4 + acceleration: 3.36 + command: 80.0 + } + calibration { + speed: 4.4 + acceleration: 3.39 + command: 50.0 + } + calibration { + speed: 4.6 + acceleration: -9.84 + command: -35.0 + } + calibration { + speed: 4.6 + acceleration: -7.8 + command: -33.0 + } + calibration { + speed: 4.6 + acceleration: -5.39 + command: -32.0 + } + calibration { + speed: 4.6 + acceleration: -4.74 + command: -31.0 + } + calibration { + speed: 4.6 + acceleration: -4.1 + command: -30.0 + } + calibration { + speed: 4.6 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 4.6 + acceleration: -3.04 + command: -28.0 + } + calibration { + speed: 4.6 + acceleration: -2.29 + command: -27.0 + } + calibration { + speed: 4.6 + acceleration: -1.88 + command: -26.0 + } + calibration { + speed: 4.6 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 4.6 + acceleration: -0.89 + command: -24.0 + } + calibration { + speed: 4.6 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 4.6 + acceleration: -0.21 + command: 17.0 + } + calibration { + speed: 4.6 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 4.6 + acceleration: -0.19 + command: -5.0 + } + calibration { + speed: 4.6 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 4.6 + acceleration: 0.19 + command: 20.0 + } + calibration { + speed: 4.6 + acceleration: 0.79 + command: 25.0 + } + calibration { + speed: 4.6 + acceleration: 1.21 + command: 27.0 + } + calibration { + speed: 4.6 + acceleration: 1.58 + command: 30.0 + } + calibration { + speed: 4.6 + acceleration: 2.66 + command: 60.0 + } + calibration { + speed: 4.6 + acceleration: 2.75 + command: 35.0 + } + calibration { + speed: 4.6 + acceleration: 2.81 + command: 65.0 + } + calibration { + speed: 4.6 + acceleration: 3.22 + command: 45.0 + } + calibration { + speed: 4.6 + acceleration: 3.24 + command: 70.0 + } + calibration { + speed: 4.6 + acceleration: 3.26 + command: 40.0 + } + calibration { + speed: 4.6 + acceleration: 3.32 + command: 55.0 + } + calibration { + speed: 4.6 + acceleration: 3.36 + command: 75.0 + } + calibration { + speed: 4.6 + acceleration: 3.44 + command: 65.0 + } + calibration { + speed: 4.8 + acceleration: -9.81 + command: -35.0 + } + calibration { + speed: 4.8 + acceleration: -7.81 + command: -33.0 + } + calibration { + speed: 4.8 + acceleration: -5.41 + command: -32.0 + } + calibration { + speed: 4.8 + acceleration: -4.73 + command: -31.0 + } + calibration { + speed: 4.8 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 4.8 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 4.8 + acceleration: -3.04 + command: -28.0 + } + calibration { + speed: 4.8 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 4.8 + acceleration: -1.89 + command: -26.0 + } + calibration { + speed: 4.8 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 4.8 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 4.8 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 4.8 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 4.8 + acceleration: -0.19 + command: 0.5 + } + calibration { + speed: 4.8 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 4.8 + acceleration: 0.19 + command: 20.0 + } + calibration { + speed: 4.8 + acceleration: 0.73 + command: 25.0 + } + calibration { + speed: 4.8 + acceleration: 1.1 + command: 27.0 + } + calibration { + speed: 4.8 + acceleration: 1.45 + command: 30.0 + } + calibration { + speed: 4.8 + acceleration: 2.66 + command: 35.0 + } + calibration { + speed: 4.8 + acceleration: 2.72 + command: 60.0 + } + calibration { + speed: 4.8 + acceleration: 2.77 + command: 65.0 + } + calibration { + speed: 4.8 + acceleration: 3.21 + command: 45.0 + } + calibration { + speed: 4.8 + acceleration: 3.22 + command: 40.0 + } + calibration { + speed: 4.8 + acceleration: 3.25 + command: 70.0 + } + calibration { + speed: 4.8 + acceleration: 3.4 + command: 55.0 + } + calibration { + speed: 4.8 + acceleration: 3.42 + command: 75.0 + } + calibration { + speed: 4.8 + acceleration: 3.48 + command: 50.0 + } + calibration { + speed: 4.8 + acceleration: 3.51 + command: 80.0 + } + calibration { + speed: 5.0 + acceleration: -9.79 + command: -35.0 + } + calibration { + speed: 5.0 + acceleration: -7.82 + command: -33.0 + } + calibration { + speed: 5.0 + acceleration: -5.42 + command: -32.0 + } + calibration { + speed: 5.0 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 5.0 + acceleration: -4.04 + command: -30.0 + } + calibration { + speed: 5.0 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 5.0 + acceleration: -3.04 + command: -28.0 + } + calibration { + speed: 5.0 + acceleration: -2.29 + command: -27.0 + } + calibration { + speed: 5.0 + acceleration: -1.89 + command: -26.0 + } + calibration { + speed: 5.0 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 5.0 + acceleration: -0.89 + command: -24.0 + } + calibration { + speed: 5.0 + acceleration: -0.6 + command: -23.0 + } + calibration { + speed: 5.0 + acceleration: -0.2 + command: 2.5 + } + calibration { + speed: 5.0 + acceleration: -0.19 + command: 2.0 + } + calibration { + speed: 5.0 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 5.0 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 5.0 + acceleration: 0.18 + command: 20.0 + } + calibration { + speed: 5.0 + acceleration: 0.66 + command: 25.0 + } + calibration { + speed: 5.0 + acceleration: 1.01 + command: 27.0 + } + calibration { + speed: 5.0 + acceleration: 1.34 + command: 30.0 + } + calibration { + speed: 5.0 + acceleration: 2.56 + command: 35.0 + } + calibration { + speed: 5.0 + acceleration: 2.76 + command: 65.0 + } + calibration { + speed: 5.0 + acceleration: 2.77 + command: 60.0 + } + calibration { + speed: 5.0 + acceleration: 3.18 + command: 40.0 + } + calibration { + speed: 5.0 + acceleration: 3.19 + command: 45.0 + } + calibration { + speed: 5.0 + acceleration: 3.25 + command: 70.0 + } + calibration { + speed: 5.0 + acceleration: 3.44 + command: 75.0 + } + calibration { + speed: 5.0 + acceleration: 3.45 + command: 55.0 + } + calibration { + speed: 5.0 + acceleration: 3.5 + command: 50.0 + } + calibration { + speed: 5.0 + acceleration: 3.56 + command: 80.0 + } + calibration { + speed: 5.2 + acceleration: -9.73 + command: -35.0 + } + calibration { + speed: 5.2 + acceleration: -7.86 + command: -33.0 + } + calibration { + speed: 5.2 + acceleration: -5.41 + command: -32.0 + } + calibration { + speed: 5.2 + acceleration: -4.69 + command: -31.0 + } + calibration { + speed: 5.2 + acceleration: -4.03 + command: -30.0 + } + calibration { + speed: 5.2 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 5.2 + acceleration: -3.04 + command: -28.0 + } + calibration { + speed: 5.2 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 5.2 + acceleration: -1.89 + command: -26.0 + } + calibration { + speed: 5.2 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 5.2 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 5.2 + acceleration: -0.6 + command: -23.0 + } + calibration { + speed: 5.2 + acceleration: -0.24 + command: 16.0 + } + calibration { + speed: 5.2 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 5.2 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 5.2 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 5.2 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 5.2 + acceleration: 0.16 + command: 20.0 + } + calibration { + speed: 5.2 + acceleration: 0.62 + command: 25.0 + } + calibration { + speed: 5.2 + acceleration: 0.94 + command: 27.0 + } + calibration { + speed: 5.2 + acceleration: 1.26 + command: 30.0 + } + calibration { + speed: 5.2 + acceleration: 2.47 + command: 35.0 + } + calibration { + speed: 5.2 + acceleration: 2.81 + command: 62.5 + } + calibration { + speed: 5.2 + acceleration: 3.13 + command: 40.0 + } + calibration { + speed: 5.2 + acceleration: 3.17 + command: 45.0 + } + calibration { + speed: 5.2 + acceleration: 3.25 + command: 70.0 + } + calibration { + speed: 5.2 + acceleration: 3.44 + command: 75.0 + } + calibration { + speed: 5.2 + acceleration: 3.47 + command: 55.0 + } + calibration { + speed: 5.2 + acceleration: 3.5 + command: 50.0 + } + calibration { + speed: 5.2 + acceleration: 3.58 + command: 80.0 + } + calibration { + speed: 5.4 + acceleration: -9.67 + command: -35.0 + } + calibration { + speed: 5.4 + acceleration: -7.89 + command: -33.0 + } + calibration { + speed: 5.4 + acceleration: -5.39 + command: -32.0 + } + calibration { + speed: 5.4 + acceleration: -4.68 + command: -31.0 + } + calibration { + speed: 5.4 + acceleration: -4.04 + command: -30.0 + } + calibration { + speed: 5.4 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 5.4 + acceleration: -3.03 + command: -28.0 + } + calibration { + speed: 5.4 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 5.4 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 5.4 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 5.4 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 5.4 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 5.4 + acceleration: -0.23 + command: 17.0 + } + calibration { + speed: 5.4 + acceleration: -0.21 + command: -1.0 + } + calibration { + speed: 5.4 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 5.4 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 5.4 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 5.4 + acceleration: 0.16 + command: 20.0 + } + calibration { + speed: 5.4 + acceleration: 0.59 + command: 25.0 + } + calibration { + speed: 5.4 + acceleration: 0.89 + command: 27.0 + } + calibration { + speed: 5.4 + acceleration: 1.19 + command: 30.0 + } + calibration { + speed: 5.4 + acceleration: 2.38 + command: 35.0 + } + calibration { + speed: 5.4 + acceleration: 2.84 + command: 60.0 + } + calibration { + speed: 5.4 + acceleration: 2.88 + command: 65.0 + } + calibration { + speed: 5.4 + acceleration: 3.07 + command: 40.0 + } + calibration { + speed: 5.4 + acceleration: 3.16 + command: 45.0 + } + calibration { + speed: 5.4 + acceleration: 3.27 + command: 70.0 + } + calibration { + speed: 5.4 + acceleration: 3.44 + command: 75.0 + } + calibration { + speed: 5.4 + acceleration: 3.47 + command: 55.0 + } + calibration { + speed: 5.4 + acceleration: 3.48 + command: 50.0 + } + calibration { + speed: 5.4 + acceleration: 3.59 + command: 80.0 + } + calibration { + speed: 5.6 + acceleration: -9.65 + command: -35.0 + } + calibration { + speed: 5.6 + acceleration: -7.94 + command: -33.0 + } + calibration { + speed: 5.6 + acceleration: -5.35 + command: -32.0 + } + calibration { + speed: 5.6 + acceleration: -4.67 + command: -31.0 + } + calibration { + speed: 5.6 + acceleration: -4.05 + command: -30.0 + } + calibration { + speed: 5.6 + acceleration: -3.54 + command: -29.0 + } + calibration { + speed: 5.6 + acceleration: -3.02 + command: -28.0 + } + calibration { + speed: 5.6 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 5.6 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 5.6 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 5.6 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 5.6 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 5.6 + acceleration: -0.23 + command: 16.0 + } + calibration { + speed: 5.6 + acceleration: -0.22 + command: -17.0 + } + calibration { + speed: 5.6 + acceleration: -0.2 + command: 4.5 + } + calibration { + speed: 5.6 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 5.6 + acceleration: 0.15 + command: 20.0 + } + calibration { + speed: 5.6 + acceleration: 0.56 + command: 25.0 + } + calibration { + speed: 5.6 + acceleration: 0.85 + command: 27.0 + } + calibration { + speed: 5.6 + acceleration: 1.13 + command: 30.0 + } + calibration { + speed: 5.6 + acceleration: 2.3 + command: 35.0 + } + calibration { + speed: 5.6 + acceleration: 2.85 + command: 60.0 + } + calibration { + speed: 5.6 + acceleration: 2.95 + command: 65.0 + } + calibration { + speed: 5.6 + acceleration: 3.01 + command: 40.0 + } + calibration { + speed: 5.6 + acceleration: 3.15 + command: 45.0 + } + calibration { + speed: 5.6 + acceleration: 3.29 + command: 70.0 + } + calibration { + speed: 5.6 + acceleration: 3.43 + command: 50.0 + } + calibration { + speed: 5.6 + acceleration: 3.45 + command: 75.0 + } + calibration { + speed: 5.6 + acceleration: 3.46 + command: 55.0 + } + calibration { + speed: 5.6 + acceleration: 3.59 + command: 80.0 + } + calibration { + speed: 5.8 + acceleration: -9.6 + command: -35.0 + } + calibration { + speed: 5.8 + acceleration: -7.97 + command: -33.0 + } + calibration { + speed: 5.8 + acceleration: -5.32 + command: -32.0 + } + calibration { + speed: 5.8 + acceleration: -4.67 + command: -31.0 + } + calibration { + speed: 5.8 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 5.8 + acceleration: -3.54 + command: -29.0 + } + calibration { + speed: 5.8 + acceleration: -3.01 + command: -28.0 + } + calibration { + speed: 5.8 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 5.8 + acceleration: -1.89 + command: -26.0 + } + calibration { + speed: 5.8 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 5.8 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 5.8 + acceleration: -0.6 + command: -23.0 + } + calibration { + speed: 5.8 + acceleration: -0.24 + command: 15.0 + } + calibration { + speed: 5.8 + acceleration: -0.21 + command: 17.0 + } + calibration { + speed: 5.8 + acceleration: -0.2 + command: 2.5 + } + calibration { + speed: 5.8 + acceleration: -0.19 + command: -15.0 + } + calibration { + speed: 5.8 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 5.8 + acceleration: 0.14 + command: 20.0 + } + calibration { + speed: 5.8 + acceleration: 0.55 + command: 25.0 + } + calibration { + speed: 5.8 + acceleration: 0.82 + command: 27.0 + } + calibration { + speed: 5.8 + acceleration: 1.07 + command: 30.0 + } + calibration { + speed: 5.8 + acceleration: 2.22 + command: 35.0 + } + calibration { + speed: 5.8 + acceleration: 2.85 + command: 60.0 + } + calibration { + speed: 5.8 + acceleration: 2.94 + command: 40.0 + } + calibration { + speed: 5.8 + acceleration: 2.97 + command: 65.0 + } + calibration { + speed: 5.8 + acceleration: 3.14 + command: 45.0 + } + calibration { + speed: 5.8 + acceleration: 3.32 + command: 70.0 + } + calibration { + speed: 5.8 + acceleration: 3.38 + command: 50.0 + } + calibration { + speed: 5.8 + acceleration: 3.44 + command: 55.0 + } + calibration { + speed: 5.8 + acceleration: 3.46 + command: 75.0 + } + calibration { + speed: 5.8 + acceleration: 3.57 + command: 80.0 + } + calibration { + speed: 6.0 + acceleration: -9.58 + command: -35.0 + } + calibration { + speed: 6.0 + acceleration: -8.0 + command: -33.0 + } + calibration { + speed: 6.0 + acceleration: -5.29 + command: -32.0 + } + calibration { + speed: 6.0 + acceleration: -4.68 + command: -31.0 + } + calibration { + speed: 6.0 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 6.0 + acceleration: -3.54 + command: -29.0 + } + calibration { + speed: 6.0 + acceleration: -3.0 + command: -28.0 + } + calibration { + speed: 6.0 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 6.0 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 6.0 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 6.0 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.0 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 6.0 + acceleration: -0.23 + command: 17.0 + } + calibration { + speed: 6.0 + acceleration: -0.22 + command: -17.0 + } + calibration { + speed: 6.0 + acceleration: -0.2 + command: 18.5 + } + calibration { + speed: 6.0 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 6.0 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 6.0 + acceleration: 0.13 + command: 20.0 + } + calibration { + speed: 6.0 + acceleration: 0.53 + command: 25.0 + } + calibration { + speed: 6.0 + acceleration: 0.78 + command: 27.0 + } + calibration { + speed: 6.0 + acceleration: 1.03 + command: 30.0 + } + calibration { + speed: 6.0 + acceleration: 2.15 + command: 35.0 + } + calibration { + speed: 6.0 + acceleration: 2.84 + command: 60.0 + } + calibration { + speed: 6.0 + acceleration: 2.87 + command: 40.0 + } + calibration { + speed: 6.0 + acceleration: 2.97 + command: 65.0 + } + calibration { + speed: 6.0 + acceleration: 3.11 + command: 45.0 + } + calibration { + speed: 6.0 + acceleration: 3.33 + command: 50.0 + } + calibration { + speed: 6.0 + acceleration: 3.34 + command: 70.0 + } + calibration { + speed: 6.0 + acceleration: 3.41 + command: 55.0 + } + calibration { + speed: 6.0 + acceleration: 3.47 + command: 75.0 + } + calibration { + speed: 6.0 + acceleration: 3.57 + command: 80.0 + } + calibration { + speed: 6.2 + acceleration: -9.52 + command: -35.0 + } + calibration { + speed: 6.2 + acceleration: -8.01 + command: -33.0 + } + calibration { + speed: 6.2 + acceleration: -5.28 + command: -32.0 + } + calibration { + speed: 6.2 + acceleration: -4.69 + command: -31.0 + } + calibration { + speed: 6.2 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 6.2 + acceleration: -3.54 + command: -29.0 + } + calibration { + speed: 6.2 + acceleration: -2.99 + command: -28.0 + } + calibration { + speed: 6.2 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 6.2 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 6.2 + acceleration: -1.33 + command: -25.0 + } + calibration { + speed: 6.2 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 6.2 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 6.2 + acceleration: -0.25 + command: 17.0 + } + calibration { + speed: 6.2 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 6.2 + acceleration: -0.2 + command: 4.5 + } + calibration { + speed: 6.2 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 6.2 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 6.2 + acceleration: 0.11 + command: 20.0 + } + calibration { + speed: 6.2 + acceleration: 0.51 + command: 25.0 + } + calibration { + speed: 6.2 + acceleration: 0.77 + command: 27.0 + } + calibration { + speed: 6.2 + acceleration: 0.98 + command: 30.0 + } + calibration { + speed: 6.2 + acceleration: 2.08 + command: 35.0 + } + calibration { + speed: 6.2 + acceleration: 2.81 + command: 40.0 + } + calibration { + speed: 6.2 + acceleration: 2.83 + command: 60.0 + } + calibration { + speed: 6.2 + acceleration: 2.95 + command: 65.0 + } + calibration { + speed: 6.2 + acceleration: 3.06 + command: 45.0 + } + calibration { + speed: 6.2 + acceleration: 3.27 + command: 50.0 + } + calibration { + speed: 6.2 + acceleration: 3.33 + command: 70.0 + } + calibration { + speed: 6.2 + acceleration: 3.37 + command: 55.0 + } + calibration { + speed: 6.2 + acceleration: 3.47 + command: 75.0 + } + calibration { + speed: 6.2 + acceleration: 3.57 + command: 80.0 + } + calibration { + speed: 6.4 + acceleration: -9.5 + command: -35.0 + } + calibration { + speed: 6.4 + acceleration: -8.01 + command: -33.0 + } + calibration { + speed: 6.4 + acceleration: -5.27 + command: -32.0 + } + calibration { + speed: 6.4 + acceleration: -4.7 + command: -31.0 + } + calibration { + speed: 6.4 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 6.4 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 6.4 + acceleration: -2.99 + command: -28.0 + } + calibration { + speed: 6.4 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 6.4 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 6.4 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 6.4 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 6.4 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 6.4 + acceleration: -0.22 + command: 17.0 + } + calibration { + speed: 6.4 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 6.4 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 6.4 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 6.4 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 6.4 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 6.4 + acceleration: 0.1 + command: 20.0 + } + calibration { + speed: 6.4 + acceleration: 0.48 + command: 25.0 + } + calibration { + speed: 6.4 + acceleration: 0.72 + command: 27.0 + } + calibration { + speed: 6.4 + acceleration: 0.95 + command: 30.0 + } + calibration { + speed: 6.4 + acceleration: 2.02 + command: 35.0 + } + calibration { + speed: 6.4 + acceleration: 2.75 + command: 40.0 + } + calibration { + speed: 6.4 + acceleration: 2.82 + command: 60.0 + } + calibration { + speed: 6.4 + acceleration: 2.94 + command: 65.0 + } + calibration { + speed: 6.4 + acceleration: 2.99 + command: 45.0 + } + calibration { + speed: 6.4 + acceleration: 3.22 + command: 50.0 + } + calibration { + speed: 6.4 + acceleration: 3.31 + command: 70.0 + } + calibration { + speed: 6.4 + acceleration: 3.33 + command: 55.0 + } + calibration { + speed: 6.4 + acceleration: 3.47 + command: 75.0 + } + calibration { + speed: 6.4 + acceleration: 3.56 + command: 80.0 + } + calibration { + speed: 6.6 + acceleration: -9.48 + command: -35.0 + } + calibration { + speed: 6.6 + acceleration: -7.99 + command: -33.0 + } + calibration { + speed: 6.6 + acceleration: -5.27 + command: -32.0 + } + calibration { + speed: 6.6 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 6.6 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 6.6 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 6.6 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 6.6 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 6.6 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 6.6 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 6.6 + acceleration: -0.92 + command: -24.0 + } + calibration { + speed: 6.6 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 6.6 + acceleration: -0.23 + command: 17.0 + } + calibration { + speed: 6.6 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 6.6 + acceleration: -0.2 + command: 4.5 + } + calibration { + speed: 6.6 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 6.6 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 6.6 + acceleration: 0.1 + command: 20.0 + } + calibration { + speed: 6.6 + acceleration: 0.46 + command: 25.0 + } + calibration { + speed: 6.6 + acceleration: 0.72 + command: 27.0 + } + calibration { + speed: 6.6 + acceleration: 0.92 + command: 30.0 + } + calibration { + speed: 6.6 + acceleration: 1.95 + command: 35.0 + } + calibration { + speed: 6.6 + acceleration: 2.69 + command: 40.0 + } + calibration { + speed: 6.6 + acceleration: 2.81 + command: 60.0 + } + calibration { + speed: 6.6 + acceleration: 2.93 + command: 45.0 + } + calibration { + speed: 6.6 + acceleration: 2.94 + command: 65.0 + } + calibration { + speed: 6.6 + acceleration: 3.17 + command: 50.0 + } + calibration { + speed: 6.6 + acceleration: 3.28 + command: 62.5 + } + calibration { + speed: 6.6 + acceleration: 3.45 + command: 75.0 + } + calibration { + speed: 6.6 + acceleration: 3.56 + command: 80.0 + } + calibration { + speed: 6.8 + acceleration: -9.48 + command: -35.0 + } + calibration { + speed: 6.8 + acceleration: -7.94 + command: -33.0 + } + calibration { + speed: 6.8 + acceleration: -5.26 + command: -32.0 + } + calibration { + speed: 6.8 + acceleration: -4.73 + command: -31.0 + } + calibration { + speed: 6.8 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 6.8 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 6.8 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 6.8 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 6.8 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 6.8 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 6.8 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.8 + acceleration: -0.63 + command: -23.0 + } + calibration { + speed: 6.8 + acceleration: -0.25 + command: 17.0 + } + calibration { + speed: 6.8 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 6.8 + acceleration: -0.2 + command: 4.5 + } + calibration { + speed: 6.8 + acceleration: -0.19 + command: -15.0 + } + calibration { + speed: 6.8 + acceleration: -0.17 + command: 15.0 + } + calibration { + speed: 6.8 + acceleration: 0.06 + command: 20.0 + } + calibration { + speed: 6.8 + acceleration: 0.43 + command: 25.0 + } + calibration { + speed: 6.8 + acceleration: 0.69 + command: 27.0 + } + calibration { + speed: 6.8 + acceleration: 0.9 + command: 30.0 + } + calibration { + speed: 6.8 + acceleration: 1.89 + command: 35.0 + } + calibration { + speed: 6.8 + acceleration: 2.62 + command: 40.0 + } + calibration { + speed: 6.8 + acceleration: 2.79 + command: 60.0 + } + calibration { + speed: 6.8 + acceleration: 2.87 + command: 45.0 + } + calibration { + speed: 6.8 + acceleration: 2.95 + command: 65.0 + } + calibration { + speed: 6.8 + acceleration: 3.13 + command: 50.0 + } + calibration { + speed: 6.8 + acceleration: 3.23 + command: 55.0 + } + calibration { + speed: 6.8 + acceleration: 3.26 + command: 70.0 + } + calibration { + speed: 6.8 + acceleration: 3.43 + command: 75.0 + } + calibration { + speed: 6.8 + acceleration: 3.56 + command: 80.0 + } + calibration { + speed: 7.0 + acceleration: -9.51 + command: -35.0 + } + calibration { + speed: 7.0 + acceleration: -7.88 + command: -33.0 + } + calibration { + speed: 7.0 + acceleration: -5.24 + command: -32.0 + } + calibration { + speed: 7.0 + acceleration: -4.73 + command: -31.0 + } + calibration { + speed: 7.0 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 7.0 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 7.0 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 7.0 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 7.0 + acceleration: -1.91 + command: -26.0 + } + calibration { + speed: 7.0 + acceleration: -1.36 + command: -25.0 + } + calibration { + speed: 7.0 + acceleration: -0.93 + command: -24.0 + } + calibration { + speed: 7.0 + acceleration: -0.62 + command: -23.0 + } + calibration { + speed: 7.0 + acceleration: -0.24 + command: 17.0 + } + calibration { + speed: 7.0 + acceleration: -0.21 + command: -15.0 + } + calibration { + speed: 7.0 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 7.0 + acceleration: -0.19 + command: -15.0 + } + calibration { + speed: 7.0 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 7.0 + acceleration: 0.07 + command: 20.0 + } + calibration { + speed: 7.0 + acceleration: 0.42 + command: 25.0 + } + calibration { + speed: 7.0 + acceleration: 0.66 + command: 27.0 + } + calibration { + speed: 7.0 + acceleration: 0.87 + command: 30.0 + } + calibration { + speed: 7.0 + acceleration: 1.83 + command: 35.0 + } + calibration { + speed: 7.0 + acceleration: 2.55 + command: 40.0 + } + calibration { + speed: 7.0 + acceleration: 2.77 + command: 60.0 + } + calibration { + speed: 7.0 + acceleration: 2.81 + command: 45.0 + } + calibration { + speed: 7.0 + acceleration: 2.93 + command: 65.0 + } + calibration { + speed: 7.0 + acceleration: 3.07 + command: 50.0 + } + calibration { + speed: 7.0 + acceleration: 3.18 + command: 55.0 + } + calibration { + speed: 7.0 + acceleration: 3.24 + command: 70.0 + } + calibration { + speed: 7.0 + acceleration: 3.41 + command: 75.0 + } + calibration { + speed: 7.0 + acceleration: 3.56 + command: 80.0 + } + calibration { + speed: 7.2 + acceleration: -9.53 + command: -35.0 + } + calibration { + speed: 7.2 + acceleration: -7.83 + command: -33.0 + } + calibration { + speed: 7.2 + acceleration: -5.22 + command: -32.0 + } + calibration { + speed: 7.2 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 7.2 + acceleration: -4.09 + command: -30.0 + } + calibration { + speed: 7.2 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 7.2 + acceleration: -2.99 + command: -28.0 + } + calibration { + speed: 7.2 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 7.2 + acceleration: -1.91 + command: -26.0 + } + calibration { + speed: 7.2 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 7.2 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 7.2 + acceleration: -0.64 + command: -23.0 + } + calibration { + speed: 7.2 + acceleration: -0.25 + command: 17.0 + } + calibration { + speed: 7.2 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 7.2 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 7.2 + acceleration: -0.19 + command: -14.0 + } + calibration { + speed: 7.2 + acceleration: -0.17 + command: 15.0 + } + calibration { + speed: 7.2 + acceleration: 0.04 + command: 20.0 + } + calibration { + speed: 7.2 + acceleration: 0.43 + command: 25.0 + } + calibration { + speed: 7.2 + acceleration: 0.65 + command: 27.0 + } + calibration { + speed: 7.2 + acceleration: 0.84 + command: 30.0 + } + calibration { + speed: 7.2 + acceleration: 1.76 + command: 35.0 + } + calibration { + speed: 7.2 + acceleration: 2.47 + command: 40.0 + } + calibration { + speed: 7.2 + acceleration: 2.75 + command: 60.0 + } + calibration { + speed: 7.2 + acceleration: 2.77 + command: 45.0 + } + calibration { + speed: 7.2 + acceleration: 2.9 + command: 65.0 + } + calibration { + speed: 7.2 + acceleration: 3.01 + command: 50.0 + } + calibration { + speed: 7.2 + acceleration: 3.13 + command: 55.0 + } + calibration { + speed: 7.2 + acceleration: 3.24 + command: 70.0 + } + calibration { + speed: 7.2 + acceleration: 3.39 + command: 75.0 + } + calibration { + speed: 7.2 + acceleration: 3.56 + command: 80.0 + } + calibration { + speed: 7.4 + acceleration: -9.6 + command: -35.0 + } + calibration { + speed: 7.4 + acceleration: -7.83 + command: -33.0 + } + calibration { + speed: 7.4 + acceleration: -5.2 + command: -32.0 + } + calibration { + speed: 7.4 + acceleration: -4.7 + command: -31.0 + } + calibration { + speed: 7.4 + acceleration: -4.1 + command: -30.0 + } + calibration { + speed: 7.4 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 7.4 + acceleration: -2.99 + command: -28.0 + } + calibration { + speed: 7.4 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 7.4 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 7.4 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 7.4 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 7.4 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 7.4 + acceleration: -0.26 + command: 17.0 + } + calibration { + speed: 7.4 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 7.4 + acceleration: -0.21 + command: -14.0 + } + calibration { + speed: 7.4 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 7.4 + acceleration: -0.17 + command: 15.0 + } + calibration { + speed: 7.4 + acceleration: 0.04 + command: 20.0 + } + calibration { + speed: 7.4 + acceleration: 0.41 + command: 25.0 + } + calibration { + speed: 7.4 + acceleration: 0.63 + command: 27.0 + } + calibration { + speed: 7.4 + acceleration: 0.82 + command: 30.0 + } + calibration { + speed: 7.4 + acceleration: 1.7 + command: 35.0 + } + calibration { + speed: 7.4 + acceleration: 2.4 + command: 40.0 + } + calibration { + speed: 7.4 + acceleration: 2.72 + command: 52.5 + } + calibration { + speed: 7.4 + acceleration: 2.87 + command: 65.0 + } + calibration { + speed: 7.4 + acceleration: 2.95 + command: 50.0 + } + calibration { + speed: 7.4 + acceleration: 3.08 + command: 55.0 + } + calibration { + speed: 7.4 + acceleration: 3.23 + command: 70.0 + } + calibration { + speed: 7.4 + acceleration: 3.37 + command: 75.0 + } + calibration { + speed: 7.4 + acceleration: 3.56 + command: 80.0 + } + calibration { + speed: 7.6 + acceleration: -9.57 + command: -35.0 + } + calibration { + speed: 7.6 + acceleration: -7.87 + command: -33.0 + } + calibration { + speed: 7.6 + acceleration: -5.19 + command: -32.0 + } + calibration { + speed: 7.6 + acceleration: -4.67 + command: -31.0 + } + calibration { + speed: 7.6 + acceleration: -4.12 + command: -30.0 + } + calibration { + speed: 7.6 + acceleration: -3.52 + command: -29.0 + } + calibration { + speed: 7.6 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 7.6 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 7.6 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 7.6 + acceleration: -1.36 + command: -25.0 + } + calibration { + speed: 7.6 + acceleration: -0.95 + command: -24.0 + } + calibration { + speed: 7.6 + acceleration: -0.63 + command: -23.0 + } + calibration { + speed: 7.6 + acceleration: -0.23 + command: 17.0 + } + calibration { + speed: 7.6 + acceleration: -0.22 + command: -17.0 + } + calibration { + speed: 7.6 + acceleration: -0.21 + command: -13.0 + } + calibration { + speed: 7.6 + acceleration: -0.2 + command: -15.0 + } + calibration { + speed: 7.6 + acceleration: -0.17 + command: 15.0 + } + calibration { + speed: 7.6 + acceleration: -0.11 + command: 22.0 + } + calibration { + speed: 7.6 + acceleration: 0.02 + command: 20.0 + } + calibration { + speed: 7.6 + acceleration: 0.36 + command: 25.0 + } + calibration { + speed: 7.6 + acceleration: 0.63 + command: 27.0 + } + calibration { + speed: 7.6 + acceleration: 0.79 + command: 30.0 + } + calibration { + speed: 7.6 + acceleration: 1.63 + command: 35.0 + } + calibration { + speed: 7.6 + acceleration: 2.34 + command: 40.0 + } + calibration { + speed: 7.6 + acceleration: 2.66 + command: 45.0 + } + calibration { + speed: 7.6 + acceleration: 2.7 + command: 60.0 + } + calibration { + speed: 7.6 + acceleration: 2.83 + command: 65.0 + } + calibration { + speed: 7.6 + acceleration: 2.89 + command: 50.0 + } + calibration { + speed: 7.6 + acceleration: 3.03 + command: 55.0 + } + calibration { + speed: 7.6 + acceleration: 3.23 + command: 70.0 + } + calibration { + speed: 7.6 + acceleration: 3.36 + command: 75.0 + } + calibration { + speed: 7.6 + acceleration: 3.55 + command: 80.0 + } + calibration { + speed: 7.8 + acceleration: -9.48 + command: -35.0 + } + calibration { + speed: 7.8 + acceleration: -7.92 + command: -33.0 + } + calibration { + speed: 7.8 + acceleration: -5.2 + command: -32.0 + } + calibration { + speed: 7.8 + acceleration: -4.65 + command: -31.0 + } + calibration { + speed: 7.8 + acceleration: -4.12 + command: -30.0 + } + calibration { + speed: 7.8 + acceleration: -3.52 + command: -29.0 + } + calibration { + speed: 7.8 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 7.8 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 7.8 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 7.8 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 7.8 + acceleration: -0.95 + command: -24.0 + } + calibration { + speed: 7.8 + acceleration: -0.64 + command: -23.0 + } + calibration { + speed: 7.8 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 7.8 + acceleration: -0.23 + command: 17.0 + } + calibration { + speed: 7.8 + acceleration: -0.2 + command: -14.0 + } + calibration { + speed: 7.8 + acceleration: -0.17 + command: 15.0 + } + calibration { + speed: 7.8 + acceleration: 0.01 + command: 20.0 + } + calibration { + speed: 7.8 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 7.8 + acceleration: 0.37 + command: 25.0 + } + calibration { + speed: 7.8 + acceleration: 0.6 + command: 27.0 + } + calibration { + speed: 7.8 + acceleration: 0.78 + command: 30.0 + } + calibration { + speed: 7.8 + acceleration: 1.58 + command: 35.0 + } + calibration { + speed: 7.8 + acceleration: 2.27 + command: 40.0 + } + calibration { + speed: 7.8 + acceleration: 2.6 + command: 45.0 + } + calibration { + speed: 7.8 + acceleration: 2.67 + command: 60.0 + } + calibration { + speed: 7.8 + acceleration: 2.81 + command: 65.0 + } + calibration { + speed: 7.8 + acceleration: 2.83 + command: 50.0 + } + calibration { + speed: 7.8 + acceleration: 2.98 + command: 55.0 + } + calibration { + speed: 7.8 + acceleration: 3.23 + command: 70.0 + } + calibration { + speed: 7.8 + acceleration: 3.36 + command: 75.0 + } + calibration { + speed: 7.8 + acceleration: 3.55 + command: 80.0 + } + calibration { + speed: 8.0 + acceleration: -9.46 + command: -35.0 + } + calibration { + speed: 8.0 + acceleration: -7.98 + command: -33.0 + } + calibration { + speed: 8.0 + acceleration: -5.23 + command: -32.0 + } + calibration { + speed: 8.0 + acceleration: -4.62 + command: -31.0 + } + calibration { + speed: 8.0 + acceleration: -4.12 + command: -30.0 + } + calibration { + speed: 8.0 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 8.0 + acceleration: -2.97 + command: -28.0 + } + calibration { + speed: 8.0 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 8.0 + acceleration: -1.89 + command: -26.0 + } + calibration { + speed: 8.0 + acceleration: -1.36 + command: -25.0 + } + calibration { + speed: 8.0 + acceleration: -0.95 + command: -24.0 + } + calibration { + speed: 8.0 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 8.0 + acceleration: -0.26 + command: 17.0 + } + calibration { + speed: 8.0 + acceleration: -0.24 + command: -1.0 + } + calibration { + speed: 8.0 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 8.0 + acceleration: -0.21 + command: -13.0 + } + calibration { + speed: 8.0 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 8.0 + acceleration: 0.35 + command: 25.0 + } + calibration { + speed: 8.0 + acceleration: 0.58 + command: 27.0 + } + calibration { + speed: 8.0 + acceleration: 0.74 + command: 30.0 + } + calibration { + speed: 8.0 + acceleration: 1.54 + command: 35.0 + } + calibration { + speed: 8.0 + acceleration: 2.21 + command: 40.0 + } + calibration { + speed: 8.0 + acceleration: 2.56 + command: 45.0 + } + calibration { + speed: 8.0 + acceleration: 2.65 + command: 60.0 + } + calibration { + speed: 8.0 + acceleration: 2.77 + command: 50.0 + } + calibration { + speed: 8.0 + acceleration: 2.81 + command: 65.0 + } + calibration { + speed: 8.0 + acceleration: 2.91 + command: 55.0 + } + calibration { + speed: 8.0 + acceleration: 3.22 + command: 70.0 + } + calibration { + speed: 8.0 + acceleration: 3.35 + command: 75.0 + } + calibration { + speed: 8.0 + acceleration: 3.55 + command: 80.0 + } + calibration { + speed: 8.2 + acceleration: -9.37 + command: -35.0 + } + calibration { + speed: 8.2 + acceleration: -8.07 + command: -33.0 + } + calibration { + speed: 8.2 + acceleration: -5.27 + command: -32.0 + } + calibration { + speed: 8.2 + acceleration: -4.62 + command: -31.0 + } + calibration { + speed: 8.2 + acceleration: -4.1 + command: -30.0 + } + calibration { + speed: 8.2 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 8.2 + acceleration: -2.97 + command: -28.0 + } + calibration { + speed: 8.2 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 8.2 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 8.2 + acceleration: -1.39 + command: -25.0 + } + calibration { + speed: 8.2 + acceleration: -0.95 + command: -24.0 + } + calibration { + speed: 8.2 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 8.2 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 8.2 + acceleration: -0.23 + command: 16.0 + } + calibration { + speed: 8.2 + acceleration: -0.22 + command: -14.0 + } + calibration { + speed: 8.2 + acceleration: -0.06 + command: 20.0 + } + calibration { + speed: 8.2 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 8.2 + acceleration: 0.35 + command: 25.0 + } + calibration { + speed: 8.2 + acceleration: 0.56 + command: 27.0 + } + calibration { + speed: 8.2 + acceleration: 0.72 + command: 30.0 + } + calibration { + speed: 8.2 + acceleration: 1.49 + command: 35.0 + } + calibration { + speed: 8.2 + acceleration: 2.15 + command: 40.0 + } + calibration { + speed: 8.2 + acceleration: 2.51 + command: 45.0 + } + calibration { + speed: 8.2 + acceleration: 2.62 + command: 60.0 + } + calibration { + speed: 8.2 + acceleration: 2.71 + command: 50.0 + } + calibration { + speed: 8.2 + acceleration: 2.82 + command: 65.0 + } + calibration { + speed: 8.2 + acceleration: 2.85 + command: 55.0 + } + calibration { + speed: 8.2 + acceleration: 3.2 + command: 70.0 + } + calibration { + speed: 8.2 + acceleration: 3.35 + command: 75.0 + } + calibration { + speed: 8.2 + acceleration: 3.54 + command: 80.0 + } + calibration { + speed: 8.4 + acceleration: -9.33 + command: -35.0 + } + calibration { + speed: 8.4 + acceleration: -8.18 + command: -33.0 + } + calibration { + speed: 8.4 + acceleration: -5.31 + command: -32.0 + } + calibration { + speed: 8.4 + acceleration: -4.65 + command: -31.0 + } + calibration { + speed: 8.4 + acceleration: -4.08 + command: -30.0 + } + calibration { + speed: 8.4 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 8.4 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 8.4 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 8.4 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 8.4 + acceleration: -1.37 + command: -25.0 + } + calibration { + speed: 8.4 + acceleration: -0.96 + command: -24.0 + } + calibration { + speed: 8.4 + acceleration: -0.66 + command: -23.0 + } + calibration { + speed: 8.4 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 8.4 + acceleration: -0.23 + command: 2.0 + } + calibration { + speed: 8.4 + acceleration: -0.21 + command: 0.0 + } + calibration { + speed: 8.4 + acceleration: -0.11 + command: 20.0 + } + calibration { + speed: 8.4 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 8.4 + acceleration: 0.35 + command: 25.0 + } + calibration { + speed: 8.4 + acceleration: 0.52 + command: 27.0 + } + calibration { + speed: 8.4 + acceleration: 0.69 + command: 30.0 + } + calibration { + speed: 8.4 + acceleration: 1.44 + command: 35.0 + } + calibration { + speed: 8.4 + acceleration: 2.09 + command: 40.0 + } + calibration { + speed: 8.4 + acceleration: 2.47 + command: 45.0 + } + calibration { + speed: 8.4 + acceleration: 2.6 + command: 60.0 + } + calibration { + speed: 8.4 + acceleration: 2.66 + command: 50.0 + } + calibration { + speed: 8.4 + acceleration: 2.78 + command: 55.0 + } + calibration { + speed: 8.4 + acceleration: 2.83 + command: 65.0 + } + calibration { + speed: 8.4 + acceleration: 3.18 + command: 70.0 + } + calibration { + speed: 8.4 + acceleration: 3.34 + command: 75.0 + } + calibration { + speed: 8.4 + acceleration: 3.53 + command: 80.0 + } + calibration { + speed: 8.6 + acceleration: -9.22 + command: -35.0 + } + calibration { + speed: 8.6 + acceleration: -8.29 + command: -33.0 + } + calibration { + speed: 8.6 + acceleration: -5.33 + command: -32.0 + } + calibration { + speed: 8.6 + acceleration: -4.68 + command: -31.0 + } + calibration { + speed: 8.6 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 8.6 + acceleration: -3.57 + command: -29.0 + } + calibration { + speed: 8.6 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 8.6 + acceleration: -2.32 + command: -27.0 + } + calibration { + speed: 8.6 + acceleration: -1.93 + command: -26.0 + } + calibration { + speed: 8.6 + acceleration: -1.38 + command: -25.0 + } + calibration { + speed: 8.6 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 8.6 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 8.6 + acceleration: -0.25 + command: -17.0 + } + calibration { + speed: 8.6 + acceleration: -0.24 + command: 16.0 + } + calibration { + speed: 8.6 + acceleration: -0.22 + command: -14.0 + } + calibration { + speed: 8.6 + acceleration: -0.1 + command: 20.0 + } + calibration { + speed: 8.6 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 8.6 + acceleration: 0.32 + command: 25.0 + } + calibration { + speed: 8.6 + acceleration: 0.5 + command: 27.0 + } + calibration { + speed: 8.6 + acceleration: 0.66 + command: 30.0 + } + calibration { + speed: 8.6 + acceleration: 1.42 + command: 35.0 + } + calibration { + speed: 8.6 + acceleration: 2.04 + command: 40.0 + } + calibration { + speed: 8.6 + acceleration: 2.42 + command: 45.0 + } + calibration { + speed: 8.6 + acceleration: 2.57 + command: 60.0 + } + calibration { + speed: 8.6 + acceleration: 2.6 + command: 50.0 + } + calibration { + speed: 8.6 + acceleration: 2.73 + command: 55.0 + } + calibration { + speed: 8.6 + acceleration: 2.83 + command: 65.0 + } + calibration { + speed: 8.6 + acceleration: 3.16 + command: 70.0 + } + calibration { + speed: 8.6 + acceleration: 3.34 + command: 75.0 + } + calibration { + speed: 8.6 + acceleration: 3.52 + command: 80.0 + } + calibration { + speed: 8.8 + acceleration: -9.17 + command: -35.0 + } + calibration { + speed: 8.8 + acceleration: -8.4 + command: -33.0 + } + calibration { + speed: 8.8 + acceleration: -5.3 + command: -32.0 + } + calibration { + speed: 8.8 + acceleration: -4.74 + command: -31.0 + } + calibration { + speed: 8.8 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 8.8 + acceleration: -3.57 + command: -29.0 + } + calibration { + speed: 8.8 + acceleration: -2.99 + command: -28.0 + } + calibration { + speed: 8.8 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 8.8 + acceleration: -1.93 + command: -26.0 + } + calibration { + speed: 8.8 + acceleration: -1.39 + command: -25.0 + } + calibration { + speed: 8.8 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 8.8 + acceleration: -0.66 + command: -23.0 + } + calibration { + speed: 8.8 + acceleration: -0.27 + command: -17.0 + } + calibration { + speed: 8.8 + acceleration: -0.23 + command: 1.0 + } + calibration { + speed: 8.8 + acceleration: -0.21 + command: -15.0 + } + calibration { + speed: 8.8 + acceleration: -0.2 + command: 17.0 + } + calibration { + speed: 8.8 + acceleration: -0.11 + command: 20.0 + } + calibration { + speed: 8.8 + acceleration: 0.17 + command: 22.0 + } + calibration { + speed: 8.8 + acceleration: 0.29 + command: 25.0 + } + calibration { + speed: 8.8 + acceleration: 0.48 + command: 27.0 + } + calibration { + speed: 8.8 + acceleration: 0.64 + command: 30.0 + } + calibration { + speed: 8.8 + acceleration: 1.39 + command: 35.0 + } + calibration { + speed: 8.8 + acceleration: 1.99 + command: 40.0 + } + calibration { + speed: 8.8 + acceleration: 2.36 + command: 45.0 + } + calibration { + speed: 8.8 + acceleration: 2.54 + command: 60.0 + } + calibration { + speed: 8.8 + acceleration: 2.55 + command: 50.0 + } + calibration { + speed: 8.8 + acceleration: 2.67 + command: 55.0 + } + calibration { + speed: 8.8 + acceleration: 2.81 + command: 65.0 + } + calibration { + speed: 8.8 + acceleration: 3.15 + command: 70.0 + } + calibration { + speed: 8.8 + acceleration: 3.33 + command: 75.0 + } + calibration { + speed: 8.8 + acceleration: 3.5 + command: 80.0 + } + calibration { + speed: 9.0 + acceleration: -9.02 + command: -35.0 + } + calibration { + speed: 9.0 + acceleration: -8.49 + command: -33.0 + } + calibration { + speed: 9.0 + acceleration: -5.24 + command: -32.0 + } + calibration { + speed: 9.0 + acceleration: -4.75 + command: -31.0 + } + calibration { + speed: 9.0 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 9.0 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 9.0 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 9.0 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 9.0 + acceleration: -1.93 + command: -26.0 + } + calibration { + speed: 9.0 + acceleration: -1.39 + command: -25.0 + } + calibration { + speed: 9.0 + acceleration: -0.95 + command: -24.0 + } + calibration { + speed: 9.0 + acceleration: -0.66 + command: -23.0 + } + calibration { + speed: 9.0 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 9.0 + acceleration: -0.24 + command: 6.33333333333 + } + calibration { + speed: 9.0 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 9.0 + acceleration: -0.09 + command: 20.0 + } + calibration { + speed: 9.0 + acceleration: 0.27 + command: 25.0 + } + calibration { + speed: 9.0 + acceleration: 0.45 + command: 27.0 + } + calibration { + speed: 9.0 + acceleration: 0.61 + command: 30.0 + } + calibration { + speed: 9.0 + acceleration: 1.32 + command: 35.0 + } + calibration { + speed: 9.0 + acceleration: 1.94 + command: 40.0 + } + calibration { + speed: 9.0 + acceleration: 2.31 + command: 45.0 + } + calibration { + speed: 9.0 + acceleration: 2.5 + command: 55.0 + } + calibration { + speed: 9.0 + acceleration: 2.62 + command: 55.0 + } + calibration { + speed: 9.0 + acceleration: 2.77 + command: 65.0 + } + calibration { + speed: 9.0 + acceleration: 3.14 + command: 70.0 + } + calibration { + speed: 9.0 + acceleration: 3.31 + command: 75.0 + } + calibration { + speed: 9.0 + acceleration: 3.48 + command: 80.0 + } + calibration { + speed: 9.2 + acceleration: -8.96 + command: -35.0 + } + calibration { + speed: 9.2 + acceleration: -8.59 + command: -33.0 + } + calibration { + speed: 9.2 + acceleration: -5.16 + command: -32.0 + } + calibration { + speed: 9.2 + acceleration: -4.7 + command: -31.0 + } + calibration { + speed: 9.2 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 9.2 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 9.2 + acceleration: -2.96 + command: -28.0 + } + calibration { + speed: 9.2 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 9.2 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 9.2 + acceleration: -1.39 + command: -25.0 + } + calibration { + speed: 9.2 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 9.2 + acceleration: -0.67 + command: -23.0 + } + calibration { + speed: 9.2 + acceleration: -0.25 + command: -1.0 + } + calibration { + speed: 9.2 + acceleration: -0.24 + command: -15.0 + } + calibration { + speed: 9.2 + acceleration: -0.23 + command: -13.0 + } + calibration { + speed: 9.2 + acceleration: -0.22 + command: 17.0 + } + calibration { + speed: 9.2 + acceleration: -0.16 + command: 20.0 + } + calibration { + speed: 9.2 + acceleration: 0.25 + command: 25.0 + } + calibration { + speed: 9.2 + acceleration: 0.43 + command: 27.0 + } + calibration { + speed: 9.2 + acceleration: 0.58 + command: 30.0 + } + calibration { + speed: 9.2 + acceleration: 1.27 + command: 35.0 + } + calibration { + speed: 9.2 + acceleration: 1.89 + command: 40.0 + } + calibration { + speed: 9.2 + acceleration: 2.26 + command: 45.0 + } + calibration { + speed: 9.2 + acceleration: 2.45 + command: 50.0 + } + calibration { + speed: 9.2 + acceleration: 2.47 + command: 60.0 + } + calibration { + speed: 9.2 + acceleration: 2.56 + command: 55.0 + } + calibration { + speed: 9.2 + acceleration: 2.72 + command: 65.0 + } + calibration { + speed: 9.2 + acceleration: 3.11 + command: 70.0 + } + calibration { + speed: 9.2 + acceleration: 3.28 + command: 75.0 + } + calibration { + speed: 9.2 + acceleration: 3.45 + command: 80.0 + } + calibration { + speed: 9.4 + acceleration: -8.89 + command: -35.0 + } + calibration { + speed: 9.4 + acceleration: -8.59 + command: -33.0 + } + calibration { + speed: 9.4 + acceleration: -5.1 + command: -32.0 + } + calibration { + speed: 9.4 + acceleration: -4.66 + command: -31.0 + } + calibration { + speed: 9.4 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 9.4 + acceleration: -3.57 + command: -29.0 + } + calibration { + speed: 9.4 + acceleration: -2.95 + command: -28.0 + } + calibration { + speed: 9.4 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 9.4 + acceleration: -1.93 + command: -26.0 + } + calibration { + speed: 9.4 + acceleration: -1.4 + command: -25.0 + } + calibration { + speed: 9.4 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 9.4 + acceleration: -0.67 + command: -23.0 + } + calibration { + speed: 9.4 + acceleration: -0.27 + command: 15.0 + } + calibration { + speed: 9.4 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 9.4 + acceleration: -0.25 + command: 1.0 + } + calibration { + speed: 9.4 + acceleration: -0.24 + command: -13.0 + } + calibration { + speed: 9.4 + acceleration: -0.14 + command: 20.0 + } + calibration { + speed: 9.4 + acceleration: 0.22 + command: 25.0 + } + calibration { + speed: 9.4 + acceleration: 0.41 + command: 27.0 + } + calibration { + speed: 9.4 + acceleration: 0.56 + command: 30.0 + } + calibration { + speed: 9.4 + acceleration: 1.25 + command: 35.0 + } + calibration { + speed: 9.4 + acceleration: 1.85 + command: 40.0 + } + calibration { + speed: 9.4 + acceleration: 2.21 + command: 45.0 + } + calibration { + speed: 9.4 + acceleration: 2.4 + command: 50.0 + } + calibration { + speed: 9.4 + acceleration: 2.43 + command: 60.0 + } + calibration { + speed: 9.4 + acceleration: 2.51 + command: 55.0 + } + calibration { + speed: 9.4 + acceleration: 2.67 + command: 65.0 + } + calibration { + speed: 9.4 + acceleration: 3.07 + command: 70.0 + } + calibration { + speed: 9.4 + acceleration: 3.22 + command: 75.0 + } + calibration { + speed: 9.4 + acceleration: 3.4 + command: 80.0 + } + calibration { + speed: 9.6 + acceleration: -8.79 + command: -35.0 + } + calibration { + speed: 9.6 + acceleration: -8.53 + command: -33.0 + } + calibration { + speed: 9.6 + acceleration: -5.11 + command: -32.0 + } + calibration { + speed: 9.6 + acceleration: -4.54 + command: -31.0 + } + calibration { + speed: 9.6 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 9.6 + acceleration: -3.58 + command: -29.0 + } + calibration { + speed: 9.6 + acceleration: -2.95 + command: -28.0 + } + calibration { + speed: 9.6 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 9.6 + acceleration: -1.95 + command: -26.0 + } + calibration { + speed: 9.6 + acceleration: -1.4 + command: -25.0 + } + calibration { + speed: 9.6 + acceleration: -0.98 + command: -24.0 + } + calibration { + speed: 9.6 + acceleration: -0.67 + command: -23.0 + } + calibration { + speed: 9.6 + acceleration: -0.27 + command: -17.0 + } + calibration { + speed: 9.6 + acceleration: -0.25 + command: 17.0 + } + calibration { + speed: 9.6 + acceleration: -0.23 + command: -4.33333333333 + } + calibration { + speed: 9.6 + acceleration: -0.16 + command: 20.0 + } + calibration { + speed: 9.6 + acceleration: 0.2 + command: 25.0 + } + calibration { + speed: 9.6 + acceleration: 0.41 + command: 27.0 + } + calibration { + speed: 9.6 + acceleration: 0.54 + command: 30.0 + } + calibration { + speed: 9.6 + acceleration: 1.22 + command: 35.0 + } + calibration { + speed: 9.6 + acceleration: 1.8 + command: 40.0 + } + calibration { + speed: 9.6 + acceleration: 2.17 + command: 45.0 + } + calibration { + speed: 9.6 + acceleration: 2.36 + command: 50.0 + } + calibration { + speed: 9.6 + acceleration: 2.4 + command: 60.0 + } + calibration { + speed: 9.6 + acceleration: 2.47 + command: 55.0 + } + calibration { + speed: 9.6 + acceleration: 2.63 + command: 65.0 + } + calibration { + speed: 9.6 + acceleration: 3.03 + command: 70.0 + } + calibration { + speed: 9.6 + acceleration: 3.16 + command: 75.0 + } + calibration { + speed: 9.6 + acceleration: 3.35 + command: 80.0 + } + calibration { + speed: 9.8 + acceleration: -8.31 + command: -35.0 + } + calibration { + speed: 9.8 + acceleration: -8.25 + command: -33.0 + } + calibration { + speed: 9.8 + acceleration: -5.19 + command: -32.0 + } + calibration { + speed: 9.8 + acceleration: -4.48 + command: -31.0 + } + calibration { + speed: 9.8 + acceleration: -4.04 + command: -30.0 + } + calibration { + speed: 9.8 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 9.8 + acceleration: -3.0 + command: -28.0 + } + calibration { + speed: 9.8 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 9.8 + acceleration: -1.95 + command: -26.0 + } + calibration { + speed: 9.8 + acceleration: -1.4 + command: -25.0 + } + calibration { + speed: 9.8 + acceleration: -0.96 + command: -24.0 + } + calibration { + speed: 9.8 + acceleration: -0.68 + command: -23.0 + } + calibration { + speed: 9.8 + acceleration: -0.28 + command: 15.0 + } + calibration { + speed: 9.8 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 9.8 + acceleration: -0.25 + command: -3.66666666667 + } + calibration { + speed: 9.8 + acceleration: -0.14 + command: 20.0 + } + calibration { + speed: 9.8 + acceleration: 0.2 + command: 25.0 + } + calibration { + speed: 9.8 + acceleration: 0.41 + command: 27.0 + } + calibration { + speed: 9.8 + acceleration: 0.53 + command: 30.0 + } + calibration { + speed: 9.8 + acceleration: 1.2 + command: 35.0 + } + calibration { + speed: 9.8 + acceleration: 1.75 + command: 40.0 + } + calibration { + speed: 9.8 + acceleration: 2.14 + command: 45.0 + } + calibration { + speed: 9.8 + acceleration: 2.32 + command: 50.0 + } + calibration { + speed: 9.8 + acceleration: 2.36 + command: 60.0 + } + calibration { + speed: 9.8 + acceleration: 2.42 + command: 55.0 + } + calibration { + speed: 9.8 + acceleration: 2.58 + command: 65.0 + } + calibration { + speed: 9.8 + acceleration: 2.98 + command: 70.0 + } + calibration { + speed: 9.8 + acceleration: 3.1 + command: 75.0 + } + calibration { + speed: 9.8 + acceleration: 3.28 + command: 80.0 + } + calibration { + speed: 10.0 + acceleration: -8.14 + command: -35.0 + } + calibration { + speed: 10.0 + acceleration: -7.92 + command: -33.0 + } + calibration { + speed: 10.0 + acceleration: -5.3 + command: -32.0 + } + calibration { + speed: 10.0 + acceleration: -4.47 + command: -31.0 + } + calibration { + speed: 10.0 + acceleration: -4.03 + command: -30.0 + } + calibration { + speed: 10.0 + acceleration: -3.51 + command: -29.0 + } + calibration { + speed: 10.0 + acceleration: -3.05 + command: -28.0 + } + calibration { + speed: 10.0 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 10.0 + acceleration: -1.96 + command: -26.0 + } + calibration { + speed: 10.0 + acceleration: -1.4 + command: -25.0 + } + calibration { + speed: 10.0 + acceleration: -0.98 + command: -24.0 + } + calibration { + speed: 10.0 + acceleration: -0.68 + command: -23.0 + } + calibration { + speed: 10.0 + acceleration: -0.28 + command: 15.0 + } + calibration { + speed: 10.0 + acceleration: -0.27 + command: -17.0 + } + calibration { + speed: 10.0 + acceleration: -0.26 + command: 1.0 + } + calibration { + speed: 10.0 + acceleration: -0.23 + command: -13.0 + } + calibration { + speed: 10.0 + acceleration: -0.16 + command: 20.0 + } + calibration { + speed: 10.0 + acceleration: 0.2 + command: 25.0 + } + calibration { + speed: 10.0 + acceleration: 0.38 + command: 27.0 + } + calibration { + speed: 10.0 + acceleration: 0.49 + command: 30.0 + } + calibration { + speed: 10.0 + acceleration: 1.18 + command: 35.0 + } + calibration { + speed: 10.0 + acceleration: 1.71 + command: 40.0 + } + calibration { + speed: 10.0 + acceleration: 2.1 + command: 45.0 + } + calibration { + speed: 10.0 + acceleration: 2.28 + command: 50.0 + } + calibration { + speed: 10.0 + acceleration: 2.29 + command: 60.0 + } + calibration { + speed: 10.0 + acceleration: 2.36 + command: 55.0 + } + calibration { + speed: 10.0 + acceleration: 2.52 + command: 65.0 + } + calibration { + speed: 10.0 + acceleration: 2.94 + command: 70.0 + } + calibration { + speed: 10.0 + acceleration: 3.04 + command: 75.0 + } + calibration { + speed: 10.0 + acceleration: 3.2 + command: 80.0 + } + } +} +trajectory_period: 0.1 +chassis_period: 0.01 +localization_period: 0.01 diff --git a/apollo_control/conf/lincoln_062147.pb.txt b/apollo_control/conf/lincoln_062147.pb.txt new file mode 100644 index 0000000..a8e6a04 --- /dev/null +++ b/apollo_control/conf/lincoln_062147.pb.txt @@ -0,0 +1,7590 @@ +control_period: 0.01 +max_planning_interval_sec: 0.2 +max_planning_delay_threshold: 4.0 +action: STOP +soft_estop_brake: 50.0 +active_controllers: LAT_CONTROLLER +active_controllers: LON_CONTROLLER +max_steering_percentage_allowed: 100 +max_status_interval_sec: 0.1 +lat_controller_conf { + ts: 0.01 + preview_window: 0 + cf: 155494.663 + cr: 155494.663 + wheelbase: 2.85 + mass_fl: 520 + mass_fr: 520 + mass_rl: 520 + mass_rr: 520 + eps: 0.01 + matrix_q: 0.05 + matrix_q: 0.0 + matrix_q: 1.0 + matrix_q: 0.0 + cutoff_freq: 10 + mean_filter_window_size: 10 + steer_transmission_ratio: 16 + steer_single_direction_max_degree: 470 + max_iteration: 150 +} +lon_controller_conf { + ts: 0.01 + brake_deadzone: 15.5 + throttle_deadzone: 18.0 + speed_controller_input_limit: 2.0 + station_error_limit: 2.0 + preview_window: 20.0 + standstill_acceleration: -3.0 + station_pid_conf { + integrator_enable: false + integrator_saturation_level: 0.3 + kp: 0.2 + ki: 0.0 + kd: 0.0 + } + low_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 0.5 + ki: 0.3 + kd: 0.0 + } + high_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 1.0 + ki: 0.3 + kd: 0.0 + } + switch_speed: 2.0 + throttle_filter_conf { + cutoff_freq: 10 + } + brake_filter_conf { + cutoff_freq: 10 + } + acceleration_filter_conf { + cutoff_freq: 5 + } + calibration_table { + calibration { + speed: 0.0 + acceleration: -4.69 + command: -33.0 + } + calibration { + speed: 0.0 + acceleration: -3.64 + command: -32.0 + } + calibration { + speed: 0.0 + acceleration: -3.38 + command: -31.0 + } + calibration { + speed: 0.0 + acceleration: -3.23 + command: -30.0 + } + calibration { + speed: 0.0 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 0.0 + acceleration: -2.5 + command: -28.0 + } + calibration { + speed: 0.0 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 0.0 + acceleration: -1.77 + command: -26.0 + } + calibration { + speed: 0.0 + acceleration: -1.21 + command: -25.0 + } + calibration { + speed: 0.0 + acceleration: -0.81 + command: -24.0 + } + calibration { + speed: 0.0 + acceleration: -0.44 + command: -23.0 + } + calibration { + speed: 0.0 + acceleration: 0.28 + command: -20.0 + } + calibration { + speed: 0.0 + acceleration: 0.37 + command: -15.0 + } + calibration { + speed: 0.0 + acceleration: 0.4 + command: 15.0 + } + calibration { + speed: 0.0 + acceleration: 0.41 + command: -15.0 + } + calibration { + speed: 0.0 + acceleration: 0.94 + command: 22.0 + } + calibration { + speed: 0.0 + acceleration: 1.38 + command: 27.0 + } + calibration { + speed: 0.0 + acceleration: 1.41 + command: 25.0 + } + calibration { + speed: 0.0 + acceleration: 1.5 + command: 30.0 + } + calibration { + speed: 0.0 + acceleration: 1.59 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 1.7 + command: 40.0 + } + calibration { + speed: 0.0 + acceleration: 1.78 + command: 45.0 + } + calibration { + speed: 0.0 + acceleration: 1.82 + command: 50.0 + } + calibration { + speed: 0.0 + acceleration: 1.89 + command: 55.0 + } + calibration { + speed: 0.0 + acceleration: 1.98 + command: 80.0 + } + calibration { + speed: 0.0 + acceleration: 2.0 + command: 60.0 + } + calibration { + speed: 0.0 + acceleration: 2.09 + command: 70.0 + } + calibration { + speed: 0.0 + acceleration: 2.12 + command: 65.0 + } + calibration { + speed: 0.0 + acceleration: 2.16 + command: 75.0 + } + calibration { + speed: 0.2 + acceleration: -4.95 + command: -33.0 + } + calibration { + speed: 0.2 + acceleration: -3.78 + command: -32.0 + } + calibration { + speed: 0.2 + acceleration: -3.51 + command: -31.0 + } + calibration { + speed: 0.2 + acceleration: -3.32 + command: -30.0 + } + calibration { + speed: 0.2 + acceleration: -2.83 + command: -29.0 + } + calibration { + speed: 0.2 + acceleration: -2.54 + command: -28.0 + } + calibration { + speed: 0.2 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 0.2 + acceleration: -1.77 + command: -26.0 + } + calibration { + speed: 0.2 + acceleration: -1.21 + command: -25.0 + } + calibration { + speed: 0.2 + acceleration: -0.81 + command: -24.0 + } + calibration { + speed: 0.2 + acceleration: -0.45 + command: -23.0 + } + calibration { + speed: 0.2 + acceleration: 0.28 + command: -20.0 + } + calibration { + speed: 0.2 + acceleration: 0.37 + command: -13.0 + } + calibration { + speed: 0.2 + acceleration: 0.38 + command: -17.0 + } + calibration { + speed: 0.2 + acceleration: 0.4 + command: 15.0 + } + calibration { + speed: 0.2 + acceleration: 0.41 + command: -15.0 + } + calibration { + speed: 0.2 + acceleration: 0.94 + command: 22.0 + } + calibration { + speed: 0.2 + acceleration: 1.44 + command: 26.0 + } + calibration { + speed: 0.2 + acceleration: 1.54 + command: 30.0 + } + calibration { + speed: 0.2 + acceleration: 1.66 + command: 35.0 + } + calibration { + speed: 0.2 + acceleration: 1.78 + command: 40.0 + } + calibration { + speed: 0.2 + acceleration: 1.87 + command: 45.0 + } + calibration { + speed: 0.2 + acceleration: 1.94 + command: 50.0 + } + calibration { + speed: 0.2 + acceleration: 2.01 + command: 55.0 + } + calibration { + speed: 0.2 + acceleration: 2.13 + command: 80.0 + } + calibration { + speed: 0.2 + acceleration: 2.14 + command: 60.0 + } + calibration { + speed: 0.2 + acceleration: 2.21 + command: 70.0 + } + calibration { + speed: 0.2 + acceleration: 2.24 + command: 65.0 + } + calibration { + speed: 0.2 + acceleration: 2.28 + command: 75.0 + } + calibration { + speed: 0.4 + acceleration: -6.17 + command: -33.0 + } + calibration { + speed: 0.4 + acceleration: -4.62 + command: -32.0 + } + calibration { + speed: 0.4 + acceleration: -4.26 + command: -31.0 + } + calibration { + speed: 0.4 + acceleration: -3.83 + command: -30.0 + } + calibration { + speed: 0.4 + acceleration: -3.13 + command: -29.0 + } + calibration { + speed: 0.4 + acceleration: -2.74 + command: -28.0 + } + calibration { + speed: 0.4 + acceleration: -2.54 + command: -27.0 + } + calibration { + speed: 0.4 + acceleration: -1.8 + command: -26.0 + } + calibration { + speed: 0.4 + acceleration: -1.22 + command: -25.0 + } + calibration { + speed: 0.4 + acceleration: -0.81 + command: -24.0 + } + calibration { + speed: 0.4 + acceleration: -0.5 + command: -23.0 + } + calibration { + speed: 0.4 + acceleration: 0.22 + command: -20.0 + } + calibration { + speed: 0.4 + acceleration: 0.38 + command: -17.0 + } + calibration { + speed: 0.4 + acceleration: 0.39 + command: -15.0 + } + calibration { + speed: 0.4 + acceleration: 0.4 + command: -13.0 + } + calibration { + speed: 0.4 + acceleration: 0.43 + command: 15.0 + } + calibration { + speed: 0.4 + acceleration: 1.0 + command: 22.0 + } + calibration { + speed: 0.4 + acceleration: 1.55 + command: 25.0 + } + calibration { + speed: 0.4 + acceleration: 1.6 + command: 27.0 + } + calibration { + speed: 0.4 + acceleration: 1.73 + command: 30.0 + } + calibration { + speed: 0.4 + acceleration: 1.85 + command: 35.0 + } + calibration { + speed: 0.4 + acceleration: 2.02 + command: 40.0 + } + calibration { + speed: 0.4 + acceleration: 2.1 + command: 45.0 + } + calibration { + speed: 0.4 + acceleration: 2.21 + command: 50.0 + } + calibration { + speed: 0.4 + acceleration: 2.27 + command: 55.0 + } + calibration { + speed: 0.4 + acceleration: 2.43 + command: 60.0 + } + calibration { + speed: 0.4 + acceleration: 2.45 + command: 65.0 + } + calibration { + speed: 0.4 + acceleration: 2.46 + command: 75.0 + } + calibration { + speed: 0.4 + acceleration: 2.48 + command: 75.0 + } + calibration { + speed: 0.6 + acceleration: -7.7 + command: -33.0 + } + calibration { + speed: 0.6 + acceleration: -5.38 + command: -32.0 + } + calibration { + speed: 0.6 + acceleration: -4.84 + command: -31.0 + } + calibration { + speed: 0.6 + acceleration: -4.31 + command: -30.0 + } + calibration { + speed: 0.6 + acceleration: -3.47 + command: -29.0 + } + calibration { + speed: 0.6 + acceleration: -2.89 + command: -28.0 + } + calibration { + speed: 0.6 + acceleration: -2.62 + command: -27.0 + } + calibration { + speed: 0.6 + acceleration: -1.82 + command: -26.0 + } + calibration { + speed: 0.6 + acceleration: -1.24 + command: -25.0 + } + calibration { + speed: 0.6 + acceleration: -0.82 + command: -24.0 + } + calibration { + speed: 0.6 + acceleration: -0.55 + command: -23.0 + } + calibration { + speed: 0.6 + acceleration: 0.15 + command: -20.0 + } + calibration { + speed: 0.6 + acceleration: 0.35 + command: -17.0 + } + calibration { + speed: 0.6 + acceleration: 0.36 + command: -13.0 + } + calibration { + speed: 0.6 + acceleration: 0.37 + command: -15.0 + } + calibration { + speed: 0.6 + acceleration: 0.38 + command: 15.0 + } + calibration { + speed: 0.6 + acceleration: 1.09 + command: 22.0 + } + calibration { + speed: 0.6 + acceleration: 1.65 + command: 25.0 + } + calibration { + speed: 0.6 + acceleration: 1.79 + command: 27.0 + } + calibration { + speed: 0.6 + acceleration: 1.96 + command: 30.0 + } + calibration { + speed: 0.6 + acceleration: 2.08 + command: 35.0 + } + calibration { + speed: 0.6 + acceleration: 2.26 + command: 40.0 + } + calibration { + speed: 0.6 + acceleration: 2.32 + command: 45.0 + } + calibration { + speed: 0.6 + acceleration: 2.46 + command: 50.0 + } + calibration { + speed: 0.6 + acceleration: 2.53 + command: 55.0 + } + calibration { + speed: 0.6 + acceleration: 2.64 + command: 80.0 + } + calibration { + speed: 0.6 + acceleration: 2.65 + command: 60.0 + } + calibration { + speed: 0.6 + acceleration: 2.66 + command: 72.5 + } + calibration { + speed: 0.6 + acceleration: 2.67 + command: 65.0 + } + calibration { + speed: 0.8 + acceleration: -8.77 + command: -33.0 + } + calibration { + speed: 0.8 + acceleration: -5.63 + command: -32.0 + } + calibration { + speed: 0.8 + acceleration: -4.99 + command: -31.0 + } + calibration { + speed: 0.8 + acceleration: -4.39 + command: -30.0 + } + calibration { + speed: 0.8 + acceleration: -3.5 + command: -29.0 + } + calibration { + speed: 0.8 + acceleration: -2.85 + command: -28.0 + } + calibration { + speed: 0.8 + acceleration: -2.56 + command: -27.0 + } + calibration { + speed: 0.8 + acceleration: -1.8 + command: -26.0 + } + calibration { + speed: 0.8 + acceleration: -1.26 + command: -25.0 + } + calibration { + speed: 0.8 + acceleration: -0.84 + command: -24.0 + } + calibration { + speed: 0.8 + acceleration: -0.55 + command: -23.0 + } + calibration { + speed: 0.8 + acceleration: 0.14 + command: -20.0 + } + calibration { + speed: 0.8 + acceleration: 0.3 + command: -15.0 + } + calibration { + speed: 0.8 + acceleration: 0.32 + command: -15.0 + } + calibration { + speed: 0.8 + acceleration: 0.35 + command: 15.0 + } + calibration { + speed: 0.8 + acceleration: 1.14 + command: 22.0 + } + calibration { + speed: 0.8 + acceleration: 1.75 + command: 25.0 + } + calibration { + speed: 0.8 + acceleration: 2.0 + command: 27.0 + } + calibration { + speed: 0.8 + acceleration: 2.15 + command: 30.0 + } + calibration { + speed: 0.8 + acceleration: 2.31 + command: 35.0 + } + calibration { + speed: 0.8 + acceleration: 2.47 + command: 40.0 + } + calibration { + speed: 0.8 + acceleration: 2.49 + command: 45.0 + } + calibration { + speed: 0.8 + acceleration: 2.63 + command: 50.0 + } + calibration { + speed: 0.8 + acceleration: 2.67 + command: 55.0 + } + calibration { + speed: 0.8 + acceleration: 2.69 + command: 80.0 + } + calibration { + speed: 0.8 + acceleration: 2.7 + command: 70.0 + } + calibration { + speed: 0.8 + acceleration: 2.71 + command: 65.0 + } + calibration { + speed: 0.8 + acceleration: 2.72 + command: 75.0 + } + calibration { + speed: 0.8 + acceleration: 2.76 + command: 60.0 + } + calibration { + speed: 1.0 + acceleration: -9.06 + command: -33.0 + } + calibration { + speed: 1.0 + acceleration: -5.63 + command: -32.0 + } + calibration { + speed: 1.0 + acceleration: -4.93 + command: -31.0 + } + calibration { + speed: 1.0 + acceleration: -4.29 + command: -30.0 + } + calibration { + speed: 1.0 + acceleration: -3.46 + command: -29.0 + } + calibration { + speed: 1.0 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 1.0 + acceleration: -2.55 + command: -27.0 + } + calibration { + speed: 1.0 + acceleration: -1.8 + command: -26.0 + } + calibration { + speed: 1.0 + acceleration: -1.25 + command: -25.0 + } + calibration { + speed: 1.0 + acceleration: -0.85 + command: -24.0 + } + calibration { + speed: 1.0 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 1.0 + acceleration: 0.04 + command: -20.0 + } + calibration { + speed: 1.0 + acceleration: 0.22 + command: -17.0 + } + calibration { + speed: 1.0 + acceleration: 0.24 + command: -13.0 + } + calibration { + speed: 1.0 + acceleration: 0.27 + command: -15.0 + } + calibration { + speed: 1.0 + acceleration: 0.31 + command: 15.0 + } + calibration { + speed: 1.0 + acceleration: 1.17 + command: 22.0 + } + calibration { + speed: 1.0 + acceleration: 1.84 + command: 25.0 + } + calibration { + speed: 1.0 + acceleration: 2.13 + command: 27.0 + } + calibration { + speed: 1.0 + acceleration: 2.31 + command: 30.0 + } + calibration { + speed: 1.0 + acceleration: 2.53 + command: 35.0 + } + calibration { + speed: 1.0 + acceleration: 2.65 + command: 42.5 + } + calibration { + speed: 1.0 + acceleration: 2.71 + command: 80.0 + } + calibration { + speed: 1.0 + acceleration: 2.72 + command: 70.0 + } + calibration { + speed: 1.0 + acceleration: 2.73 + command: 75.0 + } + calibration { + speed: 1.0 + acceleration: 2.74 + command: 65.0 + } + calibration { + speed: 1.0 + acceleration: 2.76 + command: 50.0 + } + calibration { + speed: 1.0 + acceleration: 2.77 + command: 55.0 + } + calibration { + speed: 1.0 + acceleration: 2.8 + command: 60.0 + } + calibration { + speed: 1.2 + acceleration: -9.19 + command: -33.0 + } + calibration { + speed: 1.2 + acceleration: -5.41 + command: -32.0 + } + calibration { + speed: 1.2 + acceleration: -4.75 + command: -31.0 + } + calibration { + speed: 1.2 + acceleration: -4.17 + command: -30.0 + } + calibration { + speed: 1.2 + acceleration: -3.44 + command: -29.0 + } + calibration { + speed: 1.2 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 1.2 + acceleration: -2.58 + command: -27.0 + } + calibration { + speed: 1.2 + acceleration: -1.8 + command: -26.0 + } + calibration { + speed: 1.2 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 1.2 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 1.2 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 1.2 + acceleration: -0.02 + command: -20.0 + } + calibration { + speed: 1.2 + acceleration: 0.16 + command: -17.0 + } + calibration { + speed: 1.2 + acceleration: 0.17 + command: -13.0 + } + calibration { + speed: 1.2 + acceleration: 0.18 + command: 15.0 + } + calibration { + speed: 1.2 + acceleration: 0.2 + command: -15.0 + } + calibration { + speed: 1.2 + acceleration: 1.19 + command: 22.0 + } + calibration { + speed: 1.2 + acceleration: 1.89 + command: 25.0 + } + calibration { + speed: 1.2 + acceleration: 2.23 + command: 27.0 + } + calibration { + speed: 1.2 + acceleration: 2.42 + command: 30.0 + } + calibration { + speed: 1.2 + acceleration: 2.69 + command: 35.0 + } + calibration { + speed: 1.2 + acceleration: 2.76 + command: 77.5 + } + calibration { + speed: 1.2 + acceleration: 2.77 + command: 70.0 + } + calibration { + speed: 1.2 + acceleration: 2.79 + command: 45.0 + } + calibration { + speed: 1.2 + acceleration: 2.8 + command: 65.0 + } + calibration { + speed: 1.2 + acceleration: 2.81 + command: 40.0 + } + calibration { + speed: 1.2 + acceleration: 2.84 + command: 55.0 + } + calibration { + speed: 1.2 + acceleration: 2.87 + command: 55.0 + } + calibration { + speed: 1.4 + acceleration: -9.14 + command: -33.0 + } + calibration { + speed: 1.4 + acceleration: -5.28 + command: -32.0 + } + calibration { + speed: 1.4 + acceleration: -4.64 + command: -31.0 + } + calibration { + speed: 1.4 + acceleration: -4.1 + command: -30.0 + } + calibration { + speed: 1.4 + acceleration: -3.43 + command: -29.0 + } + calibration { + speed: 1.4 + acceleration: -2.81 + command: -28.0 + } + calibration { + speed: 1.4 + acceleration: -2.58 + command: -27.0 + } + calibration { + speed: 1.4 + acceleration: -1.79 + command: -26.0 + } + calibration { + speed: 1.4 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 1.4 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 1.4 + acceleration: -0.6 + command: -23.0 + } + calibration { + speed: 1.4 + acceleration: -0.07 + command: -20.0 + } + calibration { + speed: 1.4 + acceleration: 0.1 + command: -13.0 + } + calibration { + speed: 1.4 + acceleration: 0.11 + command: -17.0 + } + calibration { + speed: 1.4 + acceleration: 0.15 + command: 15.0 + } + calibration { + speed: 1.4 + acceleration: 0.19 + command: -15.0 + } + calibration { + speed: 1.4 + acceleration: 1.18 + command: 22.0 + } + calibration { + speed: 1.4 + acceleration: 1.93 + command: 25.0 + } + calibration { + speed: 1.4 + acceleration: 2.3 + command: 27.0 + } + calibration { + speed: 1.4 + acceleration: 2.5 + command: 30.0 + } + calibration { + speed: 1.4 + acceleration: 2.82 + command: 35.0 + } + calibration { + speed: 1.4 + acceleration: 2.83 + command: 75.0 + } + calibration { + speed: 1.4 + acceleration: 2.84 + command: 80.0 + } + calibration { + speed: 1.4 + acceleration: 2.85 + command: 70.0 + } + calibration { + speed: 1.4 + acceleration: 2.91 + command: 65.0 + } + calibration { + speed: 1.4 + acceleration: 2.93 + command: 45.0 + } + calibration { + speed: 1.4 + acceleration: 2.94 + command: 40.0 + } + calibration { + speed: 1.4 + acceleration: 2.96 + command: 57.5 + } + calibration { + speed: 1.4 + acceleration: 2.98 + command: 50.0 + } + calibration { + speed: 1.6 + acceleration: -8.97 + command: -33.0 + } + calibration { + speed: 1.6 + acceleration: -5.14 + command: -32.0 + } + calibration { + speed: 1.6 + acceleration: -4.58 + command: -31.0 + } + calibration { + speed: 1.6 + acceleration: -4.09 + command: -30.0 + } + calibration { + speed: 1.6 + acceleration: -3.44 + command: -29.0 + } + calibration { + speed: 1.6 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 1.6 + acceleration: -2.54 + command: -27.0 + } + calibration { + speed: 1.6 + acceleration: -1.81 + command: -26.0 + } + calibration { + speed: 1.6 + acceleration: -1.26 + command: -25.0 + } + calibration { + speed: 1.6 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 1.6 + acceleration: -0.69 + command: -23.0 + } + calibration { + speed: 1.6 + acceleration: -0.12 + command: -20.0 + } + calibration { + speed: 1.6 + acceleration: 0.01 + command: 15.0 + } + calibration { + speed: 1.6 + acceleration: 0.03 + command: -17.0 + } + calibration { + speed: 1.6 + acceleration: 0.05 + command: -13.0 + } + calibration { + speed: 1.6 + acceleration: 0.09 + command: -15.0 + } + calibration { + speed: 1.6 + acceleration: 1.15 + command: 22.0 + } + calibration { + speed: 1.6 + acceleration: 1.96 + command: 25.0 + } + calibration { + speed: 1.6 + acceleration: 2.35 + command: 27.0 + } + calibration { + speed: 1.6 + acceleration: 2.57 + command: 30.0 + } + calibration { + speed: 1.6 + acceleration: 2.93 + command: 72.5 + } + calibration { + speed: 1.6 + acceleration: 2.94 + command: 35.0 + } + calibration { + speed: 1.6 + acceleration: 2.97 + command: 80.0 + } + calibration { + speed: 1.6 + acceleration: 3.02 + command: 65.0 + } + calibration { + speed: 1.6 + acceleration: 3.03 + command: 45.0 + } + calibration { + speed: 1.6 + acceleration: 3.04 + command: 55.0 + } + calibration { + speed: 1.6 + acceleration: 3.05 + command: 40.0 + } + calibration { + speed: 1.6 + acceleration: 3.06 + command: 60.0 + } + calibration { + speed: 1.6 + acceleration: 3.08 + command: 50.0 + } + calibration { + speed: 1.8 + acceleration: -8.82 + command: -33.0 + } + calibration { + speed: 1.8 + acceleration: -5.11 + command: -32.0 + } + calibration { + speed: 1.8 + acceleration: -4.59 + command: -31.0 + } + calibration { + speed: 1.8 + acceleration: -4.11 + command: -30.0 + } + calibration { + speed: 1.8 + acceleration: -3.42 + command: -29.0 + } + calibration { + speed: 1.8 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 1.8 + acceleration: -2.48 + command: -27.0 + } + calibration { + speed: 1.8 + acceleration: -1.82 + command: -26.0 + } + calibration { + speed: 1.8 + acceleration: -1.24 + command: -25.0 + } + calibration { + speed: 1.8 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 1.8 + acceleration: -0.66 + command: -23.0 + } + calibration { + speed: 1.8 + acceleration: -0.17 + command: -20.0 + } + calibration { + speed: 1.8 + acceleration: -0.05 + command: 15.0 + } + calibration { + speed: 1.8 + acceleration: 0.0 + command: -14.0 + } + calibration { + speed: 1.8 + acceleration: 1.11 + command: 22.0 + } + calibration { + speed: 1.8 + acceleration: 1.98 + command: 25.0 + } + calibration { + speed: 1.8 + acceleration: 2.39 + command: 27.0 + } + calibration { + speed: 1.8 + acceleration: 2.63 + command: 30.0 + } + calibration { + speed: 1.8 + acceleration: 3.02 + command: 35.0 + } + calibration { + speed: 1.8 + acceleration: 3.03 + command: 75.0 + } + calibration { + speed: 1.8 + acceleration: 3.06 + command: 80.0 + } + calibration { + speed: 1.8 + acceleration: 3.07 + command: 70.0 + } + calibration { + speed: 1.8 + acceleration: 3.11 + command: 60.0 + } + calibration { + speed: 1.8 + acceleration: 3.12 + command: 55.0 + } + calibration { + speed: 1.8 + acceleration: 3.15 + command: 47.5 + } + calibration { + speed: 1.8 + acceleration: 3.18 + command: 50.0 + } + calibration { + speed: 2.0 + acceleration: -8.61 + command: -33.0 + } + calibration { + speed: 2.0 + acceleration: -5.13 + command: -32.0 + } + calibration { + speed: 2.0 + acceleration: -4.65 + command: -31.0 + } + calibration { + speed: 2.0 + acceleration: -4.15 + command: -30.0 + } + calibration { + speed: 2.0 + acceleration: -3.4 + command: -29.0 + } + calibration { + speed: 2.0 + acceleration: -2.77 + command: -28.0 + } + calibration { + speed: 2.0 + acceleration: -2.44 + command: -27.0 + } + calibration { + speed: 2.0 + acceleration: -1.79 + command: -26.0 + } + calibration { + speed: 2.0 + acceleration: -1.26 + command: -25.0 + } + calibration { + speed: 2.0 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 2.0 + acceleration: -0.63 + command: -23.0 + } + calibration { + speed: 2.0 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 2.0 + acceleration: -0.09 + command: -15.0 + } + calibration { + speed: 2.0 + acceleration: -0.07 + command: 1.0 + } + calibration { + speed: 2.0 + acceleration: -0.02 + command: -17.0 + } + calibration { + speed: 2.0 + acceleration: 1.05 + command: 22.0 + } + calibration { + speed: 2.0 + acceleration: 1.95 + command: 25.0 + } + calibration { + speed: 2.0 + acceleration: 2.4 + command: 27.0 + } + calibration { + speed: 2.0 + acceleration: 2.67 + command: 30.0 + } + calibration { + speed: 2.0 + acceleration: 3.08 + command: 35.0 + } + calibration { + speed: 2.0 + acceleration: 3.11 + command: 60.0 + } + calibration { + speed: 2.0 + acceleration: 3.14 + command: 75.0 + } + calibration { + speed: 2.0 + acceleration: 3.15 + command: 80.0 + } + calibration { + speed: 2.0 + acceleration: 3.16 + command: 70.0 + } + calibration { + speed: 2.0 + acceleration: 3.19 + command: 45.0 + } + calibration { + speed: 2.0 + acceleration: 3.21 + command: 65.0 + } + calibration { + speed: 2.0 + acceleration: 3.23 + command: 55.0 + } + calibration { + speed: 2.0 + acceleration: 3.24 + command: 40.0 + } + calibration { + speed: 2.0 + acceleration: 3.25 + command: 50.0 + } + calibration { + speed: 2.2 + acceleration: -8.5 + command: -33.0 + } + calibration { + speed: 2.2 + acceleration: -5.19 + command: -32.0 + } + calibration { + speed: 2.2 + acceleration: -4.69 + command: -31.0 + } + calibration { + speed: 2.2 + acceleration: -4.17 + command: -30.0 + } + calibration { + speed: 2.2 + acceleration: -3.38 + command: -29.0 + } + calibration { + speed: 2.2 + acceleration: -2.76 + command: -28.0 + } + calibration { + speed: 2.2 + acceleration: -2.44 + command: -27.0 + } + calibration { + speed: 2.2 + acceleration: -1.76 + command: -26.0 + } + calibration { + speed: 2.2 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 2.2 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 2.2 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 2.2 + acceleration: -0.23 + command: -20.0 + } + calibration { + speed: 2.2 + acceleration: -0.12 + command: -4.33333333333 + } + calibration { + speed: 2.2 + acceleration: -0.06 + command: -17.0 + } + calibration { + speed: 2.2 + acceleration: 0.94 + command: 22.0 + } + calibration { + speed: 2.2 + acceleration: 1.89 + command: 25.0 + } + calibration { + speed: 2.2 + acceleration: 2.38 + command: 27.0 + } + calibration { + speed: 2.2 + acceleration: 2.7 + command: 30.0 + } + calibration { + speed: 2.2 + acceleration: 3.1 + command: 60.0 + } + calibration { + speed: 2.2 + acceleration: 3.13 + command: 35.0 + } + calibration { + speed: 2.2 + acceleration: 3.22 + command: 75.0 + } + calibration { + speed: 2.2 + acceleration: 3.26 + command: 45.0 + } + calibration { + speed: 2.2 + acceleration: 3.28 + command: 65.0 + } + calibration { + speed: 2.2 + acceleration: 3.29 + command: 50.0 + } + calibration { + speed: 2.2 + acceleration: 3.3 + command: 47.5 + } + calibration { + speed: 2.4 + acceleration: -8.43 + command: -33.0 + } + calibration { + speed: 2.4 + acceleration: -5.25 + command: -32.0 + } + calibration { + speed: 2.4 + acceleration: -4.71 + command: -31.0 + } + calibration { + speed: 2.4 + acceleration: -4.17 + command: -30.0 + } + calibration { + speed: 2.4 + acceleration: -3.37 + command: -29.0 + } + calibration { + speed: 2.4 + acceleration: -2.77 + command: -28.0 + } + calibration { + speed: 2.4 + acceleration: -2.45 + command: -27.0 + } + calibration { + speed: 2.4 + acceleration: -1.77 + command: -26.0 + } + calibration { + speed: 2.4 + acceleration: -1.26 + command: -25.0 + } + calibration { + speed: 2.4 + acceleration: -0.89 + command: -24.0 + } + calibration { + speed: 2.4 + acceleration: -0.6 + command: -23.0 + } + calibration { + speed: 2.4 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 2.4 + acceleration: -0.15 + command: -13.0 + } + calibration { + speed: 2.4 + acceleration: -0.13 + command: -15.0 + } + calibration { + speed: 2.4 + acceleration: -0.12 + command: 15.0 + } + calibration { + speed: 2.4 + acceleration: -0.07 + command: -17.0 + } + calibration { + speed: 2.4 + acceleration: 0.88 + command: 22.0 + } + calibration { + speed: 2.4 + acceleration: 1.8 + command: 25.0 + } + calibration { + speed: 2.4 + acceleration: 2.33 + command: 27.0 + } + calibration { + speed: 2.4 + acceleration: 2.7 + command: 30.0 + } + calibration { + speed: 2.4 + acceleration: 3.15 + command: 35.0 + } + calibration { + speed: 2.4 + acceleration: 3.17 + command: 60.0 + } + calibration { + speed: 2.4 + acceleration: 3.27 + command: 75.0 + } + calibration { + speed: 2.4 + acceleration: 3.28 + command: 75.0 + } + calibration { + speed: 2.4 + acceleration: 3.31 + command: 50.0 + } + calibration { + speed: 2.4 + acceleration: 3.32 + command: 55.0 + } + calibration { + speed: 2.4 + acceleration: 3.33 + command: 40.0 + } + calibration { + speed: 2.4 + acceleration: 3.36 + command: 55.0 + } + calibration { + speed: 2.6 + acceleration: -8.39 + command: -33.0 + } + calibration { + speed: 2.6 + acceleration: -5.31 + command: -32.0 + } + calibration { + speed: 2.6 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 2.6 + acceleration: -4.15 + command: -30.0 + } + calibration { + speed: 2.6 + acceleration: -3.36 + command: -29.0 + } + calibration { + speed: 2.6 + acceleration: -2.77 + command: -28.0 + } + calibration { + speed: 2.6 + acceleration: -2.43 + command: -27.0 + } + calibration { + speed: 2.6 + acceleration: -1.79 + command: -26.0 + } + calibration { + speed: 2.6 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 2.6 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 2.6 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 2.6 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 2.6 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 2.6 + acceleration: -0.14 + command: -15.0 + } + calibration { + speed: 2.6 + acceleration: -0.13 + command: 15.0 + } + calibration { + speed: 2.6 + acceleration: -0.08 + command: -17.0 + } + calibration { + speed: 2.6 + acceleration: 0.75 + command: 22.0 + } + calibration { + speed: 2.6 + acceleration: 1.71 + command: 25.0 + } + calibration { + speed: 2.6 + acceleration: 2.26 + command: 27.0 + } + calibration { + speed: 2.6 + acceleration: 2.71 + command: 30.0 + } + calibration { + speed: 2.6 + acceleration: 3.17 + command: 35.0 + } + calibration { + speed: 2.6 + acceleration: 3.25 + command: 60.0 + } + calibration { + speed: 2.6 + acceleration: 3.31 + command: 50.0 + } + calibration { + speed: 2.6 + acceleration: 3.32 + command: 75.0 + } + calibration { + speed: 2.6 + acceleration: 3.33 + command: 80.0 + } + calibration { + speed: 2.6 + acceleration: 3.34 + command: 70.0 + } + calibration { + speed: 2.6 + acceleration: 3.35 + command: 40.0 + } + calibration { + speed: 2.6 + acceleration: 3.36 + command: 45.0 + } + calibration { + speed: 2.6 + acceleration: 3.38 + command: 65.0 + } + calibration { + speed: 2.6 + acceleration: 3.41 + command: 55.0 + } + calibration { + speed: 2.8 + acceleration: -8.39 + command: -33.0 + } + calibration { + speed: 2.8 + acceleration: -5.33 + command: -32.0 + } + calibration { + speed: 2.8 + acceleration: -4.7 + command: -31.0 + } + calibration { + speed: 2.8 + acceleration: -4.13 + command: -30.0 + } + calibration { + speed: 2.8 + acceleration: -3.38 + command: -29.0 + } + calibration { + speed: 2.8 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 2.8 + acceleration: -2.38 + command: -27.0 + } + calibration { + speed: 2.8 + acceleration: -1.8 + command: -26.0 + } + calibration { + speed: 2.8 + acceleration: -1.29 + command: -25.0 + } + calibration { + speed: 2.8 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 2.8 + acceleration: -0.58 + command: -23.0 + } + calibration { + speed: 2.8 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 2.8 + acceleration: -0.17 + command: -13.0 + } + calibration { + speed: 2.8 + acceleration: -0.13 + command: 0.0 + } + calibration { + speed: 2.8 + acceleration: -0.09 + command: -17.0 + } + calibration { + speed: 2.8 + acceleration: 0.02 + command: 17.0 + } + calibration { + speed: 2.8 + acceleration: 0.69 + command: 22.0 + } + calibration { + speed: 2.8 + acceleration: 1.61 + command: 25.0 + } + calibration { + speed: 2.8 + acceleration: 2.19 + command: 27.0 + } + calibration { + speed: 2.8 + acceleration: 2.71 + command: 30.0 + } + calibration { + speed: 2.8 + acceleration: 3.19 + command: 35.0 + } + calibration { + speed: 2.8 + acceleration: 3.31 + command: 50.0 + } + calibration { + speed: 2.8 + acceleration: 3.33 + command: 60.0 + } + calibration { + speed: 2.8 + acceleration: 3.36 + command: 40.0 + } + calibration { + speed: 2.8 + acceleration: 3.37 + command: 77.5 + } + calibration { + speed: 2.8 + acceleration: 3.38 + command: 45.0 + } + calibration { + speed: 2.8 + acceleration: 3.4 + command: 70.0 + } + calibration { + speed: 2.8 + acceleration: 3.43 + command: 65.0 + } + calibration { + speed: 2.8 + acceleration: 3.46 + command: 55.0 + } + calibration { + speed: 3.0 + acceleration: -8.42 + command: -33.0 + } + calibration { + speed: 3.0 + acceleration: -5.32 + command: -32.0 + } + calibration { + speed: 3.0 + acceleration: -4.67 + command: -31.0 + } + calibration { + speed: 3.0 + acceleration: -4.11 + command: -30.0 + } + calibration { + speed: 3.0 + acceleration: -3.39 + command: -29.0 + } + calibration { + speed: 3.0 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 3.0 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 3.0 + acceleration: -1.83 + command: -26.0 + } + calibration { + speed: 3.0 + acceleration: -1.26 + command: -25.0 + } + calibration { + speed: 3.0 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 3.0 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 3.0 + acceleration: -0.26 + command: -20.0 + } + calibration { + speed: 3.0 + acceleration: -0.15 + command: -14.0 + } + calibration { + speed: 3.0 + acceleration: -0.14 + command: 15.0 + } + calibration { + speed: 3.0 + acceleration: -0.11 + command: -17.0 + } + calibration { + speed: 3.0 + acceleration: -0.05 + command: 17.0 + } + calibration { + speed: 3.0 + acceleration: 0.59 + command: 22.0 + } + calibration { + speed: 3.0 + acceleration: 1.52 + command: 25.0 + } + calibration { + speed: 3.0 + acceleration: 2.13 + command: 27.0 + } + calibration { + speed: 3.0 + acceleration: 2.71 + command: 30.0 + } + calibration { + speed: 3.0 + acceleration: 3.21 + command: 35.0 + } + calibration { + speed: 3.0 + acceleration: 3.3 + command: 50.0 + } + calibration { + speed: 3.0 + acceleration: 3.37 + command: 42.5 + } + calibration { + speed: 3.0 + acceleration: 3.39 + command: 60.0 + } + calibration { + speed: 3.0 + acceleration: 3.41 + command: 77.5 + } + calibration { + speed: 3.0 + acceleration: 3.45 + command: 70.0 + } + calibration { + speed: 3.0 + acceleration: 3.46 + command: 65.0 + } + calibration { + speed: 3.0 + acceleration: 3.5 + command: 55.0 + } + calibration { + speed: 3.2 + acceleration: -8.47 + command: -33.0 + } + calibration { + speed: 3.2 + acceleration: -5.29 + command: -32.0 + } + calibration { + speed: 3.2 + acceleration: -4.66 + command: -31.0 + } + calibration { + speed: 3.2 + acceleration: -4.11 + command: -30.0 + } + calibration { + speed: 3.2 + acceleration: -3.4 + command: -29.0 + } + calibration { + speed: 3.2 + acceleration: -2.83 + command: -28.0 + } + calibration { + speed: 3.2 + acceleration: -2.29 + command: -27.0 + } + calibration { + speed: 3.2 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 3.2 + acceleration: -1.25 + command: -25.0 + } + calibration { + speed: 3.2 + acceleration: -0.84 + command: -24.0 + } + calibration { + speed: 3.2 + acceleration: -0.51 + command: -23.0 + } + calibration { + speed: 3.2 + acceleration: -0.22 + command: -20.0 + } + calibration { + speed: 3.2 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 3.2 + acceleration: -0.15 + command: -15.0 + } + calibration { + speed: 3.2 + acceleration: -0.14 + command: -13.0 + } + calibration { + speed: 3.2 + acceleration: -0.13 + command: -17.0 + } + calibration { + speed: 3.2 + acceleration: -0.03 + command: 17.0 + } + calibration { + speed: 3.2 + acceleration: 0.52 + command: 22.0 + } + calibration { + speed: 3.2 + acceleration: 1.44 + command: 25.0 + } + calibration { + speed: 3.2 + acceleration: 2.05 + command: 27.0 + } + calibration { + speed: 3.2 + acceleration: 2.69 + command: 30.0 + } + calibration { + speed: 3.2 + acceleration: 3.22 + command: 35.0 + } + calibration { + speed: 3.2 + acceleration: 3.3 + command: 50.0 + } + calibration { + speed: 3.2 + acceleration: 3.34 + command: 45.0 + } + calibration { + speed: 3.2 + acceleration: 3.39 + command: 40.0 + } + calibration { + speed: 3.2 + acceleration: 3.42 + command: 80.0 + } + calibration { + speed: 3.2 + acceleration: 3.43 + command: 67.5 + } + calibration { + speed: 3.2 + acceleration: 3.49 + command: 67.5 + } + calibration { + speed: 3.2 + acceleration: 3.51 + command: 55.0 + } + calibration { + speed: 3.4 + acceleration: -8.55 + command: -33.0 + } + calibration { + speed: 3.4 + acceleration: -5.26 + command: -32.0 + } + calibration { + speed: 3.4 + acceleration: -4.65 + command: -31.0 + } + calibration { + speed: 3.4 + acceleration: -4.12 + command: -30.0 + } + calibration { + speed: 3.4 + acceleration: -3.41 + command: -29.0 + } + calibration { + speed: 3.4 + acceleration: -2.83 + command: -28.0 + } + calibration { + speed: 3.4 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 3.4 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 3.4 + acceleration: -1.28 + command: -25.0 + } + calibration { + speed: 3.4 + acceleration: -0.85 + command: -24.0 + } + calibration { + speed: 3.4 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 3.4 + acceleration: -0.21 + command: -20.0 + } + calibration { + speed: 3.4 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 3.4 + acceleration: -0.14 + command: -5.0 + } + calibration { + speed: 3.4 + acceleration: -0.05 + command: 17.0 + } + calibration { + speed: 3.4 + acceleration: 0.49 + command: 22.0 + } + calibration { + speed: 3.4 + acceleration: 1.35 + command: 25.0 + } + calibration { + speed: 3.4 + acceleration: 1.96 + command: 27.0 + } + calibration { + speed: 3.4 + acceleration: 2.65 + command: 30.0 + } + calibration { + speed: 3.4 + acceleration: 3.23 + command: 35.0 + } + calibration { + speed: 3.4 + acceleration: 3.31 + command: 50.0 + } + calibration { + speed: 3.4 + acceleration: 3.33 + command: 45.0 + } + calibration { + speed: 3.4 + acceleration: 3.42 + command: 60.0 + } + calibration { + speed: 3.4 + acceleration: 3.43 + command: 75.0 + } + calibration { + speed: 3.4 + acceleration: 3.45 + command: 60.0 + } + calibration { + speed: 3.4 + acceleration: 3.49 + command: 65.0 + } + calibration { + speed: 3.4 + acceleration: 3.5 + command: 70.0 + } + calibration { + speed: 3.4 + acceleration: 3.51 + command: 55.0 + } + calibration { + speed: 3.6 + acceleration: -8.6 + command: -33.0 + } + calibration { + speed: 3.6 + acceleration: -5.21 + command: -32.0 + } + calibration { + speed: 3.6 + acceleration: -4.66 + command: -31.0 + } + calibration { + speed: 3.6 + acceleration: -4.13 + command: -30.0 + } + calibration { + speed: 3.6 + acceleration: -3.41 + command: -29.0 + } + calibration { + speed: 3.6 + acceleration: -2.81 + command: -28.0 + } + calibration { + speed: 3.6 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 3.6 + acceleration: -1.84 + command: -26.0 + } + calibration { + speed: 3.6 + acceleration: -1.25 + command: -25.0 + } + calibration { + speed: 3.6 + acceleration: -0.84 + command: -24.0 + } + calibration { + speed: 3.6 + acceleration: -0.55 + command: -23.0 + } + calibration { + speed: 3.6 + acceleration: -0.21 + command: -20.0 + } + calibration { + speed: 3.6 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 3.6 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 3.6 + acceleration: -0.15 + command: -14.0 + } + calibration { + speed: 3.6 + acceleration: -0.06 + command: 17.0 + } + calibration { + speed: 3.6 + acceleration: 0.45 + command: 22.0 + } + calibration { + speed: 3.6 + acceleration: 1.25 + command: 25.0 + } + calibration { + speed: 3.6 + acceleration: 1.84 + command: 27.0 + } + calibration { + speed: 3.6 + acceleration: 2.58 + command: 30.0 + } + calibration { + speed: 3.6 + acceleration: 3.21 + command: 35.0 + } + calibration { + speed: 3.6 + acceleration: 3.32 + command: 45.0 + } + calibration { + speed: 3.6 + acceleration: 3.33 + command: 50.0 + } + calibration { + speed: 3.6 + acceleration: 3.4 + command: 75.0 + } + calibration { + speed: 3.6 + acceleration: 3.41 + command: 80.0 + } + calibration { + speed: 3.6 + acceleration: 3.44 + command: 60.0 + } + calibration { + speed: 3.6 + acceleration: 3.45 + command: 40.0 + } + calibration { + speed: 3.6 + acceleration: 3.49 + command: 67.5 + } + calibration { + speed: 3.6 + acceleration: 3.5 + command: 55.0 + } + calibration { + speed: 3.8 + acceleration: -8.65 + command: -33.0 + } + calibration { + speed: 3.8 + acceleration: -5.18 + command: -32.0 + } + calibration { + speed: 3.8 + acceleration: -4.68 + command: -31.0 + } + calibration { + speed: 3.8 + acceleration: -4.15 + command: -30.0 + } + calibration { + speed: 3.8 + acceleration: -3.4 + command: -29.0 + } + calibration { + speed: 3.8 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 3.8 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 3.8 + acceleration: -1.83 + command: -26.0 + } + calibration { + speed: 3.8 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 3.8 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 3.8 + acceleration: -0.54 + command: -23.0 + } + calibration { + speed: 3.8 + acceleration: -0.24 + command: -20.0 + } + calibration { + speed: 3.8 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 3.8 + acceleration: -0.16 + command: 0.0 + } + calibration { + speed: 3.8 + acceleration: -0.15 + command: -13.0 + } + calibration { + speed: 3.8 + acceleration: -0.03 + command: 17.0 + } + calibration { + speed: 3.8 + acceleration: 0.44 + command: 22.0 + } + calibration { + speed: 3.8 + acceleration: 1.17 + command: 25.0 + } + calibration { + speed: 3.8 + acceleration: 1.71 + command: 27.0 + } + calibration { + speed: 3.8 + acceleration: 2.5 + command: 30.0 + } + calibration { + speed: 3.8 + acceleration: 3.15 + command: 35.0 + } + calibration { + speed: 3.8 + acceleration: 3.34 + command: 45.0 + } + calibration { + speed: 3.8 + acceleration: 3.36 + command: 62.5 + } + calibration { + speed: 3.8 + acceleration: 3.4 + command: 80.0 + } + calibration { + speed: 3.8 + acceleration: 3.41 + command: 60.0 + } + calibration { + speed: 3.8 + acceleration: 3.46 + command: 40.0 + } + calibration { + speed: 3.8 + acceleration: 3.47 + command: 65.0 + } + calibration { + speed: 3.8 + acceleration: 3.48 + command: 70.0 + } + calibration { + speed: 3.8 + acceleration: 3.49 + command: 55.0 + } + calibration { + speed: 4.0 + acceleration: -8.69 + command: -33.0 + } + calibration { + speed: 4.0 + acceleration: -5.17 + command: -32.0 + } + calibration { + speed: 4.0 + acceleration: -4.69 + command: -31.0 + } + calibration { + speed: 4.0 + acceleration: -4.15 + command: -30.0 + } + calibration { + speed: 4.0 + acceleration: -3.37 + command: -29.0 + } + calibration { + speed: 4.0 + acceleration: -2.76 + command: -28.0 + } + calibration { + speed: 4.0 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 4.0 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 4.0 + acceleration: -1.29 + command: -25.0 + } + calibration { + speed: 4.0 + acceleration: -0.85 + command: -24.0 + } + calibration { + speed: 4.0 + acceleration: -0.54 + command: -23.0 + } + calibration { + speed: 4.0 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 4.0 + acceleration: -0.2 + command: -15.0 + } + calibration { + speed: 4.0 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 4.0 + acceleration: -0.17 + command: -13.0 + } + calibration { + speed: 4.0 + acceleration: -0.16 + command: -17.0 + } + calibration { + speed: 4.0 + acceleration: -0.05 + command: 17.0 + } + calibration { + speed: 4.0 + acceleration: 0.4 + command: 22.0 + } + calibration { + speed: 4.0 + acceleration: 1.08 + command: 25.0 + } + calibration { + speed: 4.0 + acceleration: 1.63 + command: 27.0 + } + calibration { + speed: 4.0 + acceleration: 2.38 + command: 30.0 + } + calibration { + speed: 4.0 + acceleration: 3.11 + command: 35.0 + } + calibration { + speed: 4.0 + acceleration: 3.35 + command: 75.0 + } + calibration { + speed: 4.0 + acceleration: 3.37 + command: 45.0 + } + calibration { + speed: 4.0 + acceleration: 3.39 + command: 55.0 + } + calibration { + speed: 4.0 + acceleration: 3.4 + command: 80.0 + } + calibration { + speed: 4.0 + acceleration: 3.46 + command: 40.0 + } + calibration { + speed: 4.0 + acceleration: 3.47 + command: 65.0 + } + calibration { + speed: 4.0 + acceleration: 3.48 + command: 62.5 + } + calibration { + speed: 4.2 + acceleration: -8.72 + command: -33.0 + } + calibration { + speed: 4.2 + acceleration: -5.18 + command: -32.0 + } + calibration { + speed: 4.2 + acceleration: -4.7 + command: -31.0 + } + calibration { + speed: 4.2 + acceleration: -4.14 + command: -30.0 + } + calibration { + speed: 4.2 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 4.2 + acceleration: -2.76 + command: -28.0 + } + calibration { + speed: 4.2 + acceleration: -2.32 + command: -27.0 + } + calibration { + speed: 4.2 + acceleration: -1.87 + command: -26.0 + } + calibration { + speed: 4.2 + acceleration: -1.3 + command: -25.0 + } + calibration { + speed: 4.2 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 4.2 + acceleration: -0.54 + command: -23.0 + } + calibration { + speed: 4.2 + acceleration: -0.23 + command: -20.0 + } + calibration { + speed: 4.2 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 4.2 + acceleration: -0.2 + command: -15.0 + } + calibration { + speed: 4.2 + acceleration: -0.17 + command: 15.0 + } + calibration { + speed: 4.2 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 4.2 + acceleration: -0.05 + command: 17.0 + } + calibration { + speed: 4.2 + acceleration: 0.39 + command: 22.0 + } + calibration { + speed: 4.2 + acceleration: 0.97 + command: 25.0 + } + calibration { + speed: 4.2 + acceleration: 1.52 + command: 27.0 + } + calibration { + speed: 4.2 + acceleration: 2.27 + command: 30.0 + } + calibration { + speed: 4.2 + acceleration: 3.03 + command: 35.0 + } + calibration { + speed: 4.2 + acceleration: 3.36 + command: 75.0 + } + calibration { + speed: 4.2 + acceleration: 3.38 + command: 60.0 + } + calibration { + speed: 4.2 + acceleration: 3.39 + command: 45.0 + } + calibration { + speed: 4.2 + acceleration: 3.41 + command: 80.0 + } + calibration { + speed: 4.2 + acceleration: 3.43 + command: 40.0 + } + calibration { + speed: 4.2 + acceleration: 3.44 + command: 50.0 + } + calibration { + speed: 4.2 + acceleration: 3.47 + command: 65.0 + } + calibration { + speed: 4.2 + acceleration: 3.48 + command: 70.0 + } + calibration { + speed: 4.2 + acceleration: 3.49 + command: 55.0 + } + calibration { + speed: 4.4 + acceleration: -8.74 + command: -33.0 + } + calibration { + speed: 4.4 + acceleration: -5.19 + command: -32.0 + } + calibration { + speed: 4.4 + acceleration: -4.69 + command: -31.0 + } + calibration { + speed: 4.4 + acceleration: -4.11 + command: -30.0 + } + calibration { + speed: 4.4 + acceleration: -3.31 + command: -29.0 + } + calibration { + speed: 4.4 + acceleration: -2.78 + command: -28.0 + } + calibration { + speed: 4.4 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 4.4 + acceleration: -1.88 + command: -26.0 + } + calibration { + speed: 4.4 + acceleration: -1.29 + command: -25.0 + } + calibration { + speed: 4.4 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 4.4 + acceleration: -0.54 + command: -23.0 + } + calibration { + speed: 4.4 + acceleration: -0.22 + command: -20.0 + } + calibration { + speed: 4.4 + acceleration: -0.2 + command: -17.0 + } + calibration { + speed: 4.4 + acceleration: -0.19 + command: 0.0 + } + calibration { + speed: 4.4 + acceleration: -0.15 + command: -13.0 + } + calibration { + speed: 4.4 + acceleration: -0.06 + command: 17.0 + } + calibration { + speed: 4.4 + acceleration: 0.36 + command: 22.0 + } + calibration { + speed: 4.4 + acceleration: 0.89 + command: 25.0 + } + calibration { + speed: 4.4 + acceleration: 1.41 + command: 27.0 + } + calibration { + speed: 4.4 + acceleration: 2.13 + command: 30.0 + } + calibration { + speed: 4.4 + acceleration: 2.97 + command: 35.0 + } + calibration { + speed: 4.4 + acceleration: 3.39 + command: 40.0 + } + calibration { + speed: 4.4 + acceleration: 3.4 + command: 60.0 + } + calibration { + speed: 4.4 + acceleration: 3.43 + command: 80.0 + } + calibration { + speed: 4.4 + acceleration: 3.47 + command: 57.5 + } + calibration { + speed: 4.4 + acceleration: 3.48 + command: 70.0 + } + calibration { + speed: 4.4 + acceleration: 3.5 + command: 55.0 + } + calibration { + speed: 4.6 + acceleration: -8.75 + command: -33.0 + } + calibration { + speed: 4.6 + acceleration: -5.22 + command: -32.0 + } + calibration { + speed: 4.6 + acceleration: -4.67 + command: -31.0 + } + calibration { + speed: 4.6 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 4.6 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 4.6 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 4.6 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 4.6 + acceleration: -1.87 + command: -26.0 + } + calibration { + speed: 4.6 + acceleration: -1.29 + command: -25.0 + } + calibration { + speed: 4.6 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 4.6 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 4.6 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 4.6 + acceleration: -0.21 + command: -15.0 + } + calibration { + speed: 4.6 + acceleration: -0.19 + command: -17.0 + } + calibration { + speed: 4.6 + acceleration: -0.16 + command: 1.0 + } + calibration { + speed: 4.6 + acceleration: -0.08 + command: 17.0 + } + calibration { + speed: 4.6 + acceleration: 0.32 + command: 22.0 + } + calibration { + speed: 4.6 + acceleration: 0.81 + command: 25.0 + } + calibration { + speed: 4.6 + acceleration: 1.29 + command: 27.0 + } + calibration { + speed: 4.6 + acceleration: 1.98 + command: 30.0 + } + calibration { + speed: 4.6 + acceleration: 2.87 + command: 35.0 + } + calibration { + speed: 4.6 + acceleration: 3.35 + command: 40.0 + } + calibration { + speed: 4.6 + acceleration: 3.39 + command: 45.0 + } + calibration { + speed: 4.6 + acceleration: 3.43 + command: 60.0 + } + calibration { + speed: 4.6 + acceleration: 3.46 + command: 80.0 + } + calibration { + speed: 4.6 + acceleration: 3.48 + command: 70.0 + } + calibration { + speed: 4.6 + acceleration: 3.5 + command: 50.0 + } + calibration { + speed: 4.6 + acceleration: 3.51 + command: 55.0 + } + calibration { + speed: 4.8 + acceleration: -8.76 + command: -33.0 + } + calibration { + speed: 4.8 + acceleration: -5.23 + command: -32.0 + } + calibration { + speed: 4.8 + acceleration: -4.64 + command: -31.0 + } + calibration { + speed: 4.8 + acceleration: -4.02 + command: -30.0 + } + calibration { + speed: 4.8 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 4.8 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 4.8 + acceleration: -2.32 + command: -27.0 + } + calibration { + speed: 4.8 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 4.8 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 4.8 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 4.8 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 4.8 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 4.8 + acceleration: -0.22 + command: -16.0 + } + calibration { + speed: 4.8 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 4.8 + acceleration: -0.15 + command: -13.0 + } + calibration { + speed: 4.8 + acceleration: -0.09 + command: 17.0 + } + calibration { + speed: 4.8 + acceleration: 0.34 + command: 22.0 + } + calibration { + speed: 4.8 + acceleration: 0.71 + command: 25.0 + } + calibration { + speed: 4.8 + acceleration: 1.17 + command: 27.0 + } + calibration { + speed: 4.8 + acceleration: 1.82 + command: 30.0 + } + calibration { + speed: 4.8 + acceleration: 2.8 + command: 35.0 + } + calibration { + speed: 4.8 + acceleration: 3.3 + command: 40.0 + } + calibration { + speed: 4.8 + acceleration: 3.37 + command: 45.0 + } + calibration { + speed: 4.8 + acceleration: 3.46 + command: 60.0 + } + calibration { + speed: 4.8 + acceleration: 3.48 + command: 70.0 + } + calibration { + speed: 4.8 + acceleration: 3.49 + command: 72.5 + } + calibration { + speed: 4.8 + acceleration: 3.51 + command: 52.5 + } + calibration { + speed: 4.8 + acceleration: 3.54 + command: 75.0 + } + calibration { + speed: 5.0 + acceleration: -8.77 + command: -33.0 + } + calibration { + speed: 5.0 + acceleration: -5.24 + command: -32.0 + } + calibration { + speed: 5.0 + acceleration: -4.6 + command: -31.0 + } + calibration { + speed: 5.0 + acceleration: -3.98 + command: -30.0 + } + calibration { + speed: 5.0 + acceleration: -3.31 + command: -29.0 + } + calibration { + speed: 5.0 + acceleration: -2.81 + command: -28.0 + } + calibration { + speed: 5.0 + acceleration: -2.32 + command: -27.0 + } + calibration { + speed: 5.0 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 5.0 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 5.0 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 5.0 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 5.0 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 5.0 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 5.0 + acceleration: -0.19 + command: -17.0 + } + calibration { + speed: 5.0 + acceleration: -0.17 + command: 1.0 + } + calibration { + speed: 5.0 + acceleration: -0.07 + command: 17.0 + } + calibration { + speed: 5.0 + acceleration: 0.32 + command: 22.0 + } + calibration { + speed: 5.0 + acceleration: 0.65 + command: 25.0 + } + calibration { + speed: 5.0 + acceleration: 1.08 + command: 27.0 + } + calibration { + speed: 5.0 + acceleration: 1.69 + command: 30.0 + } + calibration { + speed: 5.0 + acceleration: 2.68 + command: 35.0 + } + calibration { + speed: 5.0 + acceleration: 3.25 + command: 40.0 + } + calibration { + speed: 5.0 + acceleration: 3.34 + command: 45.0 + } + calibration { + speed: 5.0 + acceleration: 3.48 + command: 70.0 + } + calibration { + speed: 5.0 + acceleration: 3.49 + command: 60.0 + } + calibration { + speed: 5.0 + acceleration: 3.5 + command: 57.5 + } + calibration { + speed: 5.0 + acceleration: 3.52 + command: 67.5 + } + calibration { + speed: 5.0 + acceleration: 3.59 + command: 75.0 + } + calibration { + speed: 5.2 + acceleration: -8.78 + command: -33.0 + } + calibration { + speed: 5.2 + acceleration: -5.22 + command: -32.0 + } + calibration { + speed: 5.2 + acceleration: -4.55 + command: -31.0 + } + calibration { + speed: 5.2 + acceleration: -3.96 + command: -30.0 + } + calibration { + speed: 5.2 + acceleration: -3.31 + command: -29.0 + } + calibration { + speed: 5.2 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 5.2 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 5.2 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 5.2 + acceleration: -1.3 + command: -25.0 + } + calibration { + speed: 5.2 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 5.2 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 5.2 + acceleration: -0.27 + command: -20.0 + } + calibration { + speed: 5.2 + acceleration: -0.2 + command: -15.0 + } + calibration { + speed: 5.2 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 5.2 + acceleration: -0.16 + command: -17.0 + } + calibration { + speed: 5.2 + acceleration: -0.14 + command: 15.0 + } + calibration { + speed: 5.2 + acceleration: -0.11 + command: 17.0 + } + calibration { + speed: 5.2 + acceleration: 0.32 + command: 22.0 + } + calibration { + speed: 5.2 + acceleration: 0.59 + command: 25.0 + } + calibration { + speed: 5.2 + acceleration: 1.0 + command: 27.0 + } + calibration { + speed: 5.2 + acceleration: 1.59 + command: 30.0 + } + calibration { + speed: 5.2 + acceleration: 2.57 + command: 35.0 + } + calibration { + speed: 5.2 + acceleration: 3.19 + command: 40.0 + } + calibration { + speed: 5.2 + acceleration: 3.3 + command: 45.0 + } + calibration { + speed: 5.2 + acceleration: 3.47 + command: 50.0 + } + calibration { + speed: 5.2 + acceleration: 3.49 + command: 70.0 + } + calibration { + speed: 5.2 + acceleration: 3.51 + command: 62.5 + } + calibration { + speed: 5.2 + acceleration: 3.53 + command: 55.0 + } + calibration { + speed: 5.2 + acceleration: 3.54 + command: 80.0 + } + calibration { + speed: 5.2 + acceleration: 3.59 + command: 75.0 + } + calibration { + speed: 5.4 + acceleration: -8.78 + command: -33.0 + } + calibration { + speed: 5.4 + acceleration: -5.2 + command: -32.0 + } + calibration { + speed: 5.4 + acceleration: -4.52 + command: -31.0 + } + calibration { + speed: 5.4 + acceleration: -3.96 + command: -30.0 + } + calibration { + speed: 5.4 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 5.4 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 5.4 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 5.4 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 5.4 + acceleration: -1.3 + command: -25.0 + } + calibration { + speed: 5.4 + acceleration: -0.89 + command: -24.0 + } + calibration { + speed: 5.4 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 5.4 + acceleration: -0.26 + command: -20.0 + } + calibration { + speed: 5.4 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 5.4 + acceleration: -0.2 + command: -17.0 + } + calibration { + speed: 5.4 + acceleration: -0.17 + command: 1.0 + } + calibration { + speed: 5.4 + acceleration: -0.09 + command: 17.0 + } + calibration { + speed: 5.4 + acceleration: 0.28 + command: 22.0 + } + calibration { + speed: 5.4 + acceleration: 0.59 + command: 25.0 + } + calibration { + speed: 5.4 + acceleration: 0.95 + command: 27.0 + } + calibration { + speed: 5.4 + acceleration: 1.5 + command: 30.0 + } + calibration { + speed: 5.4 + acceleration: 2.49 + command: 35.0 + } + calibration { + speed: 5.4 + acceleration: 3.13 + command: 40.0 + } + calibration { + speed: 5.4 + acceleration: 3.26 + command: 45.0 + } + calibration { + speed: 5.4 + acceleration: 3.45 + command: 50.0 + } + calibration { + speed: 5.4 + acceleration: 3.5 + command: 70.0 + } + calibration { + speed: 5.4 + acceleration: 3.52 + command: 62.5 + } + calibration { + speed: 5.4 + acceleration: 3.53 + command: 55.0 + } + calibration { + speed: 5.4 + acceleration: 3.56 + command: 80.0 + } + calibration { + speed: 5.4 + acceleration: 3.58 + command: 75.0 + } + calibration { + speed: 5.6 + acceleration: -8.78 + command: -33.0 + } + calibration { + speed: 5.6 + acceleration: -5.15 + command: -32.0 + } + calibration { + speed: 5.6 + acceleration: -4.5 + command: -31.0 + } + calibration { + speed: 5.6 + acceleration: -3.96 + command: -30.0 + } + calibration { + speed: 5.6 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 5.6 + acceleration: -2.78 + command: -28.0 + } + calibration { + speed: 5.6 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 5.6 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 5.6 + acceleration: -1.3 + command: -25.0 + } + calibration { + speed: 5.6 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 5.6 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 5.6 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 5.6 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 5.6 + acceleration: -0.2 + command: -17.0 + } + calibration { + speed: 5.6 + acceleration: -0.17 + command: 1.0 + } + calibration { + speed: 5.6 + acceleration: -0.13 + command: 17.0 + } + calibration { + speed: 5.6 + acceleration: 0.27 + command: 22.0 + } + calibration { + speed: 5.6 + acceleration: 0.55 + command: 25.0 + } + calibration { + speed: 5.6 + acceleration: 0.91 + command: 27.0 + } + calibration { + speed: 5.6 + acceleration: 1.41 + command: 30.0 + } + calibration { + speed: 5.6 + acceleration: 2.42 + command: 35.0 + } + calibration { + speed: 5.6 + acceleration: 3.07 + command: 40.0 + } + calibration { + speed: 5.6 + acceleration: 3.22 + command: 45.0 + } + calibration { + speed: 5.6 + acceleration: 3.41 + command: 50.0 + } + calibration { + speed: 5.6 + acceleration: 3.52 + command: 70.0 + } + calibration { + speed: 5.6 + acceleration: 3.53 + command: 60.0 + } + calibration { + speed: 5.6 + acceleration: 3.54 + command: 60.0 + } + calibration { + speed: 5.6 + acceleration: 3.56 + command: 75.0 + } + calibration { + speed: 5.6 + acceleration: 3.58 + command: 80.0 + } + calibration { + speed: 5.8 + acceleration: -8.78 + command: -33.0 + } + calibration { + speed: 5.8 + acceleration: -5.11 + command: -32.0 + } + calibration { + speed: 5.8 + acceleration: -4.5 + command: -31.0 + } + calibration { + speed: 5.8 + acceleration: -3.98 + command: -30.0 + } + calibration { + speed: 5.8 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 5.8 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 5.8 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 5.8 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 5.8 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 5.8 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 5.8 + acceleration: -0.58 + command: -23.0 + } + calibration { + speed: 5.8 + acceleration: -0.27 + command: -20.0 + } + calibration { + speed: 5.8 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 5.8 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 5.8 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 5.8 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 5.8 + acceleration: -0.12 + command: 17.0 + } + calibration { + speed: 5.8 + acceleration: 0.28 + command: 22.0 + } + calibration { + speed: 5.8 + acceleration: 0.52 + command: 25.0 + } + calibration { + speed: 5.8 + acceleration: 0.86 + command: 27.0 + } + calibration { + speed: 5.8 + acceleration: 1.35 + command: 30.0 + } + calibration { + speed: 5.8 + acceleration: 2.35 + command: 35.0 + } + calibration { + speed: 5.8 + acceleration: 3.0 + command: 40.0 + } + calibration { + speed: 5.8 + acceleration: 3.18 + command: 45.0 + } + calibration { + speed: 5.8 + acceleration: 3.38 + command: 50.0 + } + calibration { + speed: 5.8 + acceleration: 3.52 + command: 60.0 + } + calibration { + speed: 5.8 + acceleration: 3.54 + command: 55.0 + } + calibration { + speed: 5.8 + acceleration: 3.55 + command: 70.0 + } + calibration { + speed: 5.8 + acceleration: 3.6 + command: 80.0 + } + calibration { + speed: 6.0 + acceleration: -8.77 + command: -33.0 + } + calibration { + speed: 6.0 + acceleration: -5.07 + command: -32.0 + } + calibration { + speed: 6.0 + acceleration: -4.51 + command: -31.0 + } + calibration { + speed: 6.0 + acceleration: -3.98 + command: -30.0 + } + calibration { + speed: 6.0 + acceleration: -3.32 + command: -29.0 + } + calibration { + speed: 6.0 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 6.0 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 6.0 + acceleration: -1.84 + command: -26.0 + } + calibration { + speed: 6.0 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 6.0 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.0 + acceleration: -0.58 + command: -23.0 + } + calibration { + speed: 6.0 + acceleration: -0.26 + command: -20.0 + } + calibration { + speed: 6.0 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 6.0 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 6.0 + acceleration: -0.19 + command: 15.0 + } + calibration { + speed: 6.0 + acceleration: -0.14 + command: 17.0 + } + calibration { + speed: 6.0 + acceleration: 0.25 + command: 22.0 + } + calibration { + speed: 6.0 + acceleration: 0.53 + command: 25.0 + } + calibration { + speed: 6.0 + acceleration: 0.83 + command: 27.0 + } + calibration { + speed: 6.0 + acceleration: 1.3 + command: 30.0 + } + calibration { + speed: 6.0 + acceleration: 2.28 + command: 35.0 + } + calibration { + speed: 6.0 + acceleration: 2.94 + command: 40.0 + } + calibration { + speed: 6.0 + acceleration: 3.14 + command: 45.0 + } + calibration { + speed: 6.0 + acceleration: 3.34 + command: 50.0 + } + calibration { + speed: 6.0 + acceleration: 3.52 + command: 60.0 + } + calibration { + speed: 6.0 + acceleration: 3.54 + command: 55.0 + } + calibration { + speed: 6.0 + acceleration: 3.55 + command: 75.0 + } + calibration { + speed: 6.0 + acceleration: 3.56 + command: 67.5 + } + calibration { + speed: 6.0 + acceleration: 3.61 + command: 80.0 + } + calibration { + speed: 6.2 + acceleration: -8.75 + command: -33.0 + } + calibration { + speed: 6.2 + acceleration: -5.05 + command: -32.0 + } + calibration { + speed: 6.2 + acceleration: -4.52 + command: -31.0 + } + calibration { + speed: 6.2 + acceleration: -3.98 + command: -30.0 + } + calibration { + speed: 6.2 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 6.2 + acceleration: -2.81 + command: -28.0 + } + calibration { + speed: 6.2 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 6.2 + acceleration: -1.84 + command: -26.0 + } + calibration { + speed: 6.2 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 6.2 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.2 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 6.2 + acceleration: -0.32 + command: -20.0 + } + calibration { + speed: 6.2 + acceleration: -0.24 + command: -13.0 + } + calibration { + speed: 6.2 + acceleration: -0.23 + command: -16.0 + } + calibration { + speed: 6.2 + acceleration: -0.2 + command: 15.0 + } + calibration { + speed: 6.2 + acceleration: -0.13 + command: 17.0 + } + calibration { + speed: 6.2 + acceleration: 0.27 + command: 22.0 + } + calibration { + speed: 6.2 + acceleration: 0.49 + command: 25.0 + } + calibration { + speed: 6.2 + acceleration: 0.77 + command: 27.0 + } + calibration { + speed: 6.2 + acceleration: 1.24 + command: 30.0 + } + calibration { + speed: 6.2 + acceleration: 2.2 + command: 35.0 + } + calibration { + speed: 6.2 + acceleration: 2.88 + command: 40.0 + } + calibration { + speed: 6.2 + acceleration: 3.08 + command: 45.0 + } + calibration { + speed: 6.2 + acceleration: 3.29 + command: 50.0 + } + calibration { + speed: 6.2 + acceleration: 3.5 + command: 60.0 + } + calibration { + speed: 6.2 + acceleration: 3.51 + command: 55.0 + } + calibration { + speed: 6.2 + acceleration: 3.57 + command: 70.0 + } + calibration { + speed: 6.2 + acceleration: 3.61 + command: 80.0 + } + calibration { + speed: 6.4 + acceleration: -8.72 + command: -33.0 + } + calibration { + speed: 6.4 + acceleration: -5.03 + command: -32.0 + } + calibration { + speed: 6.4 + acceleration: -4.53 + command: -31.0 + } + calibration { + speed: 6.4 + acceleration: -3.98 + command: -30.0 + } + calibration { + speed: 6.4 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 6.4 + acceleration: -2.81 + command: -28.0 + } + calibration { + speed: 6.4 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 6.4 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 6.4 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 6.4 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.4 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 6.4 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 6.4 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 6.4 + acceleration: -0.22 + command: -17.0 + } + calibration { + speed: 6.4 + acceleration: -0.21 + command: -13.0 + } + calibration { + speed: 6.4 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 6.4 + acceleration: -0.14 + command: 17.0 + } + calibration { + speed: 6.4 + acceleration: 0.25 + command: 22.0 + } + calibration { + speed: 6.4 + acceleration: 0.47 + command: 25.0 + } + calibration { + speed: 6.4 + acceleration: 0.76 + command: 27.0 + } + calibration { + speed: 6.4 + acceleration: 1.19 + command: 30.0 + } + calibration { + speed: 6.4 + acceleration: 2.13 + command: 35.0 + } + calibration { + speed: 6.4 + acceleration: 2.8 + command: 40.0 + } + calibration { + speed: 6.4 + acceleration: 3.02 + command: 45.0 + } + calibration { + speed: 6.4 + acceleration: 3.24 + command: 50.0 + } + calibration { + speed: 6.4 + acceleration: 3.46 + command: 55.0 + } + calibration { + speed: 6.4 + acceleration: 3.48 + command: 60.0 + } + calibration { + speed: 6.4 + acceleration: 3.56 + command: 65.0 + } + calibration { + speed: 6.4 + acceleration: 3.57 + command: 70.0 + } + calibration { + speed: 6.4 + acceleration: 3.6 + command: 75.0 + } + calibration { + speed: 6.4 + acceleration: 3.61 + command: 80.0 + } + calibration { + speed: 6.6 + acceleration: -8.69 + command: -33.0 + } + calibration { + speed: 6.6 + acceleration: -5.03 + command: -32.0 + } + calibration { + speed: 6.6 + acceleration: -4.55 + command: -31.0 + } + calibration { + speed: 6.6 + acceleration: -3.97 + command: -30.0 + } + calibration { + speed: 6.6 + acceleration: -3.32 + command: -29.0 + } + calibration { + speed: 6.6 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 6.6 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 6.6 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 6.6 + acceleration: -1.33 + command: -25.0 + } + calibration { + speed: 6.6 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.6 + acceleration: -0.58 + command: -23.0 + } + calibration { + speed: 6.6 + acceleration: -0.28 + command: -20.0 + } + calibration { + speed: 6.6 + acceleration: -0.24 + command: -15.0 + } + calibration { + speed: 6.6 + acceleration: -0.22 + command: -17.0 + } + calibration { + speed: 6.6 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 6.6 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 6.6 + acceleration: -0.15 + command: 17.0 + } + calibration { + speed: 6.6 + acceleration: 0.24 + command: 22.0 + } + calibration { + speed: 6.6 + acceleration: 0.46 + command: 25.0 + } + calibration { + speed: 6.6 + acceleration: 0.72 + command: 27.0 + } + calibration { + speed: 6.6 + acceleration: 1.14 + command: 30.0 + } + calibration { + speed: 6.6 + acceleration: 2.07 + command: 35.0 + } + calibration { + speed: 6.6 + acceleration: 2.73 + command: 40.0 + } + calibration { + speed: 6.6 + acceleration: 2.94 + command: 45.0 + } + calibration { + speed: 6.6 + acceleration: 3.18 + command: 50.0 + } + calibration { + speed: 6.6 + acceleration: 3.42 + command: 55.0 + } + calibration { + speed: 6.6 + acceleration: 3.46 + command: 60.0 + } + calibration { + speed: 6.6 + acceleration: 3.55 + command: 65.0 + } + calibration { + speed: 6.6 + acceleration: 3.58 + command: 70.0 + } + calibration { + speed: 6.6 + acceleration: 3.61 + command: 80.0 + } + calibration { + speed: 6.6 + acceleration: 3.63 + command: 75.0 + } + calibration { + speed: 6.8 + acceleration: -8.64 + command: -33.0 + } + calibration { + speed: 6.8 + acceleration: -5.04 + command: -32.0 + } + calibration { + speed: 6.8 + acceleration: -4.56 + command: -31.0 + } + calibration { + speed: 6.8 + acceleration: -3.96 + command: -30.0 + } + calibration { + speed: 6.8 + acceleration: -3.31 + command: -29.0 + } + calibration { + speed: 6.8 + acceleration: -2.78 + command: -28.0 + } + calibration { + speed: 6.8 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 6.8 + acceleration: -1.87 + command: -26.0 + } + calibration { + speed: 6.8 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 6.8 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.8 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 6.8 + acceleration: -0.28 + command: -20.0 + } + calibration { + speed: 6.8 + acceleration: -0.25 + command: -15.0 + } + calibration { + speed: 6.8 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 6.8 + acceleration: -0.2 + command: 1.0 + } + calibration { + speed: 6.8 + acceleration: -0.15 + command: 17.0 + } + calibration { + speed: 6.8 + acceleration: 0.16 + command: 22.0 + } + calibration { + speed: 6.8 + acceleration: 0.47 + command: 25.0 + } + calibration { + speed: 6.8 + acceleration: 0.71 + command: 27.0 + } + calibration { + speed: 6.8 + acceleration: 1.11 + command: 30.0 + } + calibration { + speed: 6.8 + acceleration: 2.02 + command: 35.0 + } + calibration { + speed: 6.8 + acceleration: 2.66 + command: 40.0 + } + calibration { + speed: 6.8 + acceleration: 2.88 + command: 45.0 + } + calibration { + speed: 6.8 + acceleration: 3.13 + command: 50.0 + } + calibration { + speed: 6.8 + acceleration: 3.38 + command: 55.0 + } + calibration { + speed: 6.8 + acceleration: 3.42 + command: 60.0 + } + calibration { + speed: 6.8 + acceleration: 3.53 + command: 65.0 + } + calibration { + speed: 6.8 + acceleration: 3.59 + command: 70.0 + } + calibration { + speed: 6.8 + acceleration: 3.6 + command: 80.0 + } + calibration { + speed: 6.8 + acceleration: 3.64 + command: 75.0 + } + calibration { + speed: 7.0 + acceleration: -8.61 + command: -33.0 + } + calibration { + speed: 7.0 + acceleration: -5.04 + command: -32.0 + } + calibration { + speed: 7.0 + acceleration: -4.57 + command: -31.0 + } + calibration { + speed: 7.0 + acceleration: -3.96 + command: -30.0 + } + calibration { + speed: 7.0 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 7.0 + acceleration: -2.76 + command: -28.0 + } + calibration { + speed: 7.0 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 7.0 + acceleration: -1.88 + command: -26.0 + } + calibration { + speed: 7.0 + acceleration: -1.33 + command: -25.0 + } + calibration { + speed: 7.0 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 7.0 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 7.0 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 7.0 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 7.0 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 7.0 + acceleration: -0.2 + command: 15.0 + } + calibration { + speed: 7.0 + acceleration: -0.17 + command: -13.0 + } + calibration { + speed: 7.0 + acceleration: -0.16 + command: 17.0 + } + calibration { + speed: 7.0 + acceleration: 0.21 + command: 22.0 + } + calibration { + speed: 7.0 + acceleration: 0.47 + command: 25.0 + } + calibration { + speed: 7.0 + acceleration: 0.69 + command: 27.0 + } + calibration { + speed: 7.0 + acceleration: 1.08 + command: 30.0 + } + calibration { + speed: 7.0 + acceleration: 1.97 + command: 35.0 + } + calibration { + speed: 7.0 + acceleration: 2.59 + command: 40.0 + } + calibration { + speed: 7.0 + acceleration: 2.83 + command: 45.0 + } + calibration { + speed: 7.0 + acceleration: 3.08 + command: 50.0 + } + calibration { + speed: 7.0 + acceleration: 3.34 + command: 55.0 + } + calibration { + speed: 7.0 + acceleration: 3.38 + command: 60.0 + } + calibration { + speed: 7.0 + acceleration: 3.51 + command: 65.0 + } + calibration { + speed: 7.0 + acceleration: 3.59 + command: 80.0 + } + calibration { + speed: 7.0 + acceleration: 3.62 + command: 70.0 + } + calibration { + speed: 7.0 + acceleration: 3.65 + command: 75.0 + } + calibration { + speed: 7.2 + acceleration: -8.59 + command: -33.0 + } + calibration { + speed: 7.2 + acceleration: -5.05 + command: -32.0 + } + calibration { + speed: 7.2 + acceleration: -4.58 + command: -31.0 + } + calibration { + speed: 7.2 + acceleration: -3.96 + command: -30.0 + } + calibration { + speed: 7.2 + acceleration: -3.29 + command: -29.0 + } + calibration { + speed: 7.2 + acceleration: -2.77 + command: -28.0 + } + calibration { + speed: 7.2 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 7.2 + acceleration: -1.89 + command: -26.0 + } + calibration { + speed: 7.2 + acceleration: -1.33 + command: -25.0 + } + calibration { + speed: 7.2 + acceleration: -0.92 + command: -24.0 + } + calibration { + speed: 7.2 + acceleration: -0.62 + command: -23.0 + } + calibration { + speed: 7.2 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 7.2 + acceleration: -0.24 + command: -15.0 + } + calibration { + speed: 7.2 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 7.2 + acceleration: -0.2 + command: 15.0 + } + calibration { + speed: 7.2 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 7.2 + acceleration: -0.15 + command: 17.0 + } + calibration { + speed: 7.2 + acceleration: 0.18 + command: 22.0 + } + calibration { + speed: 7.2 + acceleration: 0.44 + command: 25.0 + } + calibration { + speed: 7.2 + acceleration: 0.66 + command: 27.0 + } + calibration { + speed: 7.2 + acceleration: 1.04 + command: 30.0 + } + calibration { + speed: 7.2 + acceleration: 1.9 + command: 35.0 + } + calibration { + speed: 7.2 + acceleration: 2.52 + command: 40.0 + } + calibration { + speed: 7.2 + acceleration: 2.78 + command: 45.0 + } + calibration { + speed: 7.2 + acceleration: 3.03 + command: 50.0 + } + calibration { + speed: 7.2 + acceleration: 3.29 + command: 55.0 + } + calibration { + speed: 7.2 + acceleration: 3.33 + command: 60.0 + } + calibration { + speed: 7.2 + acceleration: 3.49 + command: 65.0 + } + calibration { + speed: 7.2 + acceleration: 3.59 + command: 80.0 + } + calibration { + speed: 7.2 + acceleration: 3.65 + command: 72.5 + } + calibration { + speed: 7.4 + acceleration: -8.61 + command: -33.0 + } + calibration { + speed: 7.4 + acceleration: -5.04 + command: -32.0 + } + calibration { + speed: 7.4 + acceleration: -4.59 + command: -31.0 + } + calibration { + speed: 7.4 + acceleration: -3.97 + command: -30.0 + } + calibration { + speed: 7.4 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 7.4 + acceleration: -2.78 + command: -28.0 + } + calibration { + speed: 7.4 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 7.4 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 7.4 + acceleration: -1.33 + command: -25.0 + } + calibration { + speed: 7.4 + acceleration: -0.92 + command: -24.0 + } + calibration { + speed: 7.4 + acceleration: -0.62 + command: -23.0 + } + calibration { + speed: 7.4 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 7.4 + acceleration: -0.25 + command: -16.0 + } + calibration { + speed: 7.4 + acceleration: -0.22 + command: 15.0 + } + calibration { + speed: 7.4 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 7.4 + acceleration: -0.16 + command: 17.0 + } + calibration { + speed: 7.4 + acceleration: 0.21 + command: 22.0 + } + calibration { + speed: 7.4 + acceleration: 0.42 + command: 25.0 + } + calibration { + speed: 7.4 + acceleration: 0.65 + command: 27.0 + } + calibration { + speed: 7.4 + acceleration: 1.0 + command: 30.0 + } + calibration { + speed: 7.4 + acceleration: 1.81 + command: 35.0 + } + calibration { + speed: 7.4 + acceleration: 2.44 + command: 40.0 + } + calibration { + speed: 7.4 + acceleration: 2.72 + command: 45.0 + } + calibration { + speed: 7.4 + acceleration: 2.99 + command: 50.0 + } + calibration { + speed: 7.4 + acceleration: 3.25 + command: 55.0 + } + calibration { + speed: 7.4 + acceleration: 3.29 + command: 60.0 + } + calibration { + speed: 7.4 + acceleration: 3.48 + command: 65.0 + } + calibration { + speed: 7.4 + acceleration: 3.59 + command: 80.0 + } + calibration { + speed: 7.4 + acceleration: 3.65 + command: 75.0 + } + calibration { + speed: 7.4 + acceleration: 3.68 + command: 70.0 + } + calibration { + speed: 7.6 + acceleration: -8.66 + command: -33.0 + } + calibration { + speed: 7.6 + acceleration: -5.03 + command: -32.0 + } + calibration { + speed: 7.6 + acceleration: -4.59 + command: -31.0 + } + calibration { + speed: 7.6 + acceleration: -3.97 + command: -30.0 + } + calibration { + speed: 7.6 + acceleration: -3.31 + command: -29.0 + } + calibration { + speed: 7.6 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 7.6 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 7.6 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 7.6 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 7.6 + acceleration: -0.92 + command: -24.0 + } + calibration { + speed: 7.6 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 7.6 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 7.6 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 7.6 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 7.6 + acceleration: -0.23 + command: 15.0 + } + calibration { + speed: 7.6 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 7.6 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 7.6 + acceleration: 0.17 + command: 22.0 + } + calibration { + speed: 7.6 + acceleration: 0.41 + command: 25.0 + } + calibration { + speed: 7.6 + acceleration: 0.62 + command: 27.0 + } + calibration { + speed: 7.6 + acceleration: 0.98 + command: 30.0 + } + calibration { + speed: 7.6 + acceleration: 1.76 + command: 35.0 + } + calibration { + speed: 7.6 + acceleration: 2.37 + command: 40.0 + } + calibration { + speed: 7.6 + acceleration: 2.66 + command: 45.0 + } + calibration { + speed: 7.6 + acceleration: 2.93 + command: 50.0 + } + calibration { + speed: 7.6 + acceleration: 3.21 + command: 55.0 + } + calibration { + speed: 7.6 + acceleration: 3.25 + command: 60.0 + } + calibration { + speed: 7.6 + acceleration: 3.47 + command: 65.0 + } + calibration { + speed: 7.6 + acceleration: 3.6 + command: 80.0 + } + calibration { + speed: 7.6 + acceleration: 3.65 + command: 75.0 + } + calibration { + speed: 7.6 + acceleration: 3.69 + command: 70.0 + } + calibration { + speed: 7.8 + acceleration: -8.77 + command: -33.0 + } + calibration { + speed: 7.8 + acceleration: -5.01 + command: -32.0 + } + calibration { + speed: 7.8 + acceleration: -4.57 + command: -31.0 + } + calibration { + speed: 7.8 + acceleration: -3.97 + command: -30.0 + } + calibration { + speed: 7.8 + acceleration: -3.32 + command: -29.0 + } + calibration { + speed: 7.8 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 7.8 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 7.8 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 7.8 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 7.8 + acceleration: -0.93 + command: -24.0 + } + calibration { + speed: 7.8 + acceleration: -0.62 + command: -23.0 + } + calibration { + speed: 7.8 + acceleration: -0.28 + command: -20.0 + } + calibration { + speed: 7.8 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 7.8 + acceleration: -0.25 + command: -17.0 + } + calibration { + speed: 7.8 + acceleration: -0.23 + command: 15.0 + } + calibration { + speed: 7.8 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 7.8 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 7.8 + acceleration: 0.14 + command: 22.0 + } + calibration { + speed: 7.8 + acceleration: 0.42 + command: 25.0 + } + calibration { + speed: 7.8 + acceleration: 0.6 + command: 27.0 + } + calibration { + speed: 7.8 + acceleration: 0.95 + command: 30.0 + } + calibration { + speed: 7.8 + acceleration: 1.73 + command: 35.0 + } + calibration { + speed: 7.8 + acceleration: 2.3 + command: 40.0 + } + calibration { + speed: 7.8 + acceleration: 2.59 + command: 45.0 + } + calibration { + speed: 7.8 + acceleration: 2.88 + command: 50.0 + } + calibration { + speed: 7.8 + acceleration: 3.15 + command: 55.0 + } + calibration { + speed: 7.8 + acceleration: 3.21 + command: 60.0 + } + calibration { + speed: 7.8 + acceleration: 3.48 + command: 65.0 + } + calibration { + speed: 7.8 + acceleration: 3.62 + command: 80.0 + } + calibration { + speed: 7.8 + acceleration: 3.66 + command: 75.0 + } + calibration { + speed: 7.8 + acceleration: 3.69 + command: 70.0 + } + calibration { + speed: 8.0 + acceleration: -8.87 + command: -33.0 + } + calibration { + speed: 8.0 + acceleration: -5.0 + command: -32.0 + } + calibration { + speed: 8.0 + acceleration: -4.54 + command: -31.0 + } + calibration { + speed: 8.0 + acceleration: -3.96 + command: -30.0 + } + calibration { + speed: 8.0 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 8.0 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 8.0 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 8.0 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 8.0 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 8.0 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 8.0 + acceleration: -0.62 + command: -23.0 + } + calibration { + speed: 8.0 + acceleration: -0.28 + command: -20.0 + } + calibration { + speed: 8.0 + acceleration: -0.26 + command: 0.0 + } + calibration { + speed: 8.0 + acceleration: -0.25 + command: -17.0 + } + calibration { + speed: 8.0 + acceleration: -0.18 + command: 2.0 + } + calibration { + speed: 8.0 + acceleration: 0.17 + command: 22.0 + } + calibration { + speed: 8.0 + acceleration: 0.4 + command: 25.0 + } + calibration { + speed: 8.0 + acceleration: 0.57 + command: 27.0 + } + calibration { + speed: 8.0 + acceleration: 0.94 + command: 30.0 + } + calibration { + speed: 8.0 + acceleration: 1.7 + command: 35.0 + } + calibration { + speed: 8.0 + acceleration: 2.24 + command: 40.0 + } + calibration { + speed: 8.0 + acceleration: 2.52 + command: 45.0 + } + calibration { + speed: 8.0 + acceleration: 2.82 + command: 50.0 + } + calibration { + speed: 8.0 + acceleration: 3.08 + command: 55.0 + } + calibration { + speed: 8.0 + acceleration: 3.16 + command: 60.0 + } + calibration { + speed: 8.0 + acceleration: 3.49 + command: 65.0 + } + calibration { + speed: 8.0 + acceleration: 3.64 + command: 80.0 + } + calibration { + speed: 8.0 + acceleration: 3.67 + command: 75.0 + } + calibration { + speed: 8.0 + acceleration: 3.68 + command: 70.0 + } + calibration { + speed: 8.2 + acceleration: -8.99 + command: -33.0 + } + calibration { + speed: 8.2 + acceleration: -5.0 + command: -32.0 + } + calibration { + speed: 8.2 + acceleration: -4.5 + command: -31.0 + } + calibration { + speed: 8.2 + acceleration: -3.95 + command: -30.0 + } + calibration { + speed: 8.2 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 8.2 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 8.2 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 8.2 + acceleration: -1.91 + command: -26.0 + } + calibration { + speed: 8.2 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 8.2 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 8.2 + acceleration: -0.64 + command: -23.0 + } + calibration { + speed: 8.2 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 8.2 + acceleration: -0.28 + command: -15.0 + } + calibration { + speed: 8.2 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 8.2 + acceleration: -0.24 + command: 15.0 + } + calibration { + speed: 8.2 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 8.2 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 8.2 + acceleration: -0.04 + command: 20.0 + } + calibration { + speed: 8.2 + acceleration: 0.17 + command: 22.0 + } + calibration { + speed: 8.2 + acceleration: 0.38 + command: 25.0 + } + calibration { + speed: 8.2 + acceleration: 0.55 + command: 27.0 + } + calibration { + speed: 8.2 + acceleration: 0.9 + command: 30.0 + } + calibration { + speed: 8.2 + acceleration: 1.64 + command: 35.0 + } + calibration { + speed: 8.2 + acceleration: 2.19 + command: 40.0 + } + calibration { + speed: 8.2 + acceleration: 2.46 + command: 45.0 + } + calibration { + speed: 8.2 + acceleration: 2.77 + command: 50.0 + } + calibration { + speed: 8.2 + acceleration: 3.03 + command: 55.0 + } + calibration { + speed: 8.2 + acceleration: 3.13 + command: 60.0 + } + calibration { + speed: 8.2 + acceleration: 3.5 + command: 65.0 + } + calibration { + speed: 8.2 + acceleration: 3.66 + command: 75.0 + } + calibration { + speed: 8.2 + acceleration: 3.69 + command: 75.0 + } + calibration { + speed: 8.4 + acceleration: -9.11 + command: -33.0 + } + calibration { + speed: 8.4 + acceleration: -5.01 + command: -32.0 + } + calibration { + speed: 8.4 + acceleration: -4.47 + command: -31.0 + } + calibration { + speed: 8.4 + acceleration: -3.95 + command: -30.0 + } + calibration { + speed: 8.4 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 8.4 + acceleration: -2.81 + command: -28.0 + } + calibration { + speed: 8.4 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 8.4 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 8.4 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 8.4 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 8.4 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 8.4 + acceleration: -0.28 + command: -20.0 + } + calibration { + speed: 8.4 + acceleration: -0.27 + command: -15.0 + } + calibration { + speed: 8.4 + acceleration: -0.25 + command: -17.0 + } + calibration { + speed: 8.4 + acceleration: -0.24 + command: 15.0 + } + calibration { + speed: 8.4 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 8.4 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 8.4 + acceleration: -0.08 + command: 20.0 + } + calibration { + speed: 8.4 + acceleration: 0.12 + command: 22.0 + } + calibration { + speed: 8.4 + acceleration: 0.36 + command: 25.0 + } + calibration { + speed: 8.4 + acceleration: 0.54 + command: 27.0 + } + calibration { + speed: 8.4 + acceleration: 0.85 + command: 30.0 + } + calibration { + speed: 8.4 + acceleration: 1.57 + command: 35.0 + } + calibration { + speed: 8.4 + acceleration: 2.13 + command: 40.0 + } + calibration { + speed: 8.4 + acceleration: 2.41 + command: 45.0 + } + calibration { + speed: 8.4 + acceleration: 2.71 + command: 50.0 + } + calibration { + speed: 8.4 + acceleration: 2.97 + command: 55.0 + } + calibration { + speed: 8.4 + acceleration: 3.1 + command: 60.0 + } + calibration { + speed: 8.4 + acceleration: 3.5 + command: 65.0 + } + calibration { + speed: 8.4 + acceleration: 3.65 + command: 70.0 + } + calibration { + speed: 8.4 + acceleration: 3.67 + command: 80.0 + } + calibration { + speed: 8.4 + acceleration: 3.69 + command: 75.0 + } + calibration { + speed: 8.6 + acceleration: -9.23 + command: -33.0 + } + calibration { + speed: 8.6 + acceleration: -5.03 + command: -32.0 + } + calibration { + speed: 8.6 + acceleration: -4.46 + command: -31.0 + } + calibration { + speed: 8.6 + acceleration: -3.95 + command: -30.0 + } + calibration { + speed: 8.6 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 8.6 + acceleration: -2.83 + command: -28.0 + } + calibration { + speed: 8.6 + acceleration: -2.35 + command: -27.0 + } + calibration { + speed: 8.6 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 8.6 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 8.6 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 8.6 + acceleration: -0.64 + command: -23.0 + } + calibration { + speed: 8.6 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 8.6 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 8.6 + acceleration: -0.25 + command: 15.0 + } + calibration { + speed: 8.6 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 8.6 + acceleration: -0.22 + command: -13.0 + } + calibration { + speed: 8.6 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 8.6 + acceleration: -0.07 + command: 20.0 + } + calibration { + speed: 8.6 + acceleration: 0.15 + command: 22.0 + } + calibration { + speed: 8.6 + acceleration: 0.34 + command: 25.0 + } + calibration { + speed: 8.6 + acceleration: 0.51 + command: 27.0 + } + calibration { + speed: 8.6 + acceleration: 0.86 + command: 30.0 + } + calibration { + speed: 8.6 + acceleration: 1.5 + command: 35.0 + } + calibration { + speed: 8.6 + acceleration: 2.08 + command: 40.0 + } + calibration { + speed: 8.6 + acceleration: 2.36 + command: 45.0 + } + calibration { + speed: 8.6 + acceleration: 2.66 + command: 50.0 + } + calibration { + speed: 8.6 + acceleration: 2.92 + command: 55.0 + } + calibration { + speed: 8.6 + acceleration: 3.07 + command: 60.0 + } + calibration { + speed: 8.6 + acceleration: 3.49 + command: 65.0 + } + calibration { + speed: 8.6 + acceleration: 3.63 + command: 70.0 + } + calibration { + speed: 8.6 + acceleration: 3.69 + command: 77.5 + } + calibration { + speed: 8.8 + acceleration: -9.34 + command: -33.0 + } + calibration { + speed: 8.8 + acceleration: -5.05 + command: -32.0 + } + calibration { + speed: 8.8 + acceleration: -4.47 + command: -31.0 + } + calibration { + speed: 8.8 + acceleration: -3.94 + command: -30.0 + } + calibration { + speed: 8.8 + acceleration: -3.31 + command: -29.0 + } + calibration { + speed: 8.8 + acceleration: -2.86 + command: -28.0 + } + calibration { + speed: 8.8 + acceleration: -2.35 + command: -27.0 + } + calibration { + speed: 8.8 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 8.8 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 8.8 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 8.8 + acceleration: -0.64 + command: -23.0 + } + calibration { + speed: 8.8 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 8.8 + acceleration: -0.28 + command: -15.0 + } + calibration { + speed: 8.8 + acceleration: -0.26 + command: 15.0 + } + calibration { + speed: 8.8 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 8.8 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 8.8 + acceleration: -0.08 + command: 20.0 + } + calibration { + speed: 8.8 + acceleration: 0.11 + command: 22.0 + } + calibration { + speed: 8.8 + acceleration: 0.3 + command: 25.0 + } + calibration { + speed: 8.8 + acceleration: 0.5 + command: 27.0 + } + calibration { + speed: 8.8 + acceleration: 0.82 + command: 30.0 + } + calibration { + speed: 8.8 + acceleration: 1.47 + command: 35.0 + } + calibration { + speed: 8.8 + acceleration: 2.03 + command: 40.0 + } + calibration { + speed: 8.8 + acceleration: 2.31 + command: 45.0 + } + calibration { + speed: 8.8 + acceleration: 2.61 + command: 50.0 + } + calibration { + speed: 8.8 + acceleration: 2.89 + command: 55.0 + } + calibration { + speed: 8.8 + acceleration: 3.04 + command: 60.0 + } + calibration { + speed: 8.8 + acceleration: 3.47 + command: 65.0 + } + calibration { + speed: 8.8 + acceleration: 3.61 + command: 70.0 + } + calibration { + speed: 8.8 + acceleration: 3.68 + command: 75.0 + } + calibration { + speed: 8.8 + acceleration: 3.69 + command: 80.0 + } + calibration { + speed: 9.0 + acceleration: -9.44 + command: -33.0 + } + calibration { + speed: 9.0 + acceleration: -5.05 + command: -32.0 + } + calibration { + speed: 9.0 + acceleration: -4.5 + command: -31.0 + } + calibration { + speed: 9.0 + acceleration: -3.92 + command: -30.0 + } + calibration { + speed: 9.0 + acceleration: -3.29 + command: -29.0 + } + calibration { + speed: 9.0 + acceleration: -2.88 + command: -28.0 + } + calibration { + speed: 9.0 + acceleration: -2.36 + command: -27.0 + } + calibration { + speed: 9.0 + acceleration: -1.91 + command: -26.0 + } + calibration { + speed: 9.0 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 9.0 + acceleration: -0.95 + command: -24.0 + } + calibration { + speed: 9.0 + acceleration: -0.64 + command: -23.0 + } + calibration { + speed: 9.0 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 9.0 + acceleration: -0.27 + command: -15.0 + } + calibration { + speed: 9.0 + acceleration: -0.23 + command: -1.0 + } + calibration { + speed: 9.0 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 9.0 + acceleration: -0.18 + command: 17.0 + } + calibration { + speed: 9.0 + acceleration: -0.06 + command: 20.0 + } + calibration { + speed: 9.0 + acceleration: 0.11 + command: 22.0 + } + calibration { + speed: 9.0 + acceleration: 0.34 + command: 25.0 + } + calibration { + speed: 9.0 + acceleration: 0.47 + command: 27.0 + } + calibration { + speed: 9.0 + acceleration: 0.79 + command: 30.0 + } + calibration { + speed: 9.0 + acceleration: 1.43 + command: 35.0 + } + calibration { + speed: 9.0 + acceleration: 1.98 + command: 40.0 + } + calibration { + speed: 9.0 + acceleration: 2.26 + command: 45.0 + } + calibration { + speed: 9.0 + acceleration: 2.56 + command: 50.0 + } + calibration { + speed: 9.0 + acceleration: 2.84 + command: 55.0 + } + calibration { + speed: 9.0 + acceleration: 3.0 + command: 60.0 + } + calibration { + speed: 9.0 + acceleration: 3.44 + command: 65.0 + } + calibration { + speed: 9.0 + acceleration: 3.59 + command: 70.0 + } + calibration { + speed: 9.0 + acceleration: 3.67 + command: 75.0 + } + calibration { + speed: 9.0 + acceleration: 3.69 + command: 80.0 + } + calibration { + speed: 9.2 + acceleration: -9.49 + command: -33.0 + } + calibration { + speed: 9.2 + acceleration: -5.02 + command: -32.0 + } + calibration { + speed: 9.2 + acceleration: -4.53 + command: -31.0 + } + calibration { + speed: 9.2 + acceleration: -3.88 + command: -30.0 + } + calibration { + speed: 9.2 + acceleration: -3.27 + command: -29.0 + } + calibration { + speed: 9.2 + acceleration: -2.88 + command: -28.0 + } + calibration { + speed: 9.2 + acceleration: -2.37 + command: -27.0 + } + calibration { + speed: 9.2 + acceleration: -1.93 + command: -26.0 + } + calibration { + speed: 9.2 + acceleration: -1.36 + command: -25.0 + } + calibration { + speed: 9.2 + acceleration: -0.96 + command: -24.0 + } + calibration { + speed: 9.2 + acceleration: -0.66 + command: -23.0 + } + calibration { + speed: 9.2 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 9.2 + acceleration: -0.27 + command: -15.0 + } + calibration { + speed: 9.2 + acceleration: -0.25 + command: -17.0 + } + calibration { + speed: 9.2 + acceleration: -0.24 + command: 15.0 + } + calibration { + speed: 9.2 + acceleration: -0.21 + command: -13.0 + } + calibration { + speed: 9.2 + acceleration: -0.18 + command: 17.0 + } + calibration { + speed: 9.2 + acceleration: -0.09 + command: 20.0 + } + calibration { + speed: 9.2 + acceleration: 0.12 + command: 22.0 + } + calibration { + speed: 9.2 + acceleration: 0.31 + command: 25.0 + } + calibration { + speed: 9.2 + acceleration: 0.43 + command: 27.0 + } + calibration { + speed: 9.2 + acceleration: 0.76 + command: 30.0 + } + calibration { + speed: 9.2 + acceleration: 1.38 + command: 35.0 + } + calibration { + speed: 9.2 + acceleration: 1.93 + command: 40.0 + } + calibration { + speed: 9.2 + acceleration: 2.21 + command: 45.0 + } + calibration { + speed: 9.2 + acceleration: 2.52 + command: 50.0 + } + calibration { + speed: 9.2 + acceleration: 2.79 + command: 55.0 + } + calibration { + speed: 9.2 + acceleration: 2.95 + command: 60.0 + } + calibration { + speed: 9.2 + acceleration: 3.41 + command: 65.0 + } + calibration { + speed: 9.2 + acceleration: 3.56 + command: 70.0 + } + calibration { + speed: 9.2 + acceleration: 3.65 + command: 75.0 + } + calibration { + speed: 9.2 + acceleration: 3.67 + command: 80.0 + } + calibration { + speed: 9.4 + acceleration: -9.5 + command: -33.0 + } + calibration { + speed: 9.4 + acceleration: -4.95 + command: -32.0 + } + calibration { + speed: 9.4 + acceleration: -4.52 + command: -31.0 + } + calibration { + speed: 9.4 + acceleration: -3.83 + command: -30.0 + } + calibration { + speed: 9.4 + acceleration: -3.27 + command: -29.0 + } + calibration { + speed: 9.4 + acceleration: -2.87 + command: -28.0 + } + calibration { + speed: 9.4 + acceleration: -2.38 + command: -27.0 + } + calibration { + speed: 9.4 + acceleration: -1.95 + command: -26.0 + } + calibration { + speed: 9.4 + acceleration: -1.37 + command: -25.0 + } + calibration { + speed: 9.4 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 9.4 + acceleration: -0.66 + command: -23.0 + } + calibration { + speed: 9.4 + acceleration: -0.3 + command: -20.0 + } + calibration { + speed: 9.4 + acceleration: -0.27 + command: 15.0 + } + calibration { + speed: 9.4 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 9.4 + acceleration: -0.25 + command: -15.0 + } + calibration { + speed: 9.4 + acceleration: -0.18 + command: 17.0 + } + calibration { + speed: 9.4 + acceleration: -0.12 + command: 20.0 + } + calibration { + speed: 9.4 + acceleration: 0.08 + command: 22.0 + } + calibration { + speed: 9.4 + acceleration: 0.3 + command: 25.0 + } + calibration { + speed: 9.4 + acceleration: 0.42 + command: 27.0 + } + calibration { + speed: 9.4 + acceleration: 0.72 + command: 30.0 + } + calibration { + speed: 9.4 + acceleration: 1.35 + command: 35.0 + } + calibration { + speed: 9.4 + acceleration: 1.88 + command: 40.0 + } + calibration { + speed: 9.4 + acceleration: 2.16 + command: 45.0 + } + calibration { + speed: 9.4 + acceleration: 2.48 + command: 50.0 + } + calibration { + speed: 9.4 + acceleration: 2.74 + command: 55.0 + } + calibration { + speed: 9.4 + acceleration: 2.9 + command: 60.0 + } + calibration { + speed: 9.4 + acceleration: 3.38 + command: 65.0 + } + calibration { + speed: 9.4 + acceleration: 3.54 + command: 70.0 + } + calibration { + speed: 9.4 + acceleration: 3.63 + command: 75.0 + } + calibration { + speed: 9.4 + acceleration: 3.64 + command: 80.0 + } + calibration { + speed: 9.6 + acceleration: -9.43 + command: -33.0 + } + calibration { + speed: 9.6 + acceleration: -4.88 + command: -32.0 + } + calibration { + speed: 9.6 + acceleration: -4.49 + command: -31.0 + } + calibration { + speed: 9.6 + acceleration: -3.73 + command: -30.0 + } + calibration { + speed: 9.6 + acceleration: -3.29 + command: -29.0 + } + calibration { + speed: 9.6 + acceleration: -2.84 + command: -28.0 + } + calibration { + speed: 9.6 + acceleration: -2.38 + command: -27.0 + } + calibration { + speed: 9.6 + acceleration: -1.96 + command: -26.0 + } + calibration { + speed: 9.6 + acceleration: -1.37 + command: -25.0 + } + calibration { + speed: 9.6 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 9.6 + acceleration: -0.67 + command: -23.0 + } + calibration { + speed: 9.6 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 9.6 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 9.6 + acceleration: -0.25 + command: 15.0 + } + calibration { + speed: 9.6 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 9.6 + acceleration: -0.23 + command: -13.0 + } + calibration { + speed: 9.6 + acceleration: -0.18 + command: 17.0 + } + calibration { + speed: 9.6 + acceleration: -0.09 + command: 20.0 + } + calibration { + speed: 9.6 + acceleration: 0.06 + command: 22.0 + } + calibration { + speed: 9.6 + acceleration: 0.27 + command: 25.0 + } + calibration { + speed: 9.6 + acceleration: 0.4 + command: 27.0 + } + calibration { + speed: 9.6 + acceleration: 0.69 + command: 30.0 + } + calibration { + speed: 9.6 + acceleration: 1.31 + command: 35.0 + } + calibration { + speed: 9.6 + acceleration: 1.84 + command: 40.0 + } + calibration { + speed: 9.6 + acceleration: 2.12 + command: 45.0 + } + calibration { + speed: 9.6 + acceleration: 2.43 + command: 50.0 + } + calibration { + speed: 9.6 + acceleration: 2.68 + command: 55.0 + } + calibration { + speed: 9.6 + acceleration: 2.85 + command: 60.0 + } + calibration { + speed: 9.6 + acceleration: 3.35 + command: 65.0 + } + calibration { + speed: 9.6 + acceleration: 3.52 + command: 70.0 + } + calibration { + speed: 9.6 + acceleration: 3.58 + command: 80.0 + } + calibration { + speed: 9.6 + acceleration: 3.62 + command: 75.0 + } + calibration { + speed: 9.8 + acceleration: -9.17 + command: -33.0 + } + calibration { + speed: 9.8 + acceleration: -4.82 + command: -32.0 + } + calibration { + speed: 9.8 + acceleration: -4.44 + command: -31.0 + } + calibration { + speed: 9.8 + acceleration: -3.69 + command: -30.0 + } + calibration { + speed: 9.8 + acceleration: -3.32 + command: -29.0 + } + calibration { + speed: 9.8 + acceleration: -2.83 + command: -28.0 + } + calibration { + speed: 9.8 + acceleration: -2.38 + command: -27.0 + } + calibration { + speed: 9.8 + acceleration: -1.97 + command: -26.0 + } + calibration { + speed: 9.8 + acceleration: -1.38 + command: -25.0 + } + calibration { + speed: 9.8 + acceleration: -0.98 + command: -24.0 + } + calibration { + speed: 9.8 + acceleration: -0.68 + command: -23.0 + } + calibration { + speed: 9.8 + acceleration: -0.32 + command: -20.0 + } + calibration { + speed: 9.8 + acceleration: -0.29 + command: 15.0 + } + calibration { + speed: 9.8 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 9.8 + acceleration: -0.25 + command: -13.0 + } + calibration { + speed: 9.8 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 9.8 + acceleration: -0.18 + command: 17.0 + } + calibration { + speed: 9.8 + acceleration: -0.1 + command: 20.0 + } + calibration { + speed: 9.8 + acceleration: 0.04 + command: 22.0 + } + calibration { + speed: 9.8 + acceleration: 0.28 + command: 25.0 + } + calibration { + speed: 9.8 + acceleration: 0.4 + command: 27.0 + } + calibration { + speed: 9.8 + acceleration: 0.65 + command: 30.0 + } + calibration { + speed: 9.8 + acceleration: 1.27 + command: 35.0 + } + calibration { + speed: 9.8 + acceleration: 1.79 + command: 40.0 + } + calibration { + speed: 9.8 + acceleration: 2.08 + command: 45.0 + } + calibration { + speed: 9.8 + acceleration: 2.39 + command: 50.0 + } + calibration { + speed: 9.8 + acceleration: 2.63 + command: 55.0 + } + calibration { + speed: 9.8 + acceleration: 2.81 + command: 60.0 + } + calibration { + speed: 9.8 + acceleration: 3.31 + command: 65.0 + } + calibration { + speed: 9.8 + acceleration: 3.5 + command: 70.0 + } + calibration { + speed: 9.8 + acceleration: 3.52 + command: 80.0 + } + calibration { + speed: 9.8 + acceleration: 3.61 + command: 75.0 + } + calibration { + speed: 10.0 + acceleration: -8.69 + command: -33.0 + } + calibration { + speed: 10.0 + acceleration: -4.8 + command: -32.0 + } + calibration { + speed: 10.0 + acceleration: -4.35 + command: -31.0 + } + calibration { + speed: 10.0 + acceleration: -3.89 + command: -30.0 + } + calibration { + speed: 10.0 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 10.0 + acceleration: -2.82 + command: -28.0 + } + calibration { + speed: 10.0 + acceleration: -2.38 + command: -27.0 + } + calibration { + speed: 10.0 + acceleration: -1.96 + command: -26.0 + } + calibration { + speed: 10.0 + acceleration: -1.4 + command: -25.0 + } + calibration { + speed: 10.0 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 10.0 + acceleration: -0.68 + command: -23.0 + } + calibration { + speed: 10.0 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 10.0 + acceleration: -0.27 + command: -15.0 + } + calibration { + speed: 10.0 + acceleration: -0.25 + command: 15.0 + } + calibration { + speed: 10.0 + acceleration: -0.24 + command: -13.0 + } + calibration { + speed: 10.0 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 10.0 + acceleration: -0.2 + command: 17.0 + } + calibration { + speed: 10.0 + acceleration: -0.09 + command: 20.0 + } + calibration { + speed: 10.0 + acceleration: 0.27 + command: 25.0 + } + calibration { + speed: 10.0 + acceleration: 0.39 + command: 27.0 + } + calibration { + speed: 10.0 + acceleration: 0.63 + command: 30.0 + } + calibration { + speed: 10.0 + acceleration: 1.27 + command: 35.0 + } + calibration { + speed: 10.0 + acceleration: 1.75 + command: 40.0 + } + calibration { + speed: 10.0 + acceleration: 2.03 + command: 45.0 + } + calibration { + speed: 10.0 + acceleration: 2.35 + command: 50.0 + } + calibration { + speed: 10.0 + acceleration: 2.59 + command: 55.0 + } + calibration { + speed: 10.0 + acceleration: 2.78 + command: 60.0 + } + calibration { + speed: 10.0 + acceleration: 3.27 + command: 65.0 + } + calibration { + speed: 10.0 + acceleration: 3.45 + command: 80.0 + } + calibration { + speed: 10.0 + acceleration: 3.49 + command: 70.0 + } + calibration { + speed: 10.0 + acceleration: 3.61 + command: 75.0 + } + } +} +trajectory_period: 0.1 +chassis_period: 0.01 +localization_period: 0.01 diff --git a/apollo_control/conf/lincoln_062546.pb.txt b/apollo_control/conf/lincoln_062546.pb.txt new file mode 100644 index 0000000..40328ed --- /dev/null +++ b/apollo_control/conf/lincoln_062546.pb.txt @@ -0,0 +1,6810 @@ +control_period: 0.01 +max_planning_interval_sec: 0.2 +max_planning_delay_threshold: 4.0 +action: STOP +soft_estop_brake: 50.0 +active_controllers: LAT_CONTROLLER +active_controllers: LON_CONTROLLER +max_steering_percentage_allowed: 100 +max_status_interval_sec: 0.1 +lat_controller_conf { + ts: 0.01 + preview_window: 0 + cf: 155494.663 + cr: 155494.663 + wheelbase: 2.85 + mass_fl: 520 + mass_fr: 520 + mass_rl: 520 + mass_rr: 520 + eps: 0.01 + matrix_q: 0.02 + matrix_q: 0.0 + matrix_q: 0.4 + matrix_q: 0.0 + cutoff_freq: 10 + mean_filter_window_size: 10 + steer_transmission_ratio: 16 + steer_single_direction_max_degree: 470 + max_iteration: 150 +} +lon_controller_conf { + ts: 0.01 + brake_deadzone: 15.5 + throttle_deadzone: 18.0 + speed_controller_input_limit: 2.0 + station_error_limit: 2.0 + preview_window: 20.0 + standstill_acceleration: -3.0 + station_pid_conf { + integrator_enable: false + integrator_saturation_level: 0.3 + kp: 0.2 + ki: 0.0 + kd: 0.0 + } + low_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 0.5 + ki: 0.3 + kd: 0.0 + } + high_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 1.0 + ki: 0.3 + kd: 0.0 + } + switch_speed: 2.0 + throttle_filter_conf { + cutoff_freq: 10 + } + brake_filter_conf { + cutoff_freq: 10 + } + acceleration_filter_conf { + cutoff_freq: 5 + } + calibration_table { + calibration { + speed: 0.0 + acceleration: -5.11 + command: -35.0 + } + calibration { + speed: 0.0 + acceleration: -4.02 + command: -33.0 + } + calibration { + speed: 0.0 + acceleration: -3.41 + command: -31.0 + } + calibration { + speed: 0.0 + acceleration: -3.39 + command: -32.0 + } + calibration { + speed: 0.0 + acceleration: -3.17 + command: -30.0 + } + calibration { + speed: 0.0 + acceleration: -2.93 + command: -29.0 + } + calibration { + speed: 0.0 + acceleration: -2.61 + command: -28.0 + } + calibration { + speed: 0.0 + acceleration: -2.19 + command: -27.0 + } + calibration { + speed: 0.0 + acceleration: -1.69 + command: -26.0 + } + calibration { + speed: 0.0 + acceleration: -1.17 + command: -25.0 + } + calibration { + speed: 0.0 + acceleration: -0.73 + command: -24.0 + } + calibration { + speed: 0.0 + acceleration: -0.46 + command: -23.0 + } + calibration { + speed: 0.0 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 0.0 + acceleration: -0.02 + command: -20.0 + } + calibration { + speed: 0.0 + acceleration: 0.21 + command: -13.0 + } + calibration { + speed: 0.0 + acceleration: 0.34 + command: 0.0 + } + calibration { + speed: 0.0 + acceleration: 0.36 + command: 0.0 + } + calibration { + speed: 0.0 + acceleration: 0.39 + command: 17.0 + } + calibration { + speed: 0.0 + acceleration: 0.8 + command: 20.0 + } + calibration { + speed: 0.0 + acceleration: 1.31 + command: 25.0 + } + calibration { + speed: 0.0 + acceleration: 1.35 + command: 27.0 + } + calibration { + speed: 0.0 + acceleration: 1.4 + command: 30.0 + } + calibration { + speed: 0.0 + acceleration: 1.55 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 1.71 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 1.76 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 1.79 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 1.88 + command: 35 + } + calibration { + speed: 0.2 + acceleration: -5.43 + command: -33.0 + } + calibration { + speed: 0.2 + acceleration: -4.28 + command: -33.0 + } + calibration { + speed: 0.2 + acceleration: -3.6 + command: -32.0 + } + calibration { + speed: 0.2 + acceleration: -3.58 + command: -31.0 + } + calibration { + speed: 0.2 + acceleration: -3.27 + command: -30.0 + } + calibration { + speed: 0.2 + acceleration: -3.01 + command: -29.0 + } + calibration { + speed: 0.2 + acceleration: -2.65 + command: -28.0 + } + calibration { + speed: 0.2 + acceleration: -2.22 + command: -27.0 + } + calibration { + speed: 0.2 + acceleration: -1.7 + command: -26.0 + } + calibration { + speed: 0.2 + acceleration: -1.17 + command: -25.0 + } + calibration { + speed: 0.2 + acceleration: -0.73 + command: -24.0 + } + calibration { + speed: 0.2 + acceleration: -0.46 + command: -23.0 + } + calibration { + speed: 0.2 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 0.2 + acceleration: -0.02 + command: -20.0 + } + calibration { + speed: 0.2 + acceleration: 0.21 + command: -13.0 + } + calibration { + speed: 0.2 + acceleration: 0.34 + command: -17.0 + } + calibration { + speed: 0.2 + acceleration: 0.36 + command: -15.0 + } + calibration { + speed: 0.2 + acceleration: 0.37 + command: 15.0 + } + calibration { + speed: 0.2 + acceleration: 0.39 + command: 17.0 + } + calibration { + speed: 0.2 + acceleration: 0.81 + command: 20.0 + } + calibration { + speed: 0.2 + acceleration: 1.36 + command: 27.5 + } + calibration { + speed: 0.2 + acceleration: 1.44 + command: 27.0 + } + calibration { + speed: 0.2 + acceleration: 1.62 + command: 35.0 + } + calibration { + speed: 0.2 + acceleration: 1.79 + command: 40.0 + } + calibration { + speed: 0.2 + acceleration: 1.87 + command: 60.0 + } + calibration { + speed: 0.2 + acceleration: 1.9 + command: 45.0 + } + calibration { + speed: 0.2 + acceleration: 2.0 + command: 50.0 + } + calibration { + speed: 0.2 + acceleration: 2.01 + command: 55.0 + } + calibration { + speed: 0.4 + acceleration: -6.7 + command: -35.0 + } + calibration { + speed: 0.4 + acceleration: -5.53 + command: -33.0 + } + calibration { + speed: 0.4 + acceleration: -4.68 + command: -32.0 + } + calibration { + speed: 0.4 + acceleration: -4.44 + command: -31.0 + } + calibration { + speed: 0.4 + acceleration: -3.86 + command: -30.0 + } + calibration { + speed: 0.4 + acceleration: -3.48 + command: -29.0 + } + calibration { + speed: 0.4 + acceleration: -2.92 + command: -28.0 + } + calibration { + speed: 0.4 + acceleration: -2.43 + command: -27.0 + } + calibration { + speed: 0.4 + acceleration: -1.75 + command: -26.0 + } + calibration { + speed: 0.4 + acceleration: -1.18 + command: -25.0 + } + calibration { + speed: 0.4 + acceleration: -0.74 + command: -24.0 + } + calibration { + speed: 0.4 + acceleration: -0.51 + command: -23.0 + } + calibration { + speed: 0.4 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 0.4 + acceleration: 0.01 + command: -20.0 + } + calibration { + speed: 0.4 + acceleration: 0.21 + command: -13.0 + } + calibration { + speed: 0.4 + acceleration: 0.34 + command: -17.0 + } + calibration { + speed: 0.4 + acceleration: 0.35 + command: 15.0 + } + calibration { + speed: 0.4 + acceleration: 0.36 + command: -15.0 + } + calibration { + speed: 0.4 + acceleration: 0.39 + command: 17.0 + } + calibration { + speed: 0.4 + acceleration: 0.88 + command: 20.0 + } + calibration { + speed: 0.4 + acceleration: 1.46 + command: 25.0 + } + calibration { + speed: 0.4 + acceleration: 1.49 + command: 30.0 + } + calibration { + speed: 0.4 + acceleration: 1.61 + command: 27.0 + } + calibration { + speed: 0.4 + acceleration: 1.83 + command: 35.0 + } + calibration { + speed: 0.4 + acceleration: 1.99 + command: 40.0 + } + calibration { + speed: 0.4 + acceleration: 2.11 + command: 60.0 + } + calibration { + speed: 0.4 + acceleration: 2.14 + command: 45.0 + } + calibration { + speed: 0.4 + acceleration: 2.29 + command: 50.0 + } + calibration { + speed: 0.4 + acceleration: 2.31 + command: 55.0 + } + calibration { + speed: 0.6 + acceleration: -7.95 + command: -35.0 + } + calibration { + speed: 0.6 + acceleration: -7.13 + command: -33.0 + } + calibration { + speed: 0.6 + acceleration: -5.64 + command: -32.0 + } + calibration { + speed: 0.6 + acceleration: -5.08 + command: -31.0 + } + calibration { + speed: 0.6 + acceleration: -4.38 + command: -30.0 + } + calibration { + speed: 0.6 + acceleration: -3.84 + command: -29.0 + } + calibration { + speed: 0.6 + acceleration: -3.13 + command: -28.0 + } + calibration { + speed: 0.6 + acceleration: -2.54 + command: -27.0 + } + calibration { + speed: 0.6 + acceleration: -1.78 + command: -26.0 + } + calibration { + speed: 0.6 + acceleration: -1.2 + command: -25.0 + } + calibration { + speed: 0.6 + acceleration: -0.75 + command: -24.0 + } + calibration { + speed: 0.6 + acceleration: -0.53 + command: -23.0 + } + calibration { + speed: 0.6 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 0.6 + acceleration: 0.01 + command: -20.0 + } + calibration { + speed: 0.6 + acceleration: 0.19 + command: -13.0 + } + calibration { + speed: 0.6 + acceleration: 0.32 + command: -16.0 + } + calibration { + speed: 0.6 + acceleration: 0.33 + command: 15.0 + } + calibration { + speed: 0.6 + acceleration: 0.36 + command: 17.0 + } + calibration { + speed: 0.6 + acceleration: 0.93 + command: 20.0 + } + calibration { + speed: 0.6 + acceleration: 1.58 + command: 25.0 + } + calibration { + speed: 0.6 + acceleration: 1.66 + command: 30.0 + } + calibration { + speed: 0.6 + acceleration: 1.81 + command: 27.0 + } + calibration { + speed: 0.6 + acceleration: 2.06 + command: 35.0 + } + calibration { + speed: 0.6 + acceleration: 2.22 + command: 40.0 + } + calibration { + speed: 0.6 + acceleration: 2.28 + command: 60.0 + } + calibration { + speed: 0.6 + acceleration: 2.38 + command: 45.0 + } + calibration { + speed: 0.6 + acceleration: 2.52 + command: 50.0 + } + calibration { + speed: 0.6 + acceleration: 2.54 + command: 55.0 + } + calibration { + speed: 0.8 + acceleration: -8.89 + command: -35.0 + } + calibration { + speed: 0.8 + acceleration: -7.89 + command: -33.0 + } + calibration { + speed: 0.8 + acceleration: -5.88 + command: -32.0 + } + calibration { + speed: 0.8 + acceleration: -5.21 + command: -31.0 + } + calibration { + speed: 0.8 + acceleration: -4.44 + command: -30.0 + } + calibration { + speed: 0.8 + acceleration: -3.83 + command: -29.0 + } + calibration { + speed: 0.8 + acceleration: -3.08 + command: -28.0 + } + calibration { + speed: 0.8 + acceleration: -2.48 + command: -27.0 + } + calibration { + speed: 0.8 + acceleration: -1.76 + command: -26.0 + } + calibration { + speed: 0.8 + acceleration: -1.21 + command: -25.0 + } + calibration { + speed: 0.8 + acceleration: -0.75 + command: -24.0 + } + calibration { + speed: 0.8 + acceleration: -0.51 + command: -23.0 + } + calibration { + speed: 0.8 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 0.8 + acceleration: 0.01 + command: -20.0 + } + calibration { + speed: 0.8 + acceleration: 0.18 + command: -13.0 + } + calibration { + speed: 0.8 + acceleration: 0.26 + command: -1.0 + } + calibration { + speed: 0.8 + acceleration: 0.28 + command: -15.0 + } + calibration { + speed: 0.8 + acceleration: 0.31 + command: 17.0 + } + calibration { + speed: 0.8 + acceleration: 0.95 + command: 20.0 + } + calibration { + speed: 0.8 + acceleration: 1.69 + command: 25.0 + } + calibration { + speed: 0.8 + acceleration: 1.8 + command: 30.0 + } + calibration { + speed: 0.8 + acceleration: 2.02 + command: 27.0 + } + calibration { + speed: 0.8 + acceleration: 2.27 + command: 35.0 + } + calibration { + speed: 0.8 + acceleration: 2.36 + command: 60.0 + } + calibration { + speed: 0.8 + acceleration: 2.43 + command: 40.0 + } + calibration { + speed: 0.8 + acceleration: 2.56 + command: 45.0 + } + calibration { + speed: 0.8 + acceleration: 2.67 + command: 55.0 + } + calibration { + speed: 0.8 + acceleration: 2.68 + command: 50.0 + } + calibration { + speed: 1.0 + acceleration: -9.22 + command: -35.0 + } + calibration { + speed: 1.0 + acceleration: -8.03 + command: -33.0 + } + calibration { + speed: 1.0 + acceleration: -5.8 + command: -32.0 + } + calibration { + speed: 1.0 + acceleration: -5.04 + command: -31.0 + } + calibration { + speed: 1.0 + acceleration: -4.31 + command: -30.0 + } + calibration { + speed: 1.0 + acceleration: -3.7 + command: -29.0 + } + calibration { + speed: 1.0 + acceleration: -3.0 + command: -28.0 + } + calibration { + speed: 1.0 + acceleration: -2.45 + command: -27.0 + } + calibration { + speed: 1.0 + acceleration: -1.76 + command: -26.0 + } + calibration { + speed: 1.0 + acceleration: -1.2 + command: -25.0 + } + calibration { + speed: 1.0 + acceleration: -0.77 + command: -24.0 + } + calibration { + speed: 1.0 + acceleration: -0.54 + command: -23.0 + } + calibration { + speed: 1.0 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 1.0 + acceleration: 0.04 + command: -20.0 + } + calibration { + speed: 1.0 + acceleration: 0.13 + command: -13.0 + } + calibration { + speed: 1.0 + acceleration: 0.2 + command: -16.0 + } + calibration { + speed: 1.0 + acceleration: 0.24 + command: 17.0 + } + calibration { + speed: 1.0 + acceleration: 0.25 + command: 15.0 + } + calibration { + speed: 1.0 + acceleration: 0.94 + command: 20.0 + } + calibration { + speed: 1.0 + acceleration: 1.75 + command: 25.0 + } + calibration { + speed: 1.0 + acceleration: 1.92 + command: 30.0 + } + calibration { + speed: 1.0 + acceleration: 2.16 + command: 27.0 + } + calibration { + speed: 1.0 + acceleration: 2.4 + command: 60.0 + } + calibration { + speed: 1.0 + acceleration: 2.47 + command: 35.0 + } + calibration { + speed: 1.0 + acceleration: 2.62 + command: 40.0 + } + calibration { + speed: 1.0 + acceleration: 2.7 + command: 45.0 + } + calibration { + speed: 1.0 + acceleration: 2.77 + command: 55.0 + } + calibration { + speed: 1.0 + acceleration: 2.8 + command: 50.0 + } + calibration { + speed: 1.2 + acceleration: -9.23 + command: -35.0 + } + calibration { + speed: 1.2 + acceleration: -7.99 + command: -33.0 + } + calibration { + speed: 1.2 + acceleration: -5.61 + command: -32.0 + } + calibration { + speed: 1.2 + acceleration: -4.85 + command: -31.0 + } + calibration { + speed: 1.2 + acceleration: -4.15 + command: -30.0 + } + calibration { + speed: 1.2 + acceleration: -3.58 + command: -29.0 + } + calibration { + speed: 1.2 + acceleration: -2.96 + command: -28.0 + } + calibration { + speed: 1.2 + acceleration: -2.45 + command: -27.0 + } + calibration { + speed: 1.2 + acceleration: -1.75 + command: -26.0 + } + calibration { + speed: 1.2 + acceleration: -1.24 + command: -25.0 + } + calibration { + speed: 1.2 + acceleration: -0.78 + command: -24.0 + } + calibration { + speed: 1.2 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 1.2 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 1.2 + acceleration: 0.1 + command: -13.0 + } + calibration { + speed: 1.2 + acceleration: 0.14 + command: -1.0 + } + calibration { + speed: 1.2 + acceleration: 0.15 + command: -15.0 + } + calibration { + speed: 1.2 + acceleration: 0.2 + command: 17.0 + } + calibration { + speed: 1.2 + acceleration: 0.94 + command: 20.0 + } + calibration { + speed: 1.2 + acceleration: 1.79 + command: 25.0 + } + calibration { + speed: 1.2 + acceleration: 2.01 + command: 30.0 + } + calibration { + speed: 1.2 + acceleration: 2.24 + command: 27.0 + } + calibration { + speed: 1.2 + acceleration: 2.46 + command: 60.0 + } + calibration { + speed: 1.2 + acceleration: 2.64 + command: 35.0 + } + calibration { + speed: 1.2 + acceleration: 2.78 + command: 40.0 + } + calibration { + speed: 1.2 + acceleration: 2.83 + command: 45.0 + } + calibration { + speed: 1.2 + acceleration: 2.87 + command: 55.0 + } + calibration { + speed: 1.2 + acceleration: 2.91 + command: 50.0 + } + calibration { + speed: 1.4 + acceleration: -9.29 + command: -35.0 + } + calibration { + speed: 1.4 + acceleration: -7.82 + command: -33.0 + } + calibration { + speed: 1.4 + acceleration: -5.37 + command: -32.0 + } + calibration { + speed: 1.4 + acceleration: -4.68 + command: -31.0 + } + calibration { + speed: 1.4 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 1.4 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 1.4 + acceleration: -2.95 + command: -28.0 + } + calibration { + speed: 1.4 + acceleration: -2.42 + command: -27.0 + } + calibration { + speed: 1.4 + acceleration: -1.74 + command: -26.0 + } + calibration { + speed: 1.4 + acceleration: -1.24 + command: -25.0 + } + calibration { + speed: 1.4 + acceleration: -0.76 + command: -24.0 + } + calibration { + speed: 1.4 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 1.4 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 1.4 + acceleration: 0.07 + command: -13.0 + } + calibration { + speed: 1.4 + acceleration: 0.08 + command: -17.0 + } + calibration { + speed: 1.4 + acceleration: 0.09 + command: -15.0 + } + calibration { + speed: 1.4 + acceleration: 0.11 + command: 17.0 + } + calibration { + speed: 1.4 + acceleration: 0.12 + command: 15.0 + } + calibration { + speed: 1.4 + acceleration: 0.93 + command: 20.0 + } + calibration { + speed: 1.4 + acceleration: 1.83 + command: 25.0 + } + calibration { + speed: 1.4 + acceleration: 2.07 + command: 30.0 + } + calibration { + speed: 1.4 + acceleration: 2.29 + command: 27.0 + } + calibration { + speed: 1.4 + acceleration: 2.52 + command: 60.0 + } + calibration { + speed: 1.4 + acceleration: 2.77 + command: 35.0 + } + calibration { + speed: 1.4 + acceleration: 2.92 + command: 40.0 + } + calibration { + speed: 1.4 + acceleration: 2.95 + command: 45.0 + } + calibration { + speed: 1.4 + acceleration: 2.97 + command: 55.0 + } + calibration { + speed: 1.4 + acceleration: 3.02 + command: 50.0 + } + calibration { + speed: 1.6 + acceleration: -9.37 + command: -35.0 + } + calibration { + speed: 1.6 + acceleration: -7.6 + command: -33.0 + } + calibration { + speed: 1.6 + acceleration: -5.25 + command: -32.0 + } + calibration { + speed: 1.6 + acceleration: -4.63 + command: -31.0 + } + calibration { + speed: 1.6 + acceleration: -4.04 + command: -30.0 + } + calibration { + speed: 1.6 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 1.6 + acceleration: -2.94 + command: -28.0 + } + calibration { + speed: 1.6 + acceleration: -2.37 + command: -27.0 + } + calibration { + speed: 1.6 + acceleration: -1.73 + command: -26.0 + } + calibration { + speed: 1.6 + acceleration: -1.19 + command: -25.0 + } + calibration { + speed: 1.6 + acceleration: -0.77 + command: -24.0 + } + calibration { + speed: 1.6 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 1.6 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 1.6 + acceleration: 0.03 + command: -15.0 + } + calibration { + speed: 1.6 + acceleration: 0.04 + command: -4.33333333333 + } + calibration { + speed: 1.6 + acceleration: 0.06 + command: 15.0 + } + calibration { + speed: 1.6 + acceleration: 0.88 + command: 20.0 + } + calibration { + speed: 1.6 + acceleration: 1.85 + command: 25.0 + } + calibration { + speed: 1.6 + acceleration: 2.12 + command: 30.0 + } + calibration { + speed: 1.6 + acceleration: 2.33 + command: 27.0 + } + calibration { + speed: 1.6 + acceleration: 2.51 + command: 60.0 + } + calibration { + speed: 1.6 + acceleration: 2.87 + command: 35.0 + } + calibration { + speed: 1.6 + acceleration: 3.01 + command: 45.0 + } + calibration { + speed: 1.6 + acceleration: 3.02 + command: 40.0 + } + calibration { + speed: 1.6 + acceleration: 3.09 + command: 55.0 + } + calibration { + speed: 1.6 + acceleration: 3.12 + command: 50.0 + } + calibration { + speed: 1.8 + acceleration: -9.46 + command: -35.0 + } + calibration { + speed: 1.8 + acceleration: -7.47 + command: -33.0 + } + calibration { + speed: 1.8 + acceleration: -5.23 + command: -32.0 + } + calibration { + speed: 1.8 + acceleration: -4.66 + command: -31.0 + } + calibration { + speed: 1.8 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 1.8 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 1.8 + acceleration: -2.92 + command: -28.0 + } + calibration { + speed: 1.8 + acceleration: -2.32 + command: -27.0 + } + calibration { + speed: 1.8 + acceleration: -1.73 + command: -26.0 + } + calibration { + speed: 1.8 + acceleration: -1.2 + command: -25.0 + } + calibration { + speed: 1.8 + acceleration: -0.78 + command: -24.0 + } + calibration { + speed: 1.8 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 1.8 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 1.8 + acceleration: -0.03 + command: 15.0 + } + calibration { + speed: 1.8 + acceleration: -0.02 + command: 17.0 + } + calibration { + speed: 1.8 + acceleration: 0.03 + command: -13.0 + } + calibration { + speed: 1.8 + acceleration: 0.83 + command: 20.0 + } + calibration { + speed: 1.8 + acceleration: 1.86 + command: 25.0 + } + calibration { + speed: 1.8 + acceleration: 2.17 + command: 30.0 + } + calibration { + speed: 1.8 + acceleration: 2.37 + command: 27.0 + } + calibration { + speed: 1.8 + acceleration: 2.48 + command: 60.0 + } + calibration { + speed: 1.8 + acceleration: 2.95 + command: 35.0 + } + calibration { + speed: 1.8 + acceleration: 3.05 + command: 45.0 + } + calibration { + speed: 1.8 + acceleration: 3.11 + command: 40.0 + } + calibration { + speed: 1.8 + acceleration: 3.18 + command: 55.0 + } + calibration { + speed: 1.8 + acceleration: 3.21 + command: 50.0 + } + calibration { + speed: 2.0 + acceleration: -9.6 + command: -35.0 + } + calibration { + speed: 2.0 + acceleration: -7.35 + command: -33.0 + } + calibration { + speed: 2.0 + acceleration: -5.28 + command: -32.0 + } + calibration { + speed: 2.0 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 2.0 + acceleration: -4.1 + command: -30.0 + } + calibration { + speed: 2.0 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 2.0 + acceleration: -2.88 + command: -28.0 + } + calibration { + speed: 2.0 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 2.0 + acceleration: -1.71 + command: -26.0 + } + calibration { + speed: 2.0 + acceleration: -1.22 + command: -25.0 + } + calibration { + speed: 2.0 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 2.0 + acceleration: -0.62 + command: -23.0 + } + calibration { + speed: 2.0 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 2.0 + acceleration: -0.1 + command: -13.0 + } + calibration { + speed: 2.0 + acceleration: -0.09 + command: 5.66666666667 + } + calibration { + speed: 2.0 + acceleration: -0.08 + command: -17.0 + } + calibration { + speed: 2.0 + acceleration: 0.75 + command: 20.0 + } + calibration { + speed: 2.0 + acceleration: 1.85 + command: 25.0 + } + calibration { + speed: 2.0 + acceleration: 2.21 + command: 30.0 + } + calibration { + speed: 2.0 + acceleration: 2.37 + command: 27.0 + } + calibration { + speed: 2.0 + acceleration: 2.46 + command: 60.0 + } + calibration { + speed: 2.0 + acceleration: 3.01 + command: 35.0 + } + calibration { + speed: 2.0 + acceleration: 3.05 + command: 45.0 + } + calibration { + speed: 2.0 + acceleration: 3.16 + command: 40.0 + } + calibration { + speed: 2.0 + acceleration: 3.23 + command: 55.0 + } + calibration { + speed: 2.0 + acceleration: 3.28 + command: 50.0 + } + calibration { + speed: 2.2 + acceleration: -9.65 + command: -35.0 + } + calibration { + speed: 2.2 + acceleration: -7.31 + command: -33.0 + } + calibration { + speed: 2.2 + acceleration: -5.37 + command: -32.0 + } + calibration { + speed: 2.2 + acceleration: -4.81 + command: -31.0 + } + calibration { + speed: 2.2 + acceleration: -4.13 + command: -30.0 + } + calibration { + speed: 2.2 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 2.2 + acceleration: -2.85 + command: -28.0 + } + calibration { + speed: 2.2 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 2.2 + acceleration: -1.72 + command: -26.0 + } + calibration { + speed: 2.2 + acceleration: -1.19 + command: -25.0 + } + calibration { + speed: 2.2 + acceleration: -0.89 + command: -24.0 + } + calibration { + speed: 2.2 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 2.2 + acceleration: -0.17 + command: 19.5 + } + calibration { + speed: 2.2 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 2.2 + acceleration: -0.14 + command: 0.0 + } + calibration { + speed: 2.2 + acceleration: -0.13 + command: -17.0 + } + calibration { + speed: 2.2 + acceleration: 0.67 + command: 20.0 + } + calibration { + speed: 2.2 + acceleration: 1.81 + command: 25.0 + } + calibration { + speed: 2.2 + acceleration: 2.22 + command: 30.0 + } + calibration { + speed: 2.2 + acceleration: 2.34 + command: 27.0 + } + calibration { + speed: 2.2 + acceleration: 2.45 + command: 60.0 + } + calibration { + speed: 2.2 + acceleration: 3.03 + command: 45.0 + } + calibration { + speed: 2.2 + acceleration: 3.05 + command: 35.0 + } + calibration { + speed: 2.2 + acceleration: 3.19 + command: 40.0 + } + calibration { + speed: 2.2 + acceleration: 3.25 + command: 55.0 + } + calibration { + speed: 2.2 + acceleration: 3.33 + command: 50.0 + } + calibration { + speed: 2.4 + acceleration: -9.76 + command: -35.0 + } + calibration { + speed: 2.4 + acceleration: -7.33 + command: -33.0 + } + calibration { + speed: 2.4 + acceleration: -5.46 + command: -32.0 + } + calibration { + speed: 2.4 + acceleration: -4.86 + command: -31.0 + } + calibration { + speed: 2.4 + acceleration: -4.13 + command: -30.0 + } + calibration { + speed: 2.4 + acceleration: -3.52 + command: -29.0 + } + calibration { + speed: 2.4 + acceleration: -2.84 + command: -28.0 + } + calibration { + speed: 2.4 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 2.4 + acceleration: -1.74 + command: -26.0 + } + calibration { + speed: 2.4 + acceleration: -1.21 + command: -25.0 + } + calibration { + speed: 2.4 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 2.4 + acceleration: -0.6 + command: -23.0 + } + calibration { + speed: 2.4 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 2.4 + acceleration: -0.15 + command: 6.33333333333 + } + calibration { + speed: 2.4 + acceleration: -0.14 + command: -15.0 + } + calibration { + speed: 2.4 + acceleration: -0.13 + command: -17.0 + } + calibration { + speed: 2.4 + acceleration: 0.56 + command: 20.0 + } + calibration { + speed: 2.4 + acceleration: 1.71 + command: 25.0 + } + calibration { + speed: 2.4 + acceleration: 2.22 + command: 30.0 + } + calibration { + speed: 2.4 + acceleration: 2.27 + command: 27.0 + } + calibration { + speed: 2.4 + acceleration: 2.43 + command: 60.0 + } + calibration { + speed: 2.4 + acceleration: 2.98 + command: 45.0 + } + calibration { + speed: 2.4 + acceleration: 3.08 + command: 35.0 + } + calibration { + speed: 2.4 + acceleration: 3.2 + command: 40.0 + } + calibration { + speed: 2.4 + acceleration: 3.23 + command: 55.0 + } + calibration { + speed: 2.4 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 2.6 + acceleration: -9.78 + command: -35.0 + } + calibration { + speed: 2.6 + acceleration: -7.37 + command: -33.0 + } + calibration { + speed: 2.6 + acceleration: -5.52 + command: -32.0 + } + calibration { + speed: 2.6 + acceleration: -4.87 + command: -31.0 + } + calibration { + speed: 2.6 + acceleration: -4.12 + command: -30.0 + } + calibration { + speed: 2.6 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 2.6 + acceleration: -2.86 + command: -28.0 + } + calibration { + speed: 2.6 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 2.6 + acceleration: -1.72 + command: -26.0 + } + calibration { + speed: 2.6 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 2.6 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 2.6 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 2.6 + acceleration: -0.17 + command: 18.5 + } + calibration { + speed: 2.6 + acceleration: -0.16 + command: 17.0 + } + calibration { + speed: 2.6 + acceleration: -0.15 + command: -14.0 + } + calibration { + speed: 2.6 + acceleration: -0.13 + command: -17.0 + } + calibration { + speed: 2.6 + acceleration: 0.49 + command: 20.0 + } + calibration { + speed: 2.6 + acceleration: 1.58 + command: 25.0 + } + calibration { + speed: 2.6 + acceleration: 2.19 + command: 27.0 + } + calibration { + speed: 2.6 + acceleration: 2.22 + command: 30.0 + } + calibration { + speed: 2.6 + acceleration: 2.45 + command: 60.0 + } + calibration { + speed: 2.6 + acceleration: 2.9 + command: 45.0 + } + calibration { + speed: 2.6 + acceleration: 3.1 + command: 35.0 + } + calibration { + speed: 2.6 + acceleration: 3.16 + command: 55.0 + } + calibration { + speed: 2.6 + acceleration: 3.21 + command: 40.0 + } + calibration { + speed: 2.6 + acceleration: 3.36 + command: 50.0 + } + calibration { + speed: 2.8 + acceleration: -9.8 + command: -35.0 + } + calibration { + speed: 2.8 + acceleration: -7.47 + command: -33.0 + } + calibration { + speed: 2.8 + acceleration: -5.54 + command: -32.0 + } + calibration { + speed: 2.8 + acceleration: -4.84 + command: -31.0 + } + calibration { + speed: 2.8 + acceleration: -4.1 + command: -30.0 + } + calibration { + speed: 2.8 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 2.8 + acceleration: -2.9 + command: -28.0 + } + calibration { + speed: 2.8 + acceleration: -2.28 + command: -27.0 + } + calibration { + speed: 2.8 + acceleration: -1.74 + command: -26.0 + } + calibration { + speed: 2.8 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 2.8 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 2.8 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 2.8 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 2.8 + acceleration: -0.17 + command: 22.0 + } + calibration { + speed: 2.8 + acceleration: -0.16 + command: -4.33333333333 + } + calibration { + speed: 2.8 + acceleration: -0.14 + command: -15.0 + } + calibration { + speed: 2.8 + acceleration: 0.43 + command: 20.0 + } + calibration { + speed: 2.8 + acceleration: 1.5 + command: 25.0 + } + calibration { + speed: 2.8 + acceleration: 2.11 + command: 27.0 + } + calibration { + speed: 2.8 + acceleration: 2.22 + command: 30.0 + } + calibration { + speed: 2.8 + acceleration: 2.47 + command: 60.0 + } + calibration { + speed: 2.8 + acceleration: 2.81 + command: 45.0 + } + calibration { + speed: 2.8 + acceleration: 3.09 + command: 55.0 + } + calibration { + speed: 2.8 + acceleration: 3.12 + command: 35.0 + } + calibration { + speed: 2.8 + acceleration: 3.2 + command: 40.0 + } + calibration { + speed: 2.8 + acceleration: 3.36 + command: 50.0 + } + calibration { + speed: 3.0 + acceleration: -9.84 + command: -35.0 + } + calibration { + speed: 3.0 + acceleration: -7.54 + command: -33.0 + } + calibration { + speed: 3.0 + acceleration: -5.52 + command: -32.0 + } + calibration { + speed: 3.0 + acceleration: -4.8 + command: -31.0 + } + calibration { + speed: 3.0 + acceleration: -4.08 + command: -30.0 + } + calibration { + speed: 3.0 + acceleration: -3.58 + command: -29.0 + } + calibration { + speed: 3.0 + acceleration: -2.93 + command: -28.0 + } + calibration { + speed: 3.0 + acceleration: -2.23 + command: -27.0 + } + calibration { + speed: 3.0 + acceleration: -1.83 + command: -26.0 + } + calibration { + speed: 3.0 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 3.0 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 3.0 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 3.0 + acceleration: -0.18 + command: 18.5 + } + calibration { + speed: 3.0 + acceleration: -0.16 + command: -3.66666666667 + } + calibration { + speed: 3.0 + acceleration: -0.14 + command: -17.0 + } + calibration { + speed: 3.0 + acceleration: 0.38 + command: 20.0 + } + calibration { + speed: 3.0 + acceleration: 1.42 + command: 25.0 + } + calibration { + speed: 3.0 + acceleration: 2.02 + command: 27.0 + } + calibration { + speed: 3.0 + acceleration: 2.21 + command: 30.0 + } + calibration { + speed: 3.0 + acceleration: 2.47 + command: 60.0 + } + calibration { + speed: 3.0 + acceleration: 2.71 + command: 45.0 + } + calibration { + speed: 3.0 + acceleration: 2.99 + command: 55.0 + } + calibration { + speed: 3.0 + acceleration: 3.14 + command: 35.0 + } + calibration { + speed: 3.0 + acceleration: 3.21 + command: 40.0 + } + calibration { + speed: 3.0 + acceleration: 3.34 + command: 50.0 + } + calibration { + speed: 3.2 + acceleration: -9.86 + command: -35.0 + } + calibration { + speed: 3.2 + acceleration: -7.64 + command: -33.0 + } + calibration { + speed: 3.2 + acceleration: -5.46 + command: -32.0 + } + calibration { + speed: 3.2 + acceleration: -4.75 + command: -31.0 + } + calibration { + speed: 3.2 + acceleration: -4.08 + command: -30.0 + } + calibration { + speed: 3.2 + acceleration: -3.61 + command: -29.0 + } + calibration { + speed: 3.2 + acceleration: -2.93 + command: -28.0 + } + calibration { + speed: 3.2 + acceleration: -2.21 + command: -27.0 + } + calibration { + speed: 3.2 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 3.2 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 3.2 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 3.2 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 3.2 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 3.2 + acceleration: -0.18 + command: 16.0 + } + calibration { + speed: 3.2 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 3.2 + acceleration: 0.38 + command: 20.0 + } + calibration { + speed: 3.2 + acceleration: 1.35 + command: 25.0 + } + calibration { + speed: 3.2 + acceleration: 1.94 + command: 27.0 + } + calibration { + speed: 3.2 + acceleration: 2.19 + command: 30.0 + } + calibration { + speed: 3.2 + acceleration: 2.45 + command: 60.0 + } + calibration { + speed: 3.2 + acceleration: 2.66 + command: 45.0 + } + calibration { + speed: 3.2 + acceleration: 2.87 + command: 55.0 + } + calibration { + speed: 3.2 + acceleration: 3.16 + command: 35.0 + } + calibration { + speed: 3.2 + acceleration: 3.23 + command: 40.0 + } + calibration { + speed: 3.2 + acceleration: 3.32 + command: 50.0 + } + calibration { + speed: 3.4 + acceleration: -9.88 + command: -35.0 + } + calibration { + speed: 3.4 + acceleration: -7.7 + command: -33.0 + } + calibration { + speed: 3.4 + acceleration: -5.41 + command: -32.0 + } + calibration { + speed: 3.4 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 3.4 + acceleration: -4.09 + command: -30.0 + } + calibration { + speed: 3.4 + acceleration: -3.61 + command: -29.0 + } + calibration { + speed: 3.4 + acceleration: -2.91 + command: -28.0 + } + calibration { + speed: 3.4 + acceleration: -2.24 + command: -27.0 + } + calibration { + speed: 3.4 + acceleration: -1.84 + command: -26.0 + } + calibration { + speed: 3.4 + acceleration: -1.28 + command: -25.0 + } + calibration { + speed: 3.4 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 3.4 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 3.4 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 3.4 + acceleration: -0.18 + command: -2.6 + } + calibration { + speed: 3.4 + acceleration: 0.33 + command: 20.0 + } + calibration { + speed: 3.4 + acceleration: 1.29 + command: 25.0 + } + calibration { + speed: 3.4 + acceleration: 1.85 + command: 27.0 + } + calibration { + speed: 3.4 + acceleration: 2.14 + command: 30.0 + } + calibration { + speed: 3.4 + acceleration: 2.44 + command: 60.0 + } + calibration { + speed: 3.4 + acceleration: 2.66 + command: 45.0 + } + calibration { + speed: 3.4 + acceleration: 2.76 + command: 55.0 + } + calibration { + speed: 3.4 + acceleration: 3.16 + command: 35.0 + } + calibration { + speed: 3.4 + acceleration: 3.26 + command: 40.0 + } + calibration { + speed: 3.4 + acceleration: 3.28 + command: 50.0 + } + calibration { + speed: 3.6 + acceleration: -9.9 + command: -35.0 + } + calibration { + speed: 3.6 + acceleration: -7.74 + command: -33.0 + } + calibration { + speed: 3.6 + acceleration: -5.36 + command: -32.0 + } + calibration { + speed: 3.6 + acceleration: -4.7 + command: -31.0 + } + calibration { + speed: 3.6 + acceleration: -4.1 + command: -30.0 + } + calibration { + speed: 3.6 + acceleration: -3.58 + command: -29.0 + } + calibration { + speed: 3.6 + acceleration: -2.89 + command: -28.0 + } + calibration { + speed: 3.6 + acceleration: -2.27 + command: -27.0 + } + calibration { + speed: 3.6 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 3.6 + acceleration: -1.29 + command: -25.0 + } + calibration { + speed: 3.6 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 3.6 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 3.6 + acceleration: -0.2 + command: 18.5 + } + calibration { + speed: 3.6 + acceleration: -0.19 + command: 17.0 + } + calibration { + speed: 3.6 + acceleration: -0.17 + command: -13.0 + } + calibration { + speed: 3.6 + acceleration: -0.16 + command: -16.0 + } + calibration { + speed: 3.6 + acceleration: 0.31 + command: 20.0 + } + calibration { + speed: 3.6 + acceleration: 1.19 + command: 25.0 + } + calibration { + speed: 3.6 + acceleration: 1.75 + command: 27.0 + } + calibration { + speed: 3.6 + acceleration: 2.07 + command: 30.0 + } + calibration { + speed: 3.6 + acceleration: 2.44 + command: 60.0 + } + calibration { + speed: 3.6 + acceleration: 2.7 + command: 55.0 + } + calibration { + speed: 3.6 + acceleration: 2.75 + command: 45.0 + } + calibration { + speed: 3.6 + acceleration: 3.14 + command: 35.0 + } + calibration { + speed: 3.6 + acceleration: 3.26 + command: 50.0 + } + calibration { + speed: 3.6 + acceleration: 3.29 + command: 40.0 + } + calibration { + speed: 3.8 + acceleration: -9.9 + command: -35.0 + } + calibration { + speed: 3.8 + acceleration: -7.77 + command: -33.0 + } + calibration { + speed: 3.8 + acceleration: -5.33 + command: -32.0 + } + calibration { + speed: 3.8 + acceleration: -4.71 + command: -31.0 + } + calibration { + speed: 3.8 + acceleration: -4.13 + command: -30.0 + } + calibration { + speed: 3.8 + acceleration: -3.54 + command: -29.0 + } + calibration { + speed: 3.8 + acceleration: -2.9 + command: -28.0 + } + calibration { + speed: 3.8 + acceleration: -2.28 + command: -27.0 + } + calibration { + speed: 3.8 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 3.8 + acceleration: -1.29 + command: -25.0 + } + calibration { + speed: 3.8 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 3.8 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 3.8 + acceleration: -0.2 + command: 19.5 + } + calibration { + speed: 3.8 + acceleration: -0.19 + command: 15.0 + } + calibration { + speed: 3.8 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 3.8 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 3.8 + acceleration: 0.31 + command: 20.0 + } + calibration { + speed: 3.8 + acceleration: 1.1 + command: 25.0 + } + calibration { + speed: 3.8 + acceleration: 1.66 + command: 27.0 + } + calibration { + speed: 3.8 + acceleration: 1.99 + command: 30.0 + } + calibration { + speed: 3.8 + acceleration: 2.47 + command: 60.0 + } + calibration { + speed: 3.8 + acceleration: 2.74 + command: 55.0 + } + calibration { + speed: 3.8 + acceleration: 2.89 + command: 45.0 + } + calibration { + speed: 3.8 + acceleration: 3.09 + command: 35.0 + } + calibration { + speed: 3.8 + acceleration: 3.26 + command: 50.0 + } + calibration { + speed: 3.8 + acceleration: 3.31 + command: 40.0 + } + calibration { + speed: 4.0 + acceleration: -9.9 + command: -35.0 + } + calibration { + speed: 4.0 + acceleration: -7.78 + command: -33.0 + } + calibration { + speed: 4.0 + acceleration: -5.32 + command: -32.0 + } + calibration { + speed: 4.0 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 4.0 + acceleration: -4.15 + command: -30.0 + } + calibration { + speed: 4.0 + acceleration: -3.51 + command: -29.0 + } + calibration { + speed: 4.0 + acceleration: -2.95 + command: -28.0 + } + calibration { + speed: 4.0 + acceleration: -2.28 + command: -27.0 + } + calibration { + speed: 4.0 + acceleration: -1.87 + command: -26.0 + } + calibration { + speed: 4.0 + acceleration: -1.28 + command: -25.0 + } + calibration { + speed: 4.0 + acceleration: -0.89 + command: -24.0 + } + calibration { + speed: 4.0 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 4.0 + acceleration: -0.21 + command: 17.0 + } + calibration { + speed: 4.0 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 4.0 + acceleration: -0.19 + command: -1.0 + } + calibration { + speed: 4.0 + acceleration: -0.18 + command: -14.0 + } + calibration { + speed: 4.0 + acceleration: 0.28 + command: 20.0 + } + calibration { + speed: 4.0 + acceleration: 1.02 + command: 25.0 + } + calibration { + speed: 4.0 + acceleration: 1.55 + command: 27.0 + } + calibration { + speed: 4.0 + acceleration: 1.9 + command: 30.0 + } + calibration { + speed: 4.0 + acceleration: 2.52 + command: 60.0 + } + calibration { + speed: 4.0 + acceleration: 2.86 + command: 55.0 + } + calibration { + speed: 4.0 + acceleration: 3.01 + command: 35.0 + } + calibration { + speed: 4.0 + acceleration: 3.03 + command: 45.0 + } + calibration { + speed: 4.0 + acceleration: 3.29 + command: 50.0 + } + calibration { + speed: 4.0 + acceleration: 3.33 + command: 40.0 + } + calibration { + speed: 4.2 + acceleration: -9.87 + command: -35.0 + } + calibration { + speed: 4.2 + acceleration: -7.79 + command: -33.0 + } + calibration { + speed: 4.2 + acceleration: -5.33 + command: -32.0 + } + calibration { + speed: 4.2 + acceleration: -4.74 + command: -31.0 + } + calibration { + speed: 4.2 + acceleration: -4.15 + command: -30.0 + } + calibration { + speed: 4.2 + acceleration: -3.5 + command: -29.0 + } + calibration { + speed: 4.2 + acceleration: -3.0 + command: -28.0 + } + calibration { + speed: 4.2 + acceleration: -2.28 + command: -27.0 + } + calibration { + speed: 4.2 + acceleration: -1.87 + command: -26.0 + } + calibration { + speed: 4.2 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 4.2 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 4.2 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 4.2 + acceleration: -0.2 + command: 7.33333333333 + } + calibration { + speed: 4.2 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 4.2 + acceleration: -0.17 + command: 0.0 + } + calibration { + speed: 4.2 + acceleration: 0.28 + command: 20.0 + } + calibration { + speed: 4.2 + acceleration: 0.95 + command: 25.0 + } + calibration { + speed: 4.2 + acceleration: 1.43 + command: 27.0 + } + calibration { + speed: 4.2 + acceleration: 1.8 + command: 30.0 + } + calibration { + speed: 4.2 + acceleration: 2.57 + command: 60.0 + } + calibration { + speed: 4.2 + acceleration: 2.93 + command: 35.0 + } + calibration { + speed: 4.2 + acceleration: 3.03 + command: 55.0 + } + calibration { + speed: 4.2 + acceleration: 3.14 + command: 45.0 + } + calibration { + speed: 4.2 + acceleration: 3.32 + command: 40.0 + } + calibration { + speed: 4.2 + acceleration: 3.33 + command: 50.0 + } + calibration { + speed: 4.4 + acceleration: -9.86 + command: -35.0 + } + calibration { + speed: 4.4 + acceleration: -7.79 + command: -33.0 + } + calibration { + speed: 4.4 + acceleration: -5.36 + command: -32.0 + } + calibration { + speed: 4.4 + acceleration: -4.75 + command: -31.0 + } + calibration { + speed: 4.4 + acceleration: -4.13 + command: -30.0 + } + calibration { + speed: 4.4 + acceleration: -3.51 + command: -29.0 + } + calibration { + speed: 4.4 + acceleration: -3.04 + command: -28.0 + } + calibration { + speed: 4.4 + acceleration: -2.29 + command: -27.0 + } + calibration { + speed: 4.4 + acceleration: -1.87 + command: -26.0 + } + calibration { + speed: 4.4 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 4.4 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 4.4 + acceleration: -0.58 + command: -23.0 + } + calibration { + speed: 4.4 + acceleration: -0.22 + command: 17.0 + } + calibration { + speed: 4.4 + acceleration: -0.21 + command: 15.0 + } + calibration { + speed: 4.4 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 4.4 + acceleration: -0.19 + command: -17.0 + } + calibration { + speed: 4.4 + acceleration: -0.18 + command: -14.0 + } + calibration { + speed: 4.4 + acceleration: 0.26 + command: 20.0 + } + calibration { + speed: 4.4 + acceleration: 0.86 + command: 25.0 + } + calibration { + speed: 4.4 + acceleration: 1.33 + command: 27.0 + } + calibration { + speed: 4.4 + acceleration: 1.71 + command: 30.0 + } + calibration { + speed: 4.4 + acceleration: 2.62 + command: 60.0 + } + calibration { + speed: 4.4 + acceleration: 2.84 + command: 35.0 + } + calibration { + speed: 4.4 + acceleration: 3.2 + command: 45.0 + } + calibration { + speed: 4.4 + acceleration: 3.21 + command: 55.0 + } + calibration { + speed: 4.4 + acceleration: 3.3 + command: 40.0 + } + calibration { + speed: 4.4 + acceleration: 3.39 + command: 50.0 + } + calibration { + speed: 4.6 + acceleration: -9.84 + command: -35.0 + } + calibration { + speed: 4.6 + acceleration: -7.8 + command: -33.0 + } + calibration { + speed: 4.6 + acceleration: -5.39 + command: -32.0 + } + calibration { + speed: 4.6 + acceleration: -4.74 + command: -31.0 + } + calibration { + speed: 4.6 + acceleration: -4.1 + command: -30.0 + } + calibration { + speed: 4.6 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 4.6 + acceleration: -3.04 + command: -28.0 + } + calibration { + speed: 4.6 + acceleration: -2.29 + command: -27.0 + } + calibration { + speed: 4.6 + acceleration: -1.88 + command: -26.0 + } + calibration { + speed: 4.6 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 4.6 + acceleration: -0.89 + command: -24.0 + } + calibration { + speed: 4.6 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 4.6 + acceleration: -0.21 + command: 17.0 + } + calibration { + speed: 4.6 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 4.6 + acceleration: -0.19 + command: -5.0 + } + calibration { + speed: 4.6 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 4.6 + acceleration: 0.19 + command: 20.0 + } + calibration { + speed: 4.6 + acceleration: 0.79 + command: 25.0 + } + calibration { + speed: 4.6 + acceleration: 1.21 + command: 27.0 + } + calibration { + speed: 4.6 + acceleration: 1.58 + command: 30.0 + } + calibration { + speed: 4.6 + acceleration: 2.66 + command: 60.0 + } + calibration { + speed: 4.6 + acceleration: 2.75 + command: 35.0 + } + calibration { + speed: 4.6 + acceleration: 3.22 + command: 45.0 + } + calibration { + speed: 4.6 + acceleration: 3.26 + command: 40.0 + } + calibration { + speed: 4.6 + acceleration: 3.32 + command: 55.0 + } + calibration { + speed: 4.6 + acceleration: 3.44 + command: 50.0 + } + calibration { + speed: 4.8 + acceleration: -9.81 + command: -35.0 + } + calibration { + speed: 4.8 + acceleration: -7.81 + command: -33.0 + } + calibration { + speed: 4.8 + acceleration: -5.41 + command: -32.0 + } + calibration { + speed: 4.8 + acceleration: -4.73 + command: -31.0 + } + calibration { + speed: 4.8 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 4.8 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 4.8 + acceleration: -3.04 + command: -28.0 + } + calibration { + speed: 4.8 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 4.8 + acceleration: -1.89 + command: -26.0 + } + calibration { + speed: 4.8 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 4.8 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 4.8 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 4.8 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 4.8 + acceleration: -0.19 + command: 0.5 + } + calibration { + speed: 4.8 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 4.8 + acceleration: 0.19 + command: 20.0 + } + calibration { + speed: 4.8 + acceleration: 0.73 + command: 25.0 + } + calibration { + speed: 4.8 + acceleration: 1.1 + command: 27.0 + } + calibration { + speed: 4.8 + acceleration: 1.45 + command: 30.0 + } + calibration { + speed: 4.8 + acceleration: 2.66 + command: 35.0 + } + calibration { + speed: 4.8 + acceleration: 2.72 + command: 60.0 + } + calibration { + speed: 4.8 + acceleration: 3.21 + command: 45.0 + } + calibration { + speed: 4.8 + acceleration: 3.22 + command: 40.0 + } + calibration { + speed: 4.8 + acceleration: 3.4 + command: 55.0 + } + calibration { + speed: 4.8 + acceleration: 3.48 + command: 50.0 + } + calibration { + speed: 5.0 + acceleration: -9.79 + command: -35.0 + } + calibration { + speed: 5.0 + acceleration: -7.82 + command: -33.0 + } + calibration { + speed: 5.0 + acceleration: -5.42 + command: -32.0 + } + calibration { + speed: 5.0 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 5.0 + acceleration: -4.05 + command: -30.0 + } + calibration { + speed: 5.0 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 5.0 + acceleration: -3.04 + command: -28.0 + } + calibration { + speed: 5.0 + acceleration: -2.29 + command: -27.0 + } + calibration { + speed: 5.0 + acceleration: -1.89 + command: -26.0 + } + calibration { + speed: 5.0 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 5.0 + acceleration: -0.89 + command: -24.0 + } + calibration { + speed: 5.0 + acceleration: -0.6 + command: -23.0 + } + calibration { + speed: 5.0 + acceleration: -0.2 + command: 2.5 + } + calibration { + speed: 5.0 + acceleration: -0.19 + command: 2.0 + } + calibration { + speed: 5.0 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 5.0 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 5.0 + acceleration: 0.18 + command: 20.0 + } + calibration { + speed: 5.0 + acceleration: 0.66 + command: 25.0 + } + calibration { + speed: 5.0 + acceleration: 1.01 + command: 27.0 + } + calibration { + speed: 5.0 + acceleration: 1.34 + command: 30.0 + } + calibration { + speed: 5.0 + acceleration: 2.56 + command: 35.0 + } + calibration { + speed: 5.0 + acceleration: 2.77 + command: 60.0 + } + calibration { + speed: 5.0 + acceleration: 3.18 + command: 40.0 + } + calibration { + speed: 5.0 + acceleration: 3.19 + command: 45.0 + } + calibration { + speed: 5.0 + acceleration: 3.45 + command: 55.0 + } + calibration { + speed: 5.0 + acceleration: 3.5 + command: 50.0 + } + calibration { + speed: 5.2 + acceleration: -9.73 + command: -35.0 + } + calibration { + speed: 5.2 + acceleration: -7.86 + command: -33.0 + } + calibration { + speed: 5.2 + acceleration: -5.41 + command: -32.0 + } + calibration { + speed: 5.2 + acceleration: -4.69 + command: -31.0 + } + calibration { + speed: 5.2 + acceleration: -4.04 + command: -30.0 + } + calibration { + speed: 5.2 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 5.2 + acceleration: -3.04 + command: -28.0 + } + calibration { + speed: 5.2 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 5.2 + acceleration: -1.89 + command: -26.0 + } + calibration { + speed: 5.2 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 5.2 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 5.2 + acceleration: -0.6 + command: -23.0 + } + calibration { + speed: 5.2 + acceleration: -0.24 + command: 16.0 + } + calibration { + speed: 5.2 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 5.2 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 5.2 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 5.2 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 5.2 + acceleration: 0.16 + command: 20.0 + } + calibration { + speed: 5.2 + acceleration: 0.62 + command: 25.0 + } + calibration { + speed: 5.2 + acceleration: 0.94 + command: 27.0 + } + calibration { + speed: 5.2 + acceleration: 1.26 + command: 30.0 + } + calibration { + speed: 5.2 + acceleration: 2.47 + command: 35.0 + } + calibration { + speed: 5.2 + acceleration: 2.81 + command: 60.0 + } + calibration { + speed: 5.2 + acceleration: 3.13 + command: 40.0 + } + calibration { + speed: 5.2 + acceleration: 3.17 + command: 45.0 + } + calibration { + speed: 5.2 + acceleration: 3.47 + command: 55.0 + } + calibration { + speed: 5.2 + acceleration: 3.5 + command: 50.0 + } + calibration { + speed: 5.4 + acceleration: -9.67 + command: -35.0 + } + calibration { + speed: 5.4 + acceleration: -7.89 + command: -33.0 + } + calibration { + speed: 5.4 + acceleration: -5.39 + command: -32.0 + } + calibration { + speed: 5.4 + acceleration: -4.68 + command: -31.0 + } + calibration { + speed: 5.4 + acceleration: -4.05 + command: -30.0 + } + calibration { + speed: 5.4 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 5.4 + acceleration: -3.03 + command: -28.0 + } + calibration { + speed: 5.4 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 5.4 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 5.4 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 5.4 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 5.4 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 5.4 + acceleration: -0.23 + command: 17.0 + } + calibration { + speed: 5.4 + acceleration: -0.21 + command: -1.0 + } + calibration { + speed: 5.4 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 5.4 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 5.4 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 5.4 + acceleration: 0.16 + command: 20.0 + } + calibration { + speed: 5.4 + acceleration: 0.59 + command: 25.0 + } + calibration { + speed: 5.4 + acceleration: 0.89 + command: 27.0 + } + calibration { + speed: 5.4 + acceleration: 1.19 + command: 30.0 + } + calibration { + speed: 5.4 + acceleration: 2.38 + command: 35.0 + } + calibration { + speed: 5.4 + acceleration: 2.84 + command: 60.0 + } + calibration { + speed: 5.4 + acceleration: 3.07 + command: 40.0 + } + calibration { + speed: 5.4 + acceleration: 3.16 + command: 45.0 + } + calibration { + speed: 5.4 + acceleration: 3.47 + command: 55.0 + } + calibration { + speed: 5.4 + acceleration: 3.48 + command: 50.0 + } + calibration { + speed: 5.6 + acceleration: -9.65 + command: -35.0 + } + calibration { + speed: 5.6 + acceleration: -7.94 + command: -33.0 + } + calibration { + speed: 5.6 + acceleration: -5.35 + command: -32.0 + } + calibration { + speed: 5.6 + acceleration: -4.67 + command: -31.0 + } + calibration { + speed: 5.6 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 5.6 + acceleration: -3.54 + command: -29.0 + } + calibration { + speed: 5.6 + acceleration: -3.02 + command: -28.0 + } + calibration { + speed: 5.6 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 5.6 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 5.6 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 5.6 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 5.6 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 5.6 + acceleration: -0.23 + command: 16.0 + } + calibration { + speed: 5.6 + acceleration: -0.22 + command: -17.0 + } + calibration { + speed: 5.6 + acceleration: -0.2 + command: 4.5 + } + calibration { + speed: 5.6 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 5.6 + acceleration: 0.15 + command: 20.0 + } + calibration { + speed: 5.6 + acceleration: 0.56 + command: 25.0 + } + calibration { + speed: 5.6 + acceleration: 0.85 + command: 27.0 + } + calibration { + speed: 5.6 + acceleration: 1.13 + command: 30.0 + } + calibration { + speed: 5.6 + acceleration: 2.3 + command: 35.0 + } + calibration { + speed: 5.6 + acceleration: 2.85 + command: 60.0 + } + calibration { + speed: 5.6 + acceleration: 3.01 + command: 40.0 + } + calibration { + speed: 5.6 + acceleration: 3.15 + command: 45.0 + } + calibration { + speed: 5.6 + acceleration: 3.43 + command: 50.0 + } + calibration { + speed: 5.6 + acceleration: 3.46 + command: 55.0 + } + calibration { + speed: 5.8 + acceleration: -9.6 + command: -35.0 + } + calibration { + speed: 5.8 + acceleration: -7.97 + command: -33.0 + } + calibration { + speed: 5.8 + acceleration: -5.32 + command: -32.0 + } + calibration { + speed: 5.8 + acceleration: -4.67 + command: -31.0 + } + calibration { + speed: 5.8 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 5.8 + acceleration: -3.54 + command: -29.0 + } + calibration { + speed: 5.8 + acceleration: -3.01 + command: -28.0 + } + calibration { + speed: 5.8 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 5.8 + acceleration: -1.89 + command: -26.0 + } + calibration { + speed: 5.8 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 5.8 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 5.8 + acceleration: -0.6 + command: -23.0 + } + calibration { + speed: 5.8 + acceleration: -0.24 + command: 15.0 + } + calibration { + speed: 5.8 + acceleration: -0.21 + command: 17.0 + } + calibration { + speed: 5.8 + acceleration: -0.2 + command: 2.5 + } + calibration { + speed: 5.8 + acceleration: -0.19 + command: -15.0 + } + calibration { + speed: 5.8 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 5.8 + acceleration: 0.14 + command: 20.0 + } + calibration { + speed: 5.8 + acceleration: 0.55 + command: 25.0 + } + calibration { + speed: 5.8 + acceleration: 0.82 + command: 27.0 + } + calibration { + speed: 5.8 + acceleration: 1.07 + command: 30.0 + } + calibration { + speed: 5.8 + acceleration: 2.22 + command: 35.0 + } + calibration { + speed: 5.8 + acceleration: 2.85 + command: 60.0 + } + calibration { + speed: 5.8 + acceleration: 2.94 + command: 40.0 + } + calibration { + speed: 5.8 + acceleration: 3.14 + command: 45.0 + } + calibration { + speed: 5.8 + acceleration: 3.38 + command: 50.0 + } + calibration { + speed: 5.8 + acceleration: 3.44 + command: 55.0 + } + calibration { + speed: 6.0 + acceleration: -9.58 + command: -35.0 + } + calibration { + speed: 6.0 + acceleration: -8.0 + command: -33.0 + } + calibration { + speed: 6.0 + acceleration: -5.29 + command: -32.0 + } + calibration { + speed: 6.0 + acceleration: -4.68 + command: -31.0 + } + calibration { + speed: 6.0 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 6.0 + acceleration: -3.54 + command: -29.0 + } + calibration { + speed: 6.0 + acceleration: -3.0 + command: -28.0 + } + calibration { + speed: 6.0 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 6.0 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 6.0 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 6.0 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.0 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 6.0 + acceleration: -0.23 + command: 17.0 + } + calibration { + speed: 6.0 + acceleration: -0.22 + command: -17.0 + } + calibration { + speed: 6.0 + acceleration: -0.2 + command: 18.5 + } + calibration { + speed: 6.0 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 6.0 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 6.0 + acceleration: 0.13 + command: 20.0 + } + calibration { + speed: 6.0 + acceleration: 0.53 + command: 25.0 + } + calibration { + speed: 6.0 + acceleration: 0.78 + command: 27.0 + } + calibration { + speed: 6.0 + acceleration: 1.03 + command: 30.0 + } + calibration { + speed: 6.0 + acceleration: 2.15 + command: 35.0 + } + calibration { + speed: 6.0 + acceleration: 2.84 + command: 60.0 + } + calibration { + speed: 6.0 + acceleration: 2.87 + command: 40.0 + } + calibration { + speed: 6.0 + acceleration: 3.11 + command: 45.0 + } + calibration { + speed: 6.0 + acceleration: 3.33 + command: 50.0 + } + calibration { + speed: 6.0 + acceleration: 3.41 + command: 55.0 + } + calibration { + speed: 6.2 + acceleration: -9.52 + command: -35.0 + } + calibration { + speed: 6.2 + acceleration: -8.01 + command: -33.0 + } + calibration { + speed: 6.2 + acceleration: -5.28 + command: -32.0 + } + calibration { + speed: 6.2 + acceleration: -4.69 + command: -31.0 + } + calibration { + speed: 6.2 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 6.2 + acceleration: -3.54 + command: -29.0 + } + calibration { + speed: 6.2 + acceleration: -2.99 + command: -28.0 + } + calibration { + speed: 6.2 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 6.2 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 6.2 + acceleration: -1.33 + command: -25.0 + } + calibration { + speed: 6.2 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 6.2 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 6.2 + acceleration: -0.25 + command: 17.0 + } + calibration { + speed: 6.2 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 6.2 + acceleration: -0.2 + command: 4.5 + } + calibration { + speed: 6.2 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 6.2 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 6.2 + acceleration: 0.11 + command: 20.0 + } + calibration { + speed: 6.2 + acceleration: 0.51 + command: 25.0 + } + calibration { + speed: 6.2 + acceleration: 0.77 + command: 27.0 + } + calibration { + speed: 6.2 + acceleration: 0.98 + command: 30.0 + } + calibration { + speed: 6.2 + acceleration: 2.08 + command: 35.0 + } + calibration { + speed: 6.2 + acceleration: 2.81 + command: 40.0 + } + calibration { + speed: 6.2 + acceleration: 2.83 + command: 60.0 + } + calibration { + speed: 6.2 + acceleration: 3.06 + command: 45.0 + } + calibration { + speed: 6.2 + acceleration: 3.27 + command: 50.0 + } + calibration { + speed: 6.2 + acceleration: 3.37 + command: 55.0 + } + calibration { + speed: 6.4 + acceleration: -9.5 + command: -35.0 + } + calibration { + speed: 6.4 + acceleration: -8.01 + command: -33.0 + } + calibration { + speed: 6.4 + acceleration: -5.27 + command: -32.0 + } + calibration { + speed: 6.4 + acceleration: -4.7 + command: -31.0 + } + calibration { + speed: 6.4 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 6.4 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 6.4 + acceleration: -2.99 + command: -28.0 + } + calibration { + speed: 6.4 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 6.4 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 6.4 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 6.4 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 6.4 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 6.4 + acceleration: -0.22 + command: 17.0 + } + calibration { + speed: 6.4 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 6.4 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 6.4 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 6.4 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 6.4 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 6.4 + acceleration: 0.1 + command: 20.0 + } + calibration { + speed: 6.4 + acceleration: 0.48 + command: 25.0 + } + calibration { + speed: 6.4 + acceleration: 0.72 + command: 27.0 + } + calibration { + speed: 6.4 + acceleration: 0.95 + command: 30.0 + } + calibration { + speed: 6.4 + acceleration: 2.02 + command: 35.0 + } + calibration { + speed: 6.4 + acceleration: 2.75 + command: 40.0 + } + calibration { + speed: 6.4 + acceleration: 2.82 + command: 60.0 + } + calibration { + speed: 6.4 + acceleration: 2.99 + command: 45.0 + } + calibration { + speed: 6.4 + acceleration: 3.22 + command: 50.0 + } + calibration { + speed: 6.4 + acceleration: 3.33 + command: 55.0 + } + calibration { + speed: 6.6 + acceleration: -9.48 + command: -35.0 + } + calibration { + speed: 6.6 + acceleration: -7.99 + command: -33.0 + } + calibration { + speed: 6.6 + acceleration: -5.27 + command: -32.0 + } + calibration { + speed: 6.6 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 6.6 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 6.6 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 6.6 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 6.6 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 6.6 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 6.6 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 6.6 + acceleration: -0.92 + command: -24.0 + } + calibration { + speed: 6.6 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 6.6 + acceleration: -0.23 + command: 17.0 + } + calibration { + speed: 6.6 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 6.6 + acceleration: -0.2 + command: 4.5 + } + calibration { + speed: 6.6 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 6.6 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 6.6 + acceleration: 0.1 + command: 20.0 + } + calibration { + speed: 6.6 + acceleration: 0.46 + command: 25.0 + } + calibration { + speed: 6.6 + acceleration: 0.72 + command: 27.0 + } + calibration { + speed: 6.6 + acceleration: 0.92 + command: 30.0 + } + calibration { + speed: 6.6 + acceleration: 1.95 + command: 35.0 + } + calibration { + speed: 6.6 + acceleration: 2.69 + command: 40.0 + } + calibration { + speed: 6.6 + acceleration: 2.81 + command: 60.0 + } + calibration { + speed: 6.6 + acceleration: 2.93 + command: 45.0 + } + calibration { + speed: 6.6 + acceleration: 3.17 + command: 50.0 + } + calibration { + speed: 6.6 + acceleration: 3.28 + command: 55.0 + } + calibration { + speed: 6.8 + acceleration: -9.48 + command: -35.0 + } + calibration { + speed: 6.8 + acceleration: -7.94 + command: -33.0 + } + calibration { + speed: 6.8 + acceleration: -5.26 + command: -32.0 + } + calibration { + speed: 6.8 + acceleration: -4.73 + command: -31.0 + } + calibration { + speed: 6.8 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 6.8 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 6.8 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 6.8 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 6.8 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 6.8 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 6.8 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.8 + acceleration: -0.63 + command: -23.0 + } + calibration { + speed: 6.8 + acceleration: -0.25 + command: 17.0 + } + calibration { + speed: 6.8 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 6.8 + acceleration: -0.2 + command: 4.5 + } + calibration { + speed: 6.8 + acceleration: -0.19 + command: -15.0 + } + calibration { + speed: 6.8 + acceleration: -0.17 + command: 15.0 + } + calibration { + speed: 6.8 + acceleration: 0.06 + command: 20.0 + } + calibration { + speed: 6.8 + acceleration: 0.43 + command: 25.0 + } + calibration { + speed: 6.8 + acceleration: 0.69 + command: 27.0 + } + calibration { + speed: 6.8 + acceleration: 0.9 + command: 30.0 + } + calibration { + speed: 6.8 + acceleration: 1.89 + command: 35.0 + } + calibration { + speed: 6.8 + acceleration: 2.62 + command: 40.0 + } + calibration { + speed: 6.8 + acceleration: 2.79 + command: 60.0 + } + calibration { + speed: 6.8 + acceleration: 2.87 + command: 45.0 + } + calibration { + speed: 6.8 + acceleration: 3.13 + command: 50.0 + } + calibration { + speed: 6.8 + acceleration: 3.23 + command: 55.0 + } + calibration { + speed: 7.0 + acceleration: -9.51 + command: -35.0 + } + calibration { + speed: 7.0 + acceleration: -7.88 + command: -33.0 + } + calibration { + speed: 7.0 + acceleration: -5.24 + command: -32.0 + } + calibration { + speed: 7.0 + acceleration: -4.73 + command: -31.0 + } + calibration { + speed: 7.0 + acceleration: -4.08 + command: -30.0 + } + calibration { + speed: 7.0 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 7.0 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 7.0 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 7.0 + acceleration: -1.91 + command: -26.0 + } + calibration { + speed: 7.0 + acceleration: -1.36 + command: -25.0 + } + calibration { + speed: 7.0 + acceleration: -0.93 + command: -24.0 + } + calibration { + speed: 7.0 + acceleration: -0.62 + command: -23.0 + } + calibration { + speed: 7.0 + acceleration: -0.24 + command: 17.0 + } + calibration { + speed: 7.0 + acceleration: -0.21 + command: -15.0 + } + calibration { + speed: 7.0 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 7.0 + acceleration: -0.19 + command: -15.0 + } + calibration { + speed: 7.0 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 7.0 + acceleration: 0.07 + command: 20.0 + } + calibration { + speed: 7.0 + acceleration: 0.42 + command: 25.0 + } + calibration { + speed: 7.0 + acceleration: 0.66 + command: 27.0 + } + calibration { + speed: 7.0 + acceleration: 0.87 + command: 30.0 + } + calibration { + speed: 7.0 + acceleration: 1.83 + command: 35.0 + } + calibration { + speed: 7.0 + acceleration: 2.55 + command: 40.0 + } + calibration { + speed: 7.0 + acceleration: 2.77 + command: 60.0 + } + calibration { + speed: 7.0 + acceleration: 2.81 + command: 45.0 + } + calibration { + speed: 7.0 + acceleration: 3.07 + command: 50.0 + } + calibration { + speed: 7.0 + acceleration: 3.18 + command: 55.0 + } + calibration { + speed: 7.2 + acceleration: -9.53 + command: -35.0 + } + calibration { + speed: 7.2 + acceleration: -7.83 + command: -33.0 + } + calibration { + speed: 7.2 + acceleration: -5.22 + command: -32.0 + } + calibration { + speed: 7.2 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 7.2 + acceleration: -4.09 + command: -30.0 + } + calibration { + speed: 7.2 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 7.2 + acceleration: -2.99 + command: -28.0 + } + calibration { + speed: 7.2 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 7.2 + acceleration: -1.91 + command: -26.0 + } + calibration { + speed: 7.2 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 7.2 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 7.2 + acceleration: -0.64 + command: -23.0 + } + calibration { + speed: 7.2 + acceleration: -0.25 + command: 17.0 + } + calibration { + speed: 7.2 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 7.2 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 7.2 + acceleration: -0.19 + command: -14.0 + } + calibration { + speed: 7.2 + acceleration: -0.17 + command: 15.0 + } + calibration { + speed: 7.2 + acceleration: 0.04 + command: 20.0 + } + calibration { + speed: 7.2 + acceleration: 0.43 + command: 25.0 + } + calibration { + speed: 7.2 + acceleration: 0.65 + command: 27.0 + } + calibration { + speed: 7.2 + acceleration: 0.84 + command: 30.0 + } + calibration { + speed: 7.2 + acceleration: 1.76 + command: 35.0 + } + calibration { + speed: 7.2 + acceleration: 2.47 + command: 40.0 + } + calibration { + speed: 7.2 + acceleration: 2.75 + command: 60.0 + } + calibration { + speed: 7.2 + acceleration: 2.77 + command: 45.0 + } + calibration { + speed: 7.2 + acceleration: 3.01 + command: 50.0 + } + calibration { + speed: 7.2 + acceleration: 3.13 + command: 55.0 + } + calibration { + speed: 7.4 + acceleration: -9.6 + command: -35.0 + } + calibration { + speed: 7.4 + acceleration: -7.83 + command: -33.0 + } + calibration { + speed: 7.4 + acceleration: -5.2 + command: -32.0 + } + calibration { + speed: 7.4 + acceleration: -4.7 + command: -31.0 + } + calibration { + speed: 7.4 + acceleration: -4.1 + command: -30.0 + } + calibration { + speed: 7.4 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 7.4 + acceleration: -2.99 + command: -28.0 + } + calibration { + speed: 7.4 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 7.4 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 7.4 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 7.4 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 7.4 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 7.4 + acceleration: -0.26 + command: 17.0 + } + calibration { + speed: 7.4 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 7.4 + acceleration: -0.21 + command: -14.0 + } + calibration { + speed: 7.4 + acceleration: -0.2 + command: 22.0 + } + calibration { + speed: 7.4 + acceleration: -0.17 + command: 15.0 + } + calibration { + speed: 7.4 + acceleration: 0.04 + command: 20.0 + } + calibration { + speed: 7.4 + acceleration: 0.41 + command: 25.0 + } + calibration { + speed: 7.4 + acceleration: 0.63 + command: 27.0 + } + calibration { + speed: 7.4 + acceleration: 0.82 + command: 30.0 + } + calibration { + speed: 7.4 + acceleration: 1.7 + command: 35.0 + } + calibration { + speed: 7.4 + acceleration: 2.4 + command: 40.0 + } + calibration { + speed: 7.4 + acceleration: 2.72 + command: 52.5 + } + calibration { + speed: 7.4 + acceleration: 2.95 + command: 50.0 + } + calibration { + speed: 7.4 + acceleration: 3.08 + command: 55.0 + } + calibration { + speed: 7.6 + acceleration: -9.57 + command: -35.0 + } + calibration { + speed: 7.6 + acceleration: -7.87 + command: -33.0 + } + calibration { + speed: 7.6 + acceleration: -5.19 + command: -32.0 + } + calibration { + speed: 7.6 + acceleration: -4.67 + command: -31.0 + } + calibration { + speed: 7.6 + acceleration: -4.11 + command: -30.0 + } + calibration { + speed: 7.6 + acceleration: -3.52 + command: -29.0 + } + calibration { + speed: 7.6 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 7.6 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 7.6 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 7.6 + acceleration: -1.36 + command: -25.0 + } + calibration { + speed: 7.6 + acceleration: -0.95 + command: -24.0 + } + calibration { + speed: 7.6 + acceleration: -0.63 + command: -23.0 + } + calibration { + speed: 7.6 + acceleration: -0.23 + command: 17.0 + } + calibration { + speed: 7.6 + acceleration: -0.22 + command: -17.0 + } + calibration { + speed: 7.6 + acceleration: -0.21 + command: -13.0 + } + calibration { + speed: 7.6 + acceleration: -0.2 + command: -15.0 + } + calibration { + speed: 7.6 + acceleration: -0.17 + command: 15.0 + } + calibration { + speed: 7.6 + acceleration: -0.11 + command: 22.0 + } + calibration { + speed: 7.6 + acceleration: 0.02 + command: 20.0 + } + calibration { + speed: 7.6 + acceleration: 0.36 + command: 25.0 + } + calibration { + speed: 7.6 + acceleration: 0.63 + command: 27.0 + } + calibration { + speed: 7.6 + acceleration: 0.79 + command: 30.0 + } + calibration { + speed: 7.6 + acceleration: 1.63 + command: 35.0 + } + calibration { + speed: 7.6 + acceleration: 2.34 + command: 40.0 + } + calibration { + speed: 7.6 + acceleration: 2.66 + command: 45.0 + } + calibration { + speed: 7.6 + acceleration: 2.7 + command: 60.0 + } + calibration { + speed: 7.6 + acceleration: 2.89 + command: 50.0 + } + calibration { + speed: 7.6 + acceleration: 3.03 + command: 55.0 + } + calibration { + speed: 7.8 + acceleration: -9.48 + command: -35.0 + } + calibration { + speed: 7.8 + acceleration: -7.92 + command: -33.0 + } + calibration { + speed: 7.8 + acceleration: -5.2 + command: -32.0 + } + calibration { + speed: 7.8 + acceleration: -4.65 + command: -31.0 + } + calibration { + speed: 7.8 + acceleration: -4.11 + command: -30.0 + } + calibration { + speed: 7.8 + acceleration: -3.52 + command: -29.0 + } + calibration { + speed: 7.8 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 7.8 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 7.8 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 7.8 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 7.8 + acceleration: -0.95 + command: -24.0 + } + calibration { + speed: 7.8 + acceleration: -0.64 + command: -23.0 + } + calibration { + speed: 7.8 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 7.8 + acceleration: -0.23 + command: 17.0 + } + calibration { + speed: 7.8 + acceleration: -0.2 + command: -14.0 + } + calibration { + speed: 7.8 + acceleration: -0.17 + command: 15.0 + } + calibration { + speed: 7.8 + acceleration: 0.01 + command: 20.0 + } + calibration { + speed: 7.8 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 7.8 + acceleration: 0.37 + command: 25.0 + } + calibration { + speed: 7.8 + acceleration: 0.6 + command: 27.0 + } + calibration { + speed: 7.8 + acceleration: 0.78 + command: 30.0 + } + calibration { + speed: 7.8 + acceleration: 1.58 + command: 35.0 + } + calibration { + speed: 7.8 + acceleration: 2.27 + command: 40.0 + } + calibration { + speed: 7.8 + acceleration: 2.6 + command: 45.0 + } + calibration { + speed: 7.8 + acceleration: 2.67 + command: 60.0 + } + calibration { + speed: 7.8 + acceleration: 2.83 + command: 50.0 + } + calibration { + speed: 7.8 + acceleration: 2.98 + command: 55.0 + } + calibration { + speed: 8.0 + acceleration: -9.46 + command: -35.0 + } + calibration { + speed: 8.0 + acceleration: -7.98 + command: -33.0 + } + calibration { + speed: 8.0 + acceleration: -5.23 + command: -32.0 + } + calibration { + speed: 8.0 + acceleration: -4.62 + command: -31.0 + } + calibration { + speed: 8.0 + acceleration: -4.11 + command: -30.0 + } + calibration { + speed: 8.0 + acceleration: -3.53 + command: -29.0 + } + calibration { + speed: 8.0 + acceleration: -2.97 + command: -28.0 + } + calibration { + speed: 8.0 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 8.0 + acceleration: -1.89 + command: -26.0 + } + calibration { + speed: 8.0 + acceleration: -1.36 + command: -25.0 + } + calibration { + speed: 8.0 + acceleration: -0.95 + command: -24.0 + } + calibration { + speed: 8.0 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 8.0 + acceleration: -0.26 + command: 17.0 + } + calibration { + speed: 8.0 + acceleration: -0.24 + command: -1.0 + } + calibration { + speed: 8.0 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 8.0 + acceleration: -0.21 + command: -13.0 + } + calibration { + speed: 8.0 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 8.0 + acceleration: 0.35 + command: 25.0 + } + calibration { + speed: 8.0 + acceleration: 0.58 + command: 27.0 + } + calibration { + speed: 8.0 + acceleration: 0.74 + command: 30.0 + } + calibration { + speed: 8.0 + acceleration: 1.54 + command: 35.0 + } + calibration { + speed: 8.0 + acceleration: 2.21 + command: 40.0 + } + calibration { + speed: 8.0 + acceleration: 2.56 + command: 45.0 + } + calibration { + speed: 8.0 + acceleration: 2.65 + command: 60.0 + } + calibration { + speed: 8.0 + acceleration: 2.77 + command: 50.0 + } + calibration { + speed: 8.0 + acceleration: 2.91 + command: 55.0 + } + calibration { + speed: 8.2 + acceleration: -9.37 + command: -35.0 + } + calibration { + speed: 8.2 + acceleration: -8.07 + command: -33.0 + } + calibration { + speed: 8.2 + acceleration: -5.27 + command: -32.0 + } + calibration { + speed: 8.2 + acceleration: -4.62 + command: -31.0 + } + calibration { + speed: 8.2 + acceleration: -4.09 + command: -30.0 + } + calibration { + speed: 8.2 + acceleration: -3.55 + command: -29.0 + } + calibration { + speed: 8.2 + acceleration: -2.97 + command: -28.0 + } + calibration { + speed: 8.2 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 8.2 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 8.2 + acceleration: -1.39 + command: -25.0 + } + calibration { + speed: 8.2 + acceleration: -0.95 + command: -24.0 + } + calibration { + speed: 8.2 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 8.2 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 8.2 + acceleration: -0.23 + command: 16.0 + } + calibration { + speed: 8.2 + acceleration: -0.22 + command: -14.0 + } + calibration { + speed: 8.2 + acceleration: -0.06 + command: 20.0 + } + calibration { + speed: 8.2 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 8.2 + acceleration: 0.35 + command: 25.0 + } + calibration { + speed: 8.2 + acceleration: 0.56 + command: 27.0 + } + calibration { + speed: 8.2 + acceleration: 0.72 + command: 30.0 + } + calibration { + speed: 8.2 + acceleration: 1.49 + command: 35.0 + } + calibration { + speed: 8.2 + acceleration: 2.15 + command: 40.0 + } + calibration { + speed: 8.2 + acceleration: 2.51 + command: 45.0 + } + calibration { + speed: 8.2 + acceleration: 2.62 + command: 60.0 + } + calibration { + speed: 8.2 + acceleration: 2.71 + command: 50.0 + } + calibration { + speed: 8.2 + acceleration: 2.85 + command: 55.0 + } + calibration { + speed: 8.4 + acceleration: -9.33 + command: -35.0 + } + calibration { + speed: 8.4 + acceleration: -8.18 + command: -33.0 + } + calibration { + speed: 8.4 + acceleration: -5.31 + command: -32.0 + } + calibration { + speed: 8.4 + acceleration: -4.65 + command: -31.0 + } + calibration { + speed: 8.4 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 8.4 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 8.4 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 8.4 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 8.4 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 8.4 + acceleration: -1.37 + command: -25.0 + } + calibration { + speed: 8.4 + acceleration: -0.96 + command: -24.0 + } + calibration { + speed: 8.4 + acceleration: -0.66 + command: -23.0 + } + calibration { + speed: 8.4 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 8.4 + acceleration: -0.23 + command: 2.0 + } + calibration { + speed: 8.4 + acceleration: -0.21 + command: 0.0 + } + calibration { + speed: 8.4 + acceleration: -0.11 + command: 20.0 + } + calibration { + speed: 8.4 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 8.4 + acceleration: 0.35 + command: 25.0 + } + calibration { + speed: 8.4 + acceleration: 0.52 + command: 27.0 + } + calibration { + speed: 8.4 + acceleration: 0.69 + command: 30.0 + } + calibration { + speed: 8.4 + acceleration: 1.44 + command: 35.0 + } + calibration { + speed: 8.4 + acceleration: 2.09 + command: 40.0 + } + calibration { + speed: 8.4 + acceleration: 2.47 + command: 45.0 + } + calibration { + speed: 8.4 + acceleration: 2.6 + command: 60.0 + } + calibration { + speed: 8.4 + acceleration: 2.66 + command: 50.0 + } + calibration { + speed: 8.4 + acceleration: 2.78 + command: 55.0 + } + calibration { + speed: 8.6 + acceleration: -9.22 + command: -35.0 + } + calibration { + speed: 8.6 + acceleration: -8.29 + command: -33.0 + } + calibration { + speed: 8.6 + acceleration: -5.33 + command: -32.0 + } + calibration { + speed: 8.6 + acceleration: -4.68 + command: -31.0 + } + calibration { + speed: 8.6 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 8.6 + acceleration: -3.57 + command: -29.0 + } + calibration { + speed: 8.6 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 8.6 + acceleration: -2.32 + command: -27.0 + } + calibration { + speed: 8.6 + acceleration: -1.93 + command: -26.0 + } + calibration { + speed: 8.6 + acceleration: -1.38 + command: -25.0 + } + calibration { + speed: 8.6 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 8.6 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 8.6 + acceleration: -0.25 + command: -17.0 + } + calibration { + speed: 8.6 + acceleration: -0.24 + command: 16.0 + } + calibration { + speed: 8.6 + acceleration: -0.22 + command: -14.0 + } + calibration { + speed: 8.6 + acceleration: -0.1 + command: 20.0 + } + calibration { + speed: 8.6 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 8.6 + acceleration: 0.32 + command: 25.0 + } + calibration { + speed: 8.6 + acceleration: 0.5 + command: 27.0 + } + calibration { + speed: 8.6 + acceleration: 0.66 + command: 30.0 + } + calibration { + speed: 8.6 + acceleration: 1.42 + command: 35.0 + } + calibration { + speed: 8.6 + acceleration: 2.04 + command: 40.0 + } + calibration { + speed: 8.6 + acceleration: 2.42 + command: 45.0 + } + calibration { + speed: 8.6 + acceleration: 2.57 + command: 60.0 + } + calibration { + speed: 8.6 + acceleration: 2.6 + command: 50.0 + } + calibration { + speed: 8.6 + acceleration: 2.73 + command: 55.0 + } + calibration { + speed: 8.8 + acceleration: -9.17 + command: -35.0 + } + calibration { + speed: 8.8 + acceleration: -8.4 + command: -33.0 + } + calibration { + speed: 8.8 + acceleration: -5.3 + command: -32.0 + } + calibration { + speed: 8.8 + acceleration: -4.74 + command: -31.0 + } + calibration { + speed: 8.8 + acceleration: -4.06 + command: -30.0 + } + calibration { + speed: 8.8 + acceleration: -3.57 + command: -29.0 + } + calibration { + speed: 8.8 + acceleration: -2.99 + command: -28.0 + } + calibration { + speed: 8.8 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 8.8 + acceleration: -1.93 + command: -26.0 + } + calibration { + speed: 8.8 + acceleration: -1.39 + command: -25.0 + } + calibration { + speed: 8.8 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 8.8 + acceleration: -0.66 + command: -23.0 + } + calibration { + speed: 8.8 + acceleration: -0.27 + command: -17.0 + } + calibration { + speed: 8.8 + acceleration: -0.23 + command: 1.0 + } + calibration { + speed: 8.8 + acceleration: -0.21 + command: -15.0 + } + calibration { + speed: 8.8 + acceleration: -0.2 + command: 17.0 + } + calibration { + speed: 8.8 + acceleration: -0.11 + command: 20.0 + } + calibration { + speed: 8.8 + acceleration: 0.17 + command: 22.0 + } + calibration { + speed: 8.8 + acceleration: 0.29 + command: 25.0 + } + calibration { + speed: 8.8 + acceleration: 0.48 + command: 27.0 + } + calibration { + speed: 8.8 + acceleration: 0.64 + command: 30.0 + } + calibration { + speed: 8.8 + acceleration: 1.39 + command: 35.0 + } + calibration { + speed: 8.8 + acceleration: 1.99 + command: 40.0 + } + calibration { + speed: 8.8 + acceleration: 2.36 + command: 45.0 + } + calibration { + speed: 8.8 + acceleration: 2.54 + command: 60.0 + } + calibration { + speed: 8.8 + acceleration: 2.55 + command: 50.0 + } + calibration { + speed: 8.8 + acceleration: 2.67 + command: 55.0 + } + calibration { + speed: 9.0 + acceleration: -9.02 + command: -35.0 + } + calibration { + speed: 9.0 + acceleration: -8.49 + command: -33.0 + } + calibration { + speed: 9.0 + acceleration: -5.24 + command: -32.0 + } + calibration { + speed: 9.0 + acceleration: -4.75 + command: -31.0 + } + calibration { + speed: 9.0 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 9.0 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 9.0 + acceleration: -2.98 + command: -28.0 + } + calibration { + speed: 9.0 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 9.0 + acceleration: -1.93 + command: -26.0 + } + calibration { + speed: 9.0 + acceleration: -1.39 + command: -25.0 + } + calibration { + speed: 9.0 + acceleration: -0.95 + command: -24.0 + } + calibration { + speed: 9.0 + acceleration: -0.66 + command: -23.0 + } + calibration { + speed: 9.0 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 9.0 + acceleration: -0.24 + command: 6.33333333333 + } + calibration { + speed: 9.0 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 9.0 + acceleration: -0.09 + command: 20.0 + } + calibration { + speed: 9.0 + acceleration: 0.27 + command: 25.0 + } + calibration { + speed: 9.0 + acceleration: 0.45 + command: 27.0 + } + calibration { + speed: 9.0 + acceleration: 0.61 + command: 30.0 + } + calibration { + speed: 9.0 + acceleration: 1.32 + command: 35.0 + } + calibration { + speed: 9.0 + acceleration: 1.94 + command: 40.0 + } + calibration { + speed: 9.0 + acceleration: 2.31 + command: 45.0 + } + calibration { + speed: 9.0 + acceleration: 2.5 + command: 55.0 + } + calibration { + speed: 9.0 + acceleration: 2.62 + command: 55.0 + } + calibration { + speed: 9.2 + acceleration: -8.96 + command: -35.0 + } + calibration { + speed: 9.2 + acceleration: -8.59 + command: -33.0 + } + calibration { + speed: 9.2 + acceleration: -5.16 + command: -32.0 + } + calibration { + speed: 9.2 + acceleration: -4.7 + command: -31.0 + } + calibration { + speed: 9.2 + acceleration: -4.08 + command: -30.0 + } + calibration { + speed: 9.2 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 9.2 + acceleration: -2.96 + command: -28.0 + } + calibration { + speed: 9.2 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 9.2 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 9.2 + acceleration: -1.39 + command: -25.0 + } + calibration { + speed: 9.2 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 9.2 + acceleration: -0.67 + command: -23.0 + } + calibration { + speed: 9.2 + acceleration: -0.25 + command: -1.0 + } + calibration { + speed: 9.2 + acceleration: -0.24 + command: -15.0 + } + calibration { + speed: 9.2 + acceleration: -0.23 + command: -13.0 + } + calibration { + speed: 9.2 + acceleration: -0.22 + command: 17.0 + } + calibration { + speed: 9.2 + acceleration: -0.16 + command: 20.0 + } + calibration { + speed: 9.2 + acceleration: 0.25 + command: 25.0 + } + calibration { + speed: 9.2 + acceleration: 0.43 + command: 27.0 + } + calibration { + speed: 9.2 + acceleration: 0.58 + command: 30.0 + } + calibration { + speed: 9.2 + acceleration: 1.27 + command: 35.0 + } + calibration { + speed: 9.2 + acceleration: 1.89 + command: 40.0 + } + calibration { + speed: 9.2 + acceleration: 2.26 + command: 45.0 + } + calibration { + speed: 9.2 + acceleration: 2.45 + command: 50.0 + } + calibration { + speed: 9.2 + acceleration: 2.47 + command: 60.0 + } + calibration { + speed: 9.2 + acceleration: 2.56 + command: 55.0 + } + calibration { + speed: 9.4 + acceleration: -8.89 + command: -35.0 + } + calibration { + speed: 9.4 + acceleration: -8.59 + command: -33.0 + } + calibration { + speed: 9.4 + acceleration: -5.1 + command: -32.0 + } + calibration { + speed: 9.4 + acceleration: -4.66 + command: -31.0 + } + calibration { + speed: 9.4 + acceleration: -4.07 + command: -30.0 + } + calibration { + speed: 9.4 + acceleration: -3.57 + command: -29.0 + } + calibration { + speed: 9.4 + acceleration: -2.95 + command: -28.0 + } + calibration { + speed: 9.4 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 9.4 + acceleration: -1.93 + command: -26.0 + } + calibration { + speed: 9.4 + acceleration: -1.4 + command: -25.0 + } + calibration { + speed: 9.4 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 9.4 + acceleration: -0.67 + command: -23.0 + } + calibration { + speed: 9.4 + acceleration: -0.27 + command: 15.0 + } + calibration { + speed: 9.4 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 9.4 + acceleration: -0.25 + command: 1.0 + } + calibration { + speed: 9.4 + acceleration: -0.24 + command: -13.0 + } + calibration { + speed: 9.4 + acceleration: -0.14 + command: 20.0 + } + calibration { + speed: 9.4 + acceleration: 0.22 + command: 25.0 + } + calibration { + speed: 9.4 + acceleration: 0.41 + command: 27.0 + } + calibration { + speed: 9.4 + acceleration: 0.56 + command: 30.0 + } + calibration { + speed: 9.4 + acceleration: 1.25 + command: 35.0 + } + calibration { + speed: 9.4 + acceleration: 1.85 + command: 40.0 + } + calibration { + speed: 9.4 + acceleration: 2.21 + command: 45.0 + } + calibration { + speed: 9.4 + acceleration: 2.4 + command: 50.0 + } + calibration { + speed: 9.4 + acceleration: 2.43 + command: 60.0 + } + calibration { + speed: 9.4 + acceleration: 2.51 + command: 55.0 + } + calibration { + speed: 9.6 + acceleration: -8.79 + command: -35.0 + } + calibration { + speed: 9.6 + acceleration: -8.53 + command: -33.0 + } + calibration { + speed: 9.6 + acceleration: -5.11 + command: -32.0 + } + calibration { + speed: 9.6 + acceleration: -4.54 + command: -31.0 + } + calibration { + speed: 9.6 + acceleration: -4.05 + command: -30.0 + } + calibration { + speed: 9.6 + acceleration: -3.58 + command: -29.0 + } + calibration { + speed: 9.6 + acceleration: -2.95 + command: -28.0 + } + calibration { + speed: 9.6 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 9.6 + acceleration: -1.95 + command: -26.0 + } + calibration { + speed: 9.6 + acceleration: -1.4 + command: -25.0 + } + calibration { + speed: 9.6 + acceleration: -0.98 + command: -24.0 + } + calibration { + speed: 9.6 + acceleration: -0.67 + command: -23.0 + } + calibration { + speed: 9.6 + acceleration: -0.27 + command: -17.0 + } + calibration { + speed: 9.6 + acceleration: -0.25 + command: 17.0 + } + calibration { + speed: 9.6 + acceleration: -0.23 + command: -4.33333333333 + } + calibration { + speed: 9.6 + acceleration: -0.16 + command: 20.0 + } + calibration { + speed: 9.6 + acceleration: 0.2 + command: 25.0 + } + calibration { + speed: 9.6 + acceleration: 0.41 + command: 27.0 + } + calibration { + speed: 9.6 + acceleration: 0.54 + command: 30.0 + } + calibration { + speed: 9.6 + acceleration: 1.22 + command: 35.0 + } + calibration { + speed: 9.6 + acceleration: 1.8 + command: 40.0 + } + calibration { + speed: 9.6 + acceleration: 2.17 + command: 45.0 + } + calibration { + speed: 9.6 + acceleration: 2.36 + command: 50.0 + } + calibration { + speed: 9.6 + acceleration: 2.4 + command: 60.0 + } + calibration { + speed: 9.6 + acceleration: 2.47 + command: 55.0 + } + calibration { + speed: 9.8 + acceleration: -8.31 + command: -35.0 + } + calibration { + speed: 9.8 + acceleration: -8.25 + command: -33.0 + } + calibration { + speed: 9.8 + acceleration: -5.19 + command: -32.0 + } + calibration { + speed: 9.8 + acceleration: -4.48 + command: -31.0 + } + calibration { + speed: 9.8 + acceleration: -4.0 + command: -30.0 + } + calibration { + speed: 9.8 + acceleration: -3.56 + command: -29.0 + } + calibration { + speed: 9.8 + acceleration: -3.0 + command: -28.0 + } + calibration { + speed: 9.8 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 9.8 + acceleration: -1.95 + command: -26.0 + } + calibration { + speed: 9.8 + acceleration: -1.4 + command: -25.0 + } + calibration { + speed: 9.8 + acceleration: -0.96 + command: -24.0 + } + calibration { + speed: 9.8 + acceleration: -0.68 + command: -23.0 + } + calibration { + speed: 9.8 + acceleration: -0.28 + command: 15.0 + } + calibration { + speed: 9.8 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 9.8 + acceleration: -0.25 + command: -3.66666666667 + } + calibration { + speed: 9.8 + acceleration: -0.14 + command: 20.0 + } + calibration { + speed: 9.8 + acceleration: 0.2 + command: 25.0 + } + calibration { + speed: 9.8 + acceleration: 0.41 + command: 27.0 + } + calibration { + speed: 9.8 + acceleration: 0.53 + command: 30.0 + } + calibration { + speed: 9.8 + acceleration: 1.2 + command: 35.0 + } + calibration { + speed: 9.8 + acceleration: 1.75 + command: 40.0 + } + calibration { + speed: 9.8 + acceleration: 2.14 + command: 45.0 + } + calibration { + speed: 9.8 + acceleration: 2.32 + command: 50.0 + } + calibration { + speed: 9.8 + acceleration: 2.36 + command: 60.0 + } + calibration { + speed: 9.8 + acceleration: 2.42 + command: 55.0 + } + calibration { + speed: 10.0 + acceleration: -8.14 + command: -35.0 + } + calibration { + speed: 10.0 + acceleration: -7.92 + command: -33.0 + } + calibration { + speed: 10.0 + acceleration: -5.3 + command: -32.0 + } + calibration { + speed: 10.0 + acceleration: -4.47 + command: -31.0 + } + calibration { + speed: 10.0 + acceleration: -3.97 + command: -30.0 + } + calibration { + speed: 10.0 + acceleration: -3.51 + command: -29.0 + } + calibration { + speed: 10.0 + acceleration: -3.05 + command: -28.0 + } + calibration { + speed: 10.0 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 10.0 + acceleration: -1.96 + command: -26.0 + } + calibration { + speed: 10.0 + acceleration: -1.4 + command: -25.0 + } + calibration { + speed: 10.0 + acceleration: -0.98 + command: -24.0 + } + calibration { + speed: 10.0 + acceleration: -0.68 + command: -23.0 + } + calibration { + speed: 10.0 + acceleration: -0.28 + command: 15.0 + } + calibration { + speed: 10.0 + acceleration: -0.27 + command: -17.0 + } + calibration { + speed: 10.0 + acceleration: -0.26 + command: 1.0 + } + calibration { + speed: 10.0 + acceleration: -0.23 + command: -13.0 + } + calibration { + speed: 10.0 + acceleration: -0.16 + command: 20.0 + } + calibration { + speed: 10.0 + acceleration: 0.2 + command: 25.0 + } + calibration { + speed: 10.0 + acceleration: 0.38 + command: 27.0 + } + calibration { + speed: 10.0 + acceleration: 0.49 + command: 30.0 + } + calibration { + speed: 10.0 + acceleration: 1.18 + command: 35.0 + } + calibration { + speed: 10.0 + acceleration: 1.71 + command: 40.0 + } + calibration { + speed: 10.0 + acceleration: 2.1 + command: 45.0 + } + calibration { + speed: 10.0 + acceleration: 2.28 + command: 50.0 + } + calibration { + speed: 10.0 + acceleration: 2.29 + command: 60.0 + } + calibration { + speed: 10.0 + acceleration: 2.36 + command: 55.0 + } + } +} +trajectory_period: 0.1 +chassis_period: 0.01 +localization_period: 0.01 diff --git a/apollo_control/conf/lincoln_062547.pb.txt b/apollo_control/conf/lincoln_062547.pb.txt new file mode 100644 index 0000000..fa1466c --- /dev/null +++ b/apollo_control/conf/lincoln_062547.pb.txt @@ -0,0 +1,6755 @@ +control_period: 0.01 +max_planning_interval_sec: 0.2 +max_planning_delay_threshold: 4.0 +action: STOP +soft_estop_brake: 50.0 +active_controllers: LAT_CONTROLLER +active_controllers: LON_CONTROLLER +max_steering_percentage_allowed: 100 +max_status_interval_sec: 0.1 +lat_controller_conf { + ts: 0.01 + preview_window: 0 + cf: 155494.663 + cr: 155494.663 + wheelbase: 2.85 + mass_fl: 520 + mass_fr: 520 + mass_rl: 520 + mass_rr: 520 + eps: 0.01 + matrix_q: 0.02 + matrix_q: 0.0 + matrix_q: 0.4 + matrix_q: 0.0 + cutoff_freq: 10 + mean_filter_window_size: 10 + steer_transmission_ratio: 16 + steer_single_direction_max_degree: 470 + max_iteration: 150 +} +lon_controller_conf { + ts: 0.01 + brake_deadzone: 15.5 + throttle_deadzone: 18.0 + speed_controller_input_limit: 2.0 + station_error_limit: 2.0 + preview_window: 20.0 + standstill_acceleration: -3.0 + station_pid_conf { + integrator_enable: false + integrator_saturation_level: 0.3 + kp: 0.5 + ki: 0.0 + kd: 0.0 + } + low_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 1.0 + ki: 0.3 + kd: 0.0 + } + high_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 1.0 + ki: 0.3 + kd: 0.0 + } + switch_speed: 2.0 + throttle_filter_conf { + cutoff_freq: 10 + } + brake_filter_conf { + cutoff_freq: 10 + } + acceleration_filter_conf { + cutoff_freq: 5 + } + calibration_table { + calibration { + speed: 0.0 + acceleration: -4.69 + command: -33.0 + } + calibration { + speed: 0.0 + acceleration: -3.64 + command: -32.0 + } + calibration { + speed: 0.0 + acceleration: -3.38 + command: -31.0 + } + calibration { + speed: 0.0 + acceleration: -3.21 + command: -30.0 + } + calibration { + speed: 0.0 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 0.0 + acceleration: -2.5 + command: -28.0 + } + calibration { + speed: 0.0 + acceleration: -2.32 + command: -27.0 + } + calibration { + speed: 0.0 + acceleration: -1.77 + command: -26.0 + } + calibration { + speed: 0.0 + acceleration: -1.21 + command: -25.0 + } + calibration { + speed: 0.0 + acceleration: -0.81 + command: -24.0 + } + calibration { + speed: 0.0 + acceleration: -0.44 + command: -23.0 + } + calibration { + speed: 0.0 + acceleration: 0.28 + command: -20.0 + } + calibration { + speed: 0.0 + acceleration: 0.37 + command: -15.0 + } + calibration { + speed: 0.0 + acceleration: 0.4 + command: -15.0 + } + calibration { + speed: 0.0 + acceleration: 0.41 + command: -15.0 + } + calibration { + speed: 0.0 + acceleration: 0.94 + command: 22.0 + } + calibration { + speed: 0.0 + acceleration: 1.38 + command: 25.0 + } + calibration { + speed: 0.0 + acceleration: 1.41 + command: 27.0 + } + calibration { + speed: 0.0 + acceleration: 1.5 + command: 30.0 + } + calibration { + speed: 0.0 + acceleration: 1.59 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 1.7 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 1.78 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 1.82 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 1.89 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 2.01 + command: 35.0 + } + calibration { + speed: 0.2 + acceleration: -4.95 + command: -33.0 + } + calibration { + speed: 0.2 + acceleration: -3.78 + command: -32.0 + } + calibration { + speed: 0.2 + acceleration: -3.51 + command: -31.0 + } + calibration { + speed: 0.2 + acceleration: -3.31 + command: -30.0 + } + calibration { + speed: 0.2 + acceleration: -2.83 + command: -29.0 + } + calibration { + speed: 0.2 + acceleration: -2.54 + command: -28.0 + } + calibration { + speed: 0.2 + acceleration: -2.35 + command: -27.0 + } + calibration { + speed: 0.2 + acceleration: -1.77 + command: -26.0 + } + calibration { + speed: 0.2 + acceleration: -1.21 + command: -25.0 + } + calibration { + speed: 0.2 + acceleration: -0.81 + command: -24.0 + } + calibration { + speed: 0.2 + acceleration: -0.45 + command: -23.0 + } + calibration { + speed: 0.2 + acceleration: 0.28 + command: -20.0 + } + calibration { + speed: 0.2 + acceleration: 0.37 + command: -13.0 + } + calibration { + speed: 0.2 + acceleration: 0.38 + command: -17.0 + } + calibration { + speed: 0.2 + acceleration: 0.4 + command: 15.0 + } + calibration { + speed: 0.2 + acceleration: 0.41 + command: -15.0 + } + calibration { + speed: 0.2 + acceleration: 0.94 + command: 22.0 + } + calibration { + speed: 0.2 + acceleration: 1.44 + command: 26.0 + } + calibration { + speed: 0.2 + acceleration: 1.54 + command: 30.0 + } + calibration { + speed: 0.2 + acceleration: 1.66 + command: 35.0 + } + calibration { + speed: 0.2 + acceleration: 1.78 + command: 40.0 + } + calibration { + speed: 0.2 + acceleration: 1.87 + command: 45.0 + } + calibration { + speed: 0.2 + acceleration: 1.94 + command: 50.0 + } + calibration { + speed: 0.2 + acceleration: 2.01 + command: 55.0 + } + calibration { + speed: 0.2 + acceleration: 2.15 + command: 60.0 + } + calibration { + speed: 0.4 + acceleration: -6.17 + command: -33.0 + } + calibration { + speed: 0.4 + acceleration: -4.62 + command: -32.0 + } + calibration { + speed: 0.4 + acceleration: -4.26 + command: -31.0 + } + calibration { + speed: 0.4 + acceleration: -3.84 + command: -30.0 + } + calibration { + speed: 0.4 + acceleration: -3.13 + command: -29.0 + } + calibration { + speed: 0.4 + acceleration: -2.74 + command: -28.0 + } + calibration { + speed: 0.4 + acceleration: -2.54 + command: -27.0 + } + calibration { + speed: 0.4 + acceleration: -1.8 + command: -26.0 + } + calibration { + speed: 0.4 + acceleration: -1.22 + command: -25.0 + } + calibration { + speed: 0.4 + acceleration: -0.81 + command: -24.0 + } + calibration { + speed: 0.4 + acceleration: -0.5 + command: -23.0 + } + calibration { + speed: 0.4 + acceleration: 0.22 + command: -20.0 + } + calibration { + speed: 0.4 + acceleration: 0.38 + command: -17.0 + } + calibration { + speed: 0.4 + acceleration: 0.39 + command: -15.0 + } + calibration { + speed: 0.4 + acceleration: 0.4 + command: -13.0 + } + calibration { + speed: 0.4 + acceleration: 0.43 + command: 15.0 + } + calibration { + speed: 0.4 + acceleration: 1.0 + command: 22.0 + } + calibration { + speed: 0.4 + acceleration: 1.55 + command: 25.0 + } + calibration { + speed: 0.4 + acceleration: 1.6 + command: 27.0 + } + calibration { + speed: 0.4 + acceleration: 1.73 + command: 30.0 + } + calibration { + speed: 0.4 + acceleration: 1.85 + command: 35.0 + } + calibration { + speed: 0.4 + acceleration: 2.02 + command: 40.0 + } + calibration { + speed: 0.4 + acceleration: 2.1 + command: 45.0 + } + calibration { + speed: 0.4 + acceleration: 2.21 + command: 50.0 + } + calibration { + speed: 0.4 + acceleration: 2.27 + command: 55.0 + } + calibration { + speed: 0.4 + acceleration: 2.43 + command: 60.0 + } + calibration { + speed: 0.6 + acceleration: -7.7 + command: -33.0 + } + calibration { + speed: 0.6 + acceleration: -5.38 + command: -32.0 + } + calibration { + speed: 0.6 + acceleration: -4.84 + command: -31.0 + } + calibration { + speed: 0.6 + acceleration: -4.32 + command: -30.0 + } + calibration { + speed: 0.6 + acceleration: -3.47 + command: -29.0 + } + calibration { + speed: 0.6 + acceleration: -2.89 + command: -28.0 + } + calibration { + speed: 0.6 + acceleration: -2.63 + command: -27.0 + } + calibration { + speed: 0.6 + acceleration: -1.82 + command: -26.0 + } + calibration { + speed: 0.6 + acceleration: -1.24 + command: -25.0 + } + calibration { + speed: 0.6 + acceleration: -0.82 + command: -24.0 + } + calibration { + speed: 0.6 + acceleration: -0.55 + command: -23.0 + } + calibration { + speed: 0.6 + acceleration: 0.15 + command: -20.0 + } + calibration { + speed: 0.6 + acceleration: 0.35 + command: -17.0 + } + calibration { + speed: 0.6 + acceleration: 0.36 + command: -13.0 + } + calibration { + speed: 0.6 + acceleration: 0.37 + command: -15.0 + } + calibration { + speed: 0.6 + acceleration: 0.38 + command: 15.0 + } + calibration { + speed: 0.6 + acceleration: 1.09 + command: 22.0 + } + calibration { + speed: 0.6 + acceleration: 1.65 + command: 25.0 + } + calibration { + speed: 0.6 + acceleration: 1.79 + command: 27.0 + } + calibration { + speed: 0.6 + acceleration: 1.96 + command: 30.0 + } + calibration { + speed: 0.6 + acceleration: 2.08 + command: 35.0 + } + calibration { + speed: 0.6 + acceleration: 2.26 + command: 40.0 + } + calibration { + speed: 0.6 + acceleration: 2.32 + command: 45.0 + } + calibration { + speed: 0.6 + acceleration: 2.46 + command: 50.0 + } + calibration { + speed: 0.6 + acceleration: 2.53 + command: 55.0 + } + calibration { + speed: 0.6 + acceleration: 2.66 + command: 60.0 + } + calibration { + speed: 0.8 + acceleration: -8.77 + command: -33.0 + } + calibration { + speed: 0.8 + acceleration: -5.63 + command: -32.0 + } + calibration { + speed: 0.8 + acceleration: -4.99 + command: -31.0 + } + calibration { + speed: 0.8 + acceleration: -4.4 + command: -30.0 + } + calibration { + speed: 0.8 + acceleration: -3.5 + command: -29.0 + } + calibration { + speed: 0.8 + acceleration: -2.85 + command: -28.0 + } + calibration { + speed: 0.8 + acceleration: -2.57 + command: -27.0 + } + calibration { + speed: 0.8 + acceleration: -1.8 + command: -26.0 + } + calibration { + speed: 0.8 + acceleration: -1.26 + command: -25.0 + } + calibration { + speed: 0.8 + acceleration: -0.84 + command: -24.0 + } + calibration { + speed: 0.8 + acceleration: -0.55 + command: -23.0 + } + calibration { + speed: 0.8 + acceleration: 0.14 + command: -20.0 + } + calibration { + speed: 0.8 + acceleration: 0.3 + command: -15.0 + } + calibration { + speed: 0.8 + acceleration: 0.32 + command: -15.0 + } + calibration { + speed: 0.8 + acceleration: 0.35 + command: 15.0 + } + calibration { + speed: 0.8 + acceleration: 1.14 + command: 22.0 + } + calibration { + speed: 0.8 + acceleration: 1.75 + command: 25.0 + } + calibration { + speed: 0.8 + acceleration: 2.0 + command: 27.0 + } + calibration { + speed: 0.8 + acceleration: 2.15 + command: 30.0 + } + calibration { + speed: 0.8 + acceleration: 2.31 + command: 35.0 + } + calibration { + speed: 0.8 + acceleration: 2.47 + command: 40.0 + } + calibration { + speed: 0.8 + acceleration: 2.49 + command: 45.0 + } + calibration { + speed: 0.8 + acceleration: 2.63 + command: 50.0 + } + calibration { + speed: 0.8 + acceleration: 2.67 + command: 55.0 + } + calibration { + speed: 0.8 + acceleration: 2.77 + command: 60.0 + } + calibration { + speed: 1.0 + acceleration: -9.06 + command: -33.0 + } + calibration { + speed: 1.0 + acceleration: -5.63 + command: -32.0 + } + calibration { + speed: 1.0 + acceleration: -4.93 + command: -31.0 + } + calibration { + speed: 1.0 + acceleration: -4.31 + command: -30.0 + } + calibration { + speed: 1.0 + acceleration: -3.46 + command: -29.0 + } + calibration { + speed: 1.0 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 1.0 + acceleration: -2.56 + command: -27.0 + } + calibration { + speed: 1.0 + acceleration: -1.8 + command: -26.0 + } + calibration { + speed: 1.0 + acceleration: -1.25 + command: -25.0 + } + calibration { + speed: 1.0 + acceleration: -0.85 + command: -24.0 + } + calibration { + speed: 1.0 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 1.0 + acceleration: 0.04 + command: -20.0 + } + calibration { + speed: 1.0 + acceleration: 0.22 + command: -17.0 + } + calibration { + speed: 1.0 + acceleration: 0.24 + command: -13.0 + } + calibration { + speed: 1.0 + acceleration: 0.27 + command: -15.0 + } + calibration { + speed: 1.0 + acceleration: 0.31 + command: 15.0 + } + calibration { + speed: 1.0 + acceleration: 1.17 + command: 22.0 + } + calibration { + speed: 1.0 + acceleration: 1.84 + command: 25.0 + } + calibration { + speed: 1.0 + acceleration: 2.13 + command: 27.0 + } + calibration { + speed: 1.0 + acceleration: 2.31 + command: 30.0 + } + calibration { + speed: 1.0 + acceleration: 2.53 + command: 35.0 + } + calibration { + speed: 1.0 + acceleration: 2.65 + command: 42.5 + } + calibration { + speed: 1.0 + acceleration: 2.76 + command: 50.0 + } + calibration { + speed: 1.0 + acceleration: 2.77 + command: 55.0 + } + calibration { + speed: 1.0 + acceleration: 2.82 + command: 60.0 + } + calibration { + speed: 1.2 + acceleration: -9.19 + command: -33.0 + } + calibration { + speed: 1.2 + acceleration: -5.41 + command: -32.0 + } + calibration { + speed: 1.2 + acceleration: -4.75 + command: -31.0 + } + calibration { + speed: 1.2 + acceleration: -4.18 + command: -30.0 + } + calibration { + speed: 1.2 + acceleration: -3.44 + command: -29.0 + } + calibration { + speed: 1.2 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 1.2 + acceleration: -2.59 + command: -27.0 + } + calibration { + speed: 1.2 + acceleration: -1.8 + command: -26.0 + } + calibration { + speed: 1.2 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 1.2 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 1.2 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 1.2 + acceleration: -0.02 + command: -20.0 + } + calibration { + speed: 1.2 + acceleration: 0.16 + command: -17.0 + } + calibration { + speed: 1.2 + acceleration: 0.17 + command: -13.0 + } + calibration { + speed: 1.2 + acceleration: 0.18 + command: 15.0 + } + calibration { + speed: 1.2 + acceleration: 0.2 + command: -15.0 + } + calibration { + speed: 1.2 + acceleration: 1.19 + command: 22.0 + } + calibration { + speed: 1.2 + acceleration: 1.89 + command: 25.0 + } + calibration { + speed: 1.2 + acceleration: 2.23 + command: 27.0 + } + calibration { + speed: 1.2 + acceleration: 2.42 + command: 30.0 + } + calibration { + speed: 1.2 + acceleration: 2.69 + command: 35.0 + } + calibration { + speed: 1.2 + acceleration: 2.79 + command: 45.0 + } + calibration { + speed: 1.2 + acceleration: 2.81 + command: 40.0 + } + calibration { + speed: 1.2 + acceleration: 2.84 + command: 55.0 + } + calibration { + speed: 1.2 + acceleration: 2.87 + command: 50.0 + } + calibration { + speed: 1.2 + acceleration: 2.88 + command: 60.0 + } + calibration { + speed: 1.4 + acceleration: -9.14 + command: -33.0 + } + calibration { + speed: 1.4 + acceleration: -5.28 + command: -32.0 + } + calibration { + speed: 1.4 + acceleration: -4.64 + command: -31.0 + } + calibration { + speed: 1.4 + acceleration: -4.11 + command: -30.0 + } + calibration { + speed: 1.4 + acceleration: -3.43 + command: -29.0 + } + calibration { + speed: 1.4 + acceleration: -2.81 + command: -28.0 + } + calibration { + speed: 1.4 + acceleration: -2.59 + command: -27.0 + } + calibration { + speed: 1.4 + acceleration: -1.79 + command: -26.0 + } + calibration { + speed: 1.4 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 1.4 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 1.4 + acceleration: -0.6 + command: -23.0 + } + calibration { + speed: 1.4 + acceleration: -0.07 + command: -20.0 + } + calibration { + speed: 1.4 + acceleration: 0.1 + command: -13.0 + } + calibration { + speed: 1.4 + acceleration: 0.11 + command: -17.0 + } + calibration { + speed: 1.4 + acceleration: 0.15 + command: 15.0 + } + calibration { + speed: 1.4 + acceleration: 0.19 + command: -15.0 + } + calibration { + speed: 1.4 + acceleration: 1.18 + command: 22.0 + } + calibration { + speed: 1.4 + acceleration: 1.93 + command: 25.0 + } + calibration { + speed: 1.4 + acceleration: 2.3 + command: 27.0 + } + calibration { + speed: 1.4 + acceleration: 2.5 + command: 30.0 + } + calibration { + speed: 1.4 + acceleration: 2.82 + command: 35.0 + } + calibration { + speed: 1.4 + acceleration: 2.93 + command: 45.0 + } + calibration { + speed: 1.4 + acceleration: 2.94 + command: 40.0 + } + calibration { + speed: 1.4 + acceleration: 2.96 + command: 55.0 + } + calibration { + speed: 1.4 + acceleration: 2.98 + command: 55.0 + } + calibration { + speed: 1.6 + acceleration: -8.97 + command: -33.0 + } + calibration { + speed: 1.6 + acceleration: -5.14 + command: -32.0 + } + calibration { + speed: 1.6 + acceleration: -4.58 + command: -31.0 + } + calibration { + speed: 1.6 + acceleration: -4.1 + command: -30.0 + } + calibration { + speed: 1.6 + acceleration: -3.44 + command: -29.0 + } + calibration { + speed: 1.6 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 1.6 + acceleration: -2.55 + command: -27.0 + } + calibration { + speed: 1.6 + acceleration: -1.81 + command: -26.0 + } + calibration { + speed: 1.6 + acceleration: -1.26 + command: -25.0 + } + calibration { + speed: 1.6 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 1.6 + acceleration: -0.69 + command: -23.0 + } + calibration { + speed: 1.6 + acceleration: -0.12 + command: -20.0 + } + calibration { + speed: 1.6 + acceleration: 0.01 + command: 15.0 + } + calibration { + speed: 1.6 + acceleration: 0.03 + command: -17.0 + } + calibration { + speed: 1.6 + acceleration: 0.05 + command: -13.0 + } + calibration { + speed: 1.6 + acceleration: 0.09 + command: -15.0 + } + calibration { + speed: 1.6 + acceleration: 1.15 + command: 22.0 + } + calibration { + speed: 1.6 + acceleration: 1.96 + command: 25.0 + } + calibration { + speed: 1.6 + acceleration: 2.35 + command: 27.0 + } + calibration { + speed: 1.6 + acceleration: 2.57 + command: 30.0 + } + calibration { + speed: 1.6 + acceleration: 2.94 + command: 35.0 + } + calibration { + speed: 1.6 + acceleration: 3.03 + command: 45.0 + } + calibration { + speed: 1.6 + acceleration: 3.04 + command: 55.0 + } + calibration { + speed: 1.6 + acceleration: 3.05 + command: 40.0 + } + calibration { + speed: 1.6 + acceleration: 3.07 + command: 60.0 + } + calibration { + speed: 1.6 + acceleration: 3.08 + command: 50.0 + } + calibration { + speed: 1.8 + acceleration: -8.82 + command: -33.0 + } + calibration { + speed: 1.8 + acceleration: -5.11 + command: -32.0 + } + calibration { + speed: 1.8 + acceleration: -4.59 + command: -31.0 + } + calibration { + speed: 1.8 + acceleration: -4.12 + command: -30.0 + } + calibration { + speed: 1.8 + acceleration: -3.42 + command: -29.0 + } + calibration { + speed: 1.8 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 1.8 + acceleration: -2.48 + command: -27.0 + } + calibration { + speed: 1.8 + acceleration: -1.82 + command: -26.0 + } + calibration { + speed: 1.8 + acceleration: -1.24 + command: -25.0 + } + calibration { + speed: 1.8 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 1.8 + acceleration: -0.66 + command: -23.0 + } + calibration { + speed: 1.8 + acceleration: -0.17 + command: -20.0 + } + calibration { + speed: 1.8 + acceleration: -0.05 + command: 15.0 + } + calibration { + speed: 1.8 + acceleration: 0.0 + command: -14.0 + } + calibration { + speed: 1.8 + acceleration: 1.11 + command: 22.0 + } + calibration { + speed: 1.8 + acceleration: 1.98 + command: 25.0 + } + calibration { + speed: 1.8 + acceleration: 2.39 + command: 27.0 + } + calibration { + speed: 1.8 + acceleration: 2.63 + command: 30.0 + } + calibration { + speed: 1.8 + acceleration: 3.02 + command: 35.0 + } + calibration { + speed: 1.8 + acceleration: 3.1 + command: 60.0 + } + calibration { + speed: 1.8 + acceleration: 3.12 + command: 45.0 + } + calibration { + speed: 1.8 + acceleration: 3.15 + command: 47.5 + } + calibration { + speed: 1.8 + acceleration: 3.18 + command: 50.0 + } + calibration { + speed: 2.0 + acceleration: -8.61 + command: -33.0 + } + calibration { + speed: 2.0 + acceleration: -5.13 + command: -32.0 + } + calibration { + speed: 2.0 + acceleration: -4.65 + command: -31.0 + } + calibration { + speed: 2.0 + acceleration: -4.16 + command: -30.0 + } + calibration { + speed: 2.0 + acceleration: -3.4 + command: -29.0 + } + calibration { + speed: 2.0 + acceleration: -2.77 + command: -28.0 + } + calibration { + speed: 2.0 + acceleration: -2.45 + command: -27.0 + } + calibration { + speed: 2.0 + acceleration: -1.79 + command: -26.0 + } + calibration { + speed: 2.0 + acceleration: -1.26 + command: -25.0 + } + calibration { + speed: 2.0 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 2.0 + acceleration: -0.63 + command: -23.0 + } + calibration { + speed: 2.0 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 2.0 + acceleration: -0.09 + command: -15.0 + } + calibration { + speed: 2.0 + acceleration: -0.07 + command: 1.0 + } + calibration { + speed: 2.0 + acceleration: -0.02 + command: -17.0 + } + calibration { + speed: 2.0 + acceleration: 1.05 + command: 22.0 + } + calibration { + speed: 2.0 + acceleration: 1.95 + command: 25.0 + } + calibration { + speed: 2.0 + acceleration: 2.4 + command: 27.0 + } + calibration { + speed: 2.0 + acceleration: 2.67 + command: 30.0 + } + calibration { + speed: 2.0 + acceleration: 3.07 + command: 60.0 + } + calibration { + speed: 2.0 + acceleration: 3.08 + command: 35.0 + } + calibration { + speed: 2.0 + acceleration: 3.19 + command: 45.0 + } + calibration { + speed: 2.0 + acceleration: 3.23 + command: 55.0 + } + calibration { + speed: 2.0 + acceleration: 3.24 + command: 40.0 + } + calibration { + speed: 2.0 + acceleration: 3.25 + command: 50.0 + } + calibration { + speed: 2.2 + acceleration: -8.5 + command: -33.0 + } + calibration { + speed: 2.2 + acceleration: -5.19 + command: -32.0 + } + calibration { + speed: 2.2 + acceleration: -4.69 + command: -31.0 + } + calibration { + speed: 2.2 + acceleration: -4.18 + command: -30.0 + } + calibration { + speed: 2.2 + acceleration: -3.38 + command: -29.0 + } + calibration { + speed: 2.2 + acceleration: -2.76 + command: -28.0 + } + calibration { + speed: 2.2 + acceleration: -2.44 + command: -27.0 + } + calibration { + speed: 2.2 + acceleration: -1.76 + command: -26.0 + } + calibration { + speed: 2.2 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 2.2 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 2.2 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 2.2 + acceleration: -0.23 + command: -20.0 + } + calibration { + speed: 2.2 + acceleration: -0.12 + command: -4.33333333333 + } + calibration { + speed: 2.2 + acceleration: -0.06 + command: -17.0 + } + calibration { + speed: 2.2 + acceleration: 0.94 + command: 22.0 + } + calibration { + speed: 2.2 + acceleration: 1.89 + command: 25.0 + } + calibration { + speed: 2.2 + acceleration: 2.38 + command: 27.0 + } + calibration { + speed: 2.2 + acceleration: 2.7 + command: 30.0 + } + calibration { + speed: 2.2 + acceleration: 3.04 + command: 60.0 + } + calibration { + speed: 2.2 + acceleration: 3.13 + command: 35.0 + } + calibration { + speed: 2.2 + acceleration: 3.26 + command: 45.0 + } + calibration { + speed: 2.2 + acceleration: 3.29 + command: 50.0 + } + calibration { + speed: 2.2 + acceleration: 3.3 + command: 47.5 + } + calibration { + speed: 2.4 + acceleration: -8.43 + command: -33.0 + } + calibration { + speed: 2.4 + acceleration: -5.25 + command: -32.0 + } + calibration { + speed: 2.4 + acceleration: -4.71 + command: -31.0 + } + calibration { + speed: 2.4 + acceleration: -4.18 + command: -30.0 + } + calibration { + speed: 2.4 + acceleration: -3.37 + command: -29.0 + } + calibration { + speed: 2.4 + acceleration: -2.77 + command: -28.0 + } + calibration { + speed: 2.4 + acceleration: -2.45 + command: -27.0 + } + calibration { + speed: 2.4 + acceleration: -1.77 + command: -26.0 + } + calibration { + speed: 2.4 + acceleration: -1.26 + command: -25.0 + } + calibration { + speed: 2.4 + acceleration: -0.89 + command: -24.0 + } + calibration { + speed: 2.4 + acceleration: -0.6 + command: -23.0 + } + calibration { + speed: 2.4 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 2.4 + acceleration: -0.15 + command: -13.0 + } + calibration { + speed: 2.4 + acceleration: -0.13 + command: -15.0 + } + calibration { + speed: 2.4 + acceleration: -0.12 + command: 15.0 + } + calibration { + speed: 2.4 + acceleration: -0.07 + command: -17.0 + } + calibration { + speed: 2.4 + acceleration: 0.88 + command: 22.0 + } + calibration { + speed: 2.4 + acceleration: 1.8 + command: 25.0 + } + calibration { + speed: 2.4 + acceleration: 2.33 + command: 27.0 + } + calibration { + speed: 2.4 + acceleration: 2.7 + command: 30.0 + } + calibration { + speed: 2.4 + acceleration: 3.1 + command: 60.0 + } + calibration { + speed: 2.4 + acceleration: 3.15 + command: 35.0 + } + calibration { + speed: 2.4 + acceleration: 3.31 + command: 50.0 + } + calibration { + speed: 2.4 + acceleration: 3.32 + command: 45.0 + } + calibration { + speed: 2.4 + acceleration: 3.33 + command: 40.0 + } + calibration { + speed: 2.4 + acceleration: 3.36 + command: 55.0 + } + calibration { + speed: 2.6 + acceleration: -8.39 + command: -33.0 + } + calibration { + speed: 2.6 + acceleration: -5.31 + command: -32.0 + } + calibration { + speed: 2.6 + acceleration: -4.72 + command: -31.0 + } + calibration { + speed: 2.6 + acceleration: -4.16 + command: -30.0 + } + calibration { + speed: 2.6 + acceleration: -3.36 + command: -29.0 + } + calibration { + speed: 2.6 + acceleration: -2.77 + command: -28.0 + } + calibration { + speed: 2.6 + acceleration: -2.43 + command: -27.0 + } + calibration { + speed: 2.6 + acceleration: -1.79 + command: -26.0 + } + calibration { + speed: 2.6 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 2.6 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 2.6 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 2.6 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 2.6 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 2.6 + acceleration: -0.14 + command: -15.0 + } + calibration { + speed: 2.6 + acceleration: -0.13 + command: 15.0 + } + calibration { + speed: 2.6 + acceleration: -0.08 + command: -17.0 + } + calibration { + speed: 2.6 + acceleration: 0.75 + command: 22.0 + } + calibration { + speed: 2.6 + acceleration: 1.71 + command: 25.0 + } + calibration { + speed: 2.6 + acceleration: 2.26 + command: 27.0 + } + calibration { + speed: 2.6 + acceleration: 2.71 + command: 30.0 + } + calibration { + speed: 2.6 + acceleration: 3.17 + command: 35.0 + } + calibration { + speed: 2.6 + acceleration: 3.2 + command: 60.0 + } + calibration { + speed: 2.6 + acceleration: 3.31 + command: 50.0 + } + calibration { + speed: 2.6 + acceleration: 3.35 + command: 40.0 + } + calibration { + speed: 2.6 + acceleration: 3.36 + command: 45.0 + } + calibration { + speed: 2.6 + acceleration: 3.41 + command: 55.0 + } + calibration { + speed: 2.8 + acceleration: -8.39 + command: -33.0 + } + calibration { + speed: 2.8 + acceleration: -5.33 + command: -32.0 + } + calibration { + speed: 2.8 + acceleration: -4.7 + command: -31.0 + } + calibration { + speed: 2.8 + acceleration: -4.14 + command: -30.0 + } + calibration { + speed: 2.8 + acceleration: -3.38 + command: -29.0 + } + calibration { + speed: 2.8 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 2.8 + acceleration: -2.38 + command: -27.0 + } + calibration { + speed: 2.8 + acceleration: -1.8 + command: -26.0 + } + calibration { + speed: 2.8 + acceleration: -1.29 + command: -25.0 + } + calibration { + speed: 2.8 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 2.8 + acceleration: -0.58 + command: -23.0 + } + calibration { + speed: 2.8 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 2.8 + acceleration: -0.17 + command: -13.0 + } + calibration { + speed: 2.8 + acceleration: -0.13 + command: 0.0 + } + calibration { + speed: 2.8 + acceleration: -0.09 + command: -17.0 + } + calibration { + speed: 2.8 + acceleration: 0.02 + command: 17.0 + } + calibration { + speed: 2.8 + acceleration: 0.69 + command: 22.0 + } + calibration { + speed: 2.8 + acceleration: 1.61 + command: 25.0 + } + calibration { + speed: 2.8 + acceleration: 2.19 + command: 27.0 + } + calibration { + speed: 2.8 + acceleration: 2.71 + command: 30.0 + } + calibration { + speed: 2.8 + acceleration: 3.19 + command: 35.0 + } + calibration { + speed: 2.8 + acceleration: 3.29 + command: 60.0 + } + calibration { + speed: 2.8 + acceleration: 3.31 + command: 50.0 + } + calibration { + speed: 2.8 + acceleration: 3.36 + command: 40.0 + } + calibration { + speed: 2.8 + acceleration: 3.38 + command: 45.0 + } + calibration { + speed: 2.8 + acceleration: 3.46 + command: 55.0 + } + calibration { + speed: 3.0 + acceleration: -8.42 + command: -33.0 + } + calibration { + speed: 3.0 + acceleration: -5.32 + command: -32.0 + } + calibration { + speed: 3.0 + acceleration: -4.67 + command: -31.0 + } + calibration { + speed: 3.0 + acceleration: -4.12 + command: -30.0 + } + calibration { + speed: 3.0 + acceleration: -3.39 + command: -29.0 + } + calibration { + speed: 3.0 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 3.0 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 3.0 + acceleration: -1.83 + command: -26.0 + } + calibration { + speed: 3.0 + acceleration: -1.26 + command: -25.0 + } + calibration { + speed: 3.0 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 3.0 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 3.0 + acceleration: -0.26 + command: -20.0 + } + calibration { + speed: 3.0 + acceleration: -0.15 + command: -14.0 + } + calibration { + speed: 3.0 + acceleration: -0.14 + command: 15.0 + } + calibration { + speed: 3.0 + acceleration: -0.11 + command: -17.0 + } + calibration { + speed: 3.0 + acceleration: -0.05 + command: 17.0 + } + calibration { + speed: 3.0 + acceleration: 0.59 + command: 22.0 + } + calibration { + speed: 3.0 + acceleration: 1.52 + command: 25.0 + } + calibration { + speed: 3.0 + acceleration: 2.13 + command: 27.0 + } + calibration { + speed: 3.0 + acceleration: 2.71 + command: 30.0 + } + calibration { + speed: 3.0 + acceleration: 3.21 + command: 35.0 + } + calibration { + speed: 3.0 + acceleration: 3.3 + command: 50.0 + } + calibration { + speed: 3.0 + acceleration: 3.36 + command: 60.0 + } + calibration { + speed: 3.0 + acceleration: 3.37 + command: 42.5 + } + calibration { + speed: 3.0 + acceleration: 3.5 + command: 55.0 + } + calibration { + speed: 3.2 + acceleration: -8.47 + command: -33.0 + } + calibration { + speed: 3.2 + acceleration: -5.29 + command: -32.0 + } + calibration { + speed: 3.2 + acceleration: -4.66 + command: -31.0 + } + calibration { + speed: 3.2 + acceleration: -4.12 + command: -30.0 + } + calibration { + speed: 3.2 + acceleration: -3.4 + command: -29.0 + } + calibration { + speed: 3.2 + acceleration: -2.83 + command: -28.0 + } + calibration { + speed: 3.2 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 3.2 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 3.2 + acceleration: -1.25 + command: -25.0 + } + calibration { + speed: 3.2 + acceleration: -0.84 + command: -24.0 + } + calibration { + speed: 3.2 + acceleration: -0.51 + command: -23.0 + } + calibration { + speed: 3.2 + acceleration: -0.22 + command: -20.0 + } + calibration { + speed: 3.2 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 3.2 + acceleration: -0.15 + command: -15.0 + } + calibration { + speed: 3.2 + acceleration: -0.14 + command: -13.0 + } + calibration { + speed: 3.2 + acceleration: -0.13 + command: -17.0 + } + calibration { + speed: 3.2 + acceleration: -0.03 + command: 17.0 + } + calibration { + speed: 3.2 + acceleration: 0.52 + command: 22.0 + } + calibration { + speed: 3.2 + acceleration: 1.44 + command: 25.0 + } + calibration { + speed: 3.2 + acceleration: 2.05 + command: 27.0 + } + calibration { + speed: 3.2 + acceleration: 2.69 + command: 30.0 + } + calibration { + speed: 3.2 + acceleration: 3.22 + command: 35.0 + } + calibration { + speed: 3.2 + acceleration: 3.3 + command: 50.0 + } + calibration { + speed: 3.2 + acceleration: 3.34 + command: 45.0 + } + calibration { + speed: 3.2 + acceleration: 3.39 + command: 40.0 + } + calibration { + speed: 3.2 + acceleration: 3.41 + command: 60.0 + } + calibration { + speed: 3.2 + acceleration: 3.51 + command: 55.0 + } + calibration { + speed: 3.4 + acceleration: -8.55 + command: -33.0 + } + calibration { + speed: 3.4 + acceleration: -5.26 + command: -32.0 + } + calibration { + speed: 3.4 + acceleration: -4.65 + command: -31.0 + } + calibration { + speed: 3.4 + acceleration: -4.13 + command: -30.0 + } + calibration { + speed: 3.4 + acceleration: -3.41 + command: -29.0 + } + calibration { + speed: 3.4 + acceleration: -2.83 + command: -28.0 + } + calibration { + speed: 3.4 + acceleration: -2.3 + command: -27.0 + } + calibration { + speed: 3.4 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 3.4 + acceleration: -1.28 + command: -25.0 + } + calibration { + speed: 3.4 + acceleration: -0.85 + command: -24.0 + } + calibration { + speed: 3.4 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 3.4 + acceleration: -0.21 + command: -20.0 + } + calibration { + speed: 3.4 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 3.4 + acceleration: -0.14 + command: -5.0 + } + calibration { + speed: 3.4 + acceleration: -0.05 + command: 17.0 + } + calibration { + speed: 3.4 + acceleration: 0.49 + command: 22.0 + } + calibration { + speed: 3.4 + acceleration: 1.35 + command: 25.0 + } + calibration { + speed: 3.4 + acceleration: 1.96 + command: 27.0 + } + calibration { + speed: 3.4 + acceleration: 2.65 + command: 30.0 + } + calibration { + speed: 3.4 + acceleration: 3.23 + command: 35.0 + } + calibration { + speed: 3.4 + acceleration: 3.31 + command: 50.0 + } + calibration { + speed: 3.4 + acceleration: 3.33 + command: 45.0 + } + calibration { + speed: 3.4 + acceleration: 3.42 + command: 40.0 + } + calibration { + speed: 3.4 + acceleration: 3.43 + command: 60.0 + } + calibration { + speed: 3.4 + acceleration: 3.51 + command: 55.0 + } + calibration { + speed: 3.6 + acceleration: -8.6 + command: -33.0 + } + calibration { + speed: 3.6 + acceleration: -5.21 + command: -32.0 + } + calibration { + speed: 3.6 + acceleration: -4.66 + command: -31.0 + } + calibration { + speed: 3.6 + acceleration: -4.14 + command: -30.0 + } + calibration { + speed: 3.6 + acceleration: -3.41 + command: -29.0 + } + calibration { + speed: 3.6 + acceleration: -2.81 + command: -28.0 + } + calibration { + speed: 3.6 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 3.6 + acceleration: -1.84 + command: -26.0 + } + calibration { + speed: 3.6 + acceleration: -1.25 + command: -25.0 + } + calibration { + speed: 3.6 + acceleration: -0.84 + command: -24.0 + } + calibration { + speed: 3.6 + acceleration: -0.55 + command: -23.0 + } + calibration { + speed: 3.6 + acceleration: -0.21 + command: -20.0 + } + calibration { + speed: 3.6 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 3.6 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 3.6 + acceleration: -0.15 + command: -14.0 + } + calibration { + speed: 3.6 + acceleration: -0.06 + command: 17.0 + } + calibration { + speed: 3.6 + acceleration: 0.45 + command: 22.0 + } + calibration { + speed: 3.6 + acceleration: 1.25 + command: 25.0 + } + calibration { + speed: 3.6 + acceleration: 1.84 + command: 27.0 + } + calibration { + speed: 3.6 + acceleration: 2.58 + command: 30.0 + } + calibration { + speed: 3.6 + acceleration: 3.21 + command: 35.0 + } + calibration { + speed: 3.6 + acceleration: 3.32 + command: 45.0 + } + calibration { + speed: 3.6 + acceleration: 3.33 + command: 50.0 + } + calibration { + speed: 3.6 + acceleration: 3.42 + command: 60.0 + } + calibration { + speed: 3.6 + acceleration: 3.45 + command: 40.0 + } + calibration { + speed: 3.6 + acceleration: 3.5 + command: 55.0 + } + calibration { + speed: 3.8 + acceleration: -8.65 + command: -33.0 + } + calibration { + speed: 3.8 + acceleration: -5.18 + command: -32.0 + } + calibration { + speed: 3.8 + acceleration: -4.68 + command: -31.0 + } + calibration { + speed: 3.8 + acceleration: -4.16 + command: -30.0 + } + calibration { + speed: 3.8 + acceleration: -3.4 + command: -29.0 + } + calibration { + speed: 3.8 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 3.8 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 3.8 + acceleration: -1.83 + command: -26.0 + } + calibration { + speed: 3.8 + acceleration: -1.27 + command: -25.0 + } + calibration { + speed: 3.8 + acceleration: -0.86 + command: -24.0 + } + calibration { + speed: 3.8 + acceleration: -0.54 + command: -23.0 + } + calibration { + speed: 3.8 + acceleration: -0.24 + command: -20.0 + } + calibration { + speed: 3.8 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 3.8 + acceleration: -0.16 + command: 0.0 + } + calibration { + speed: 3.8 + acceleration: -0.15 + command: -13.0 + } + calibration { + speed: 3.8 + acceleration: -0.03 + command: 17.0 + } + calibration { + speed: 3.8 + acceleration: 0.44 + command: 22.0 + } + calibration { + speed: 3.8 + acceleration: 1.17 + command: 25.0 + } + calibration { + speed: 3.8 + acceleration: 1.71 + command: 27.0 + } + calibration { + speed: 3.8 + acceleration: 2.5 + command: 30.0 + } + calibration { + speed: 3.8 + acceleration: 3.15 + command: 35.0 + } + calibration { + speed: 3.8 + acceleration: 3.34 + command: 45.0 + } + calibration { + speed: 3.8 + acceleration: 3.36 + command: 50.0 + } + calibration { + speed: 3.8 + acceleration: 3.39 + command: 60.0 + } + calibration { + speed: 3.8 + acceleration: 3.46 + command: 40.0 + } + calibration { + speed: 3.8 + acceleration: 3.49 + command: 55.0 + } + calibration { + speed: 4.0 + acceleration: -8.69 + command: -33.0 + } + calibration { + speed: 4.0 + acceleration: -5.17 + command: -32.0 + } + calibration { + speed: 4.0 + acceleration: -4.69 + command: -31.0 + } + calibration { + speed: 4.0 + acceleration: -4.16 + command: -30.0 + } + calibration { + speed: 4.0 + acceleration: -3.37 + command: -29.0 + } + calibration { + speed: 4.0 + acceleration: -2.76 + command: -28.0 + } + calibration { + speed: 4.0 + acceleration: -2.31 + command: -27.0 + } + calibration { + speed: 4.0 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 4.0 + acceleration: -1.29 + command: -25.0 + } + calibration { + speed: 4.0 + acceleration: -0.85 + command: -24.0 + } + calibration { + speed: 4.0 + acceleration: -0.54 + command: -23.0 + } + calibration { + speed: 4.0 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 4.0 + acceleration: -0.2 + command: -15.0 + } + calibration { + speed: 4.0 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 4.0 + acceleration: -0.17 + command: -13.0 + } + calibration { + speed: 4.0 + acceleration: -0.16 + command: -17.0 + } + calibration { + speed: 4.0 + acceleration: -0.05 + command: 17.0 + } + calibration { + speed: 4.0 + acceleration: 0.4 + command: 22.0 + } + calibration { + speed: 4.0 + acceleration: 1.08 + command: 25.0 + } + calibration { + speed: 4.0 + acceleration: 1.63 + command: 27.0 + } + calibration { + speed: 4.0 + acceleration: 2.38 + command: 30.0 + } + calibration { + speed: 4.0 + acceleration: 3.11 + command: 35.0 + } + calibration { + speed: 4.0 + acceleration: 3.36 + command: 60.0 + } + calibration { + speed: 4.0 + acceleration: 3.37 + command: 45.0 + } + calibration { + speed: 4.0 + acceleration: 3.39 + command: 50.0 + } + calibration { + speed: 4.0 + acceleration: 3.46 + command: 40.0 + } + calibration { + speed: 4.0 + acceleration: 3.48 + command: 55.0 + } + calibration { + speed: 4.2 + acceleration: -8.72 + command: -33.0 + } + calibration { + speed: 4.2 + acceleration: -5.18 + command: -32.0 + } + calibration { + speed: 4.2 + acceleration: -4.7 + command: -31.0 + } + calibration { + speed: 4.2 + acceleration: -4.15 + command: -30.0 + } + calibration { + speed: 4.2 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 4.2 + acceleration: -2.76 + command: -28.0 + } + calibration { + speed: 4.2 + acceleration: -2.32 + command: -27.0 + } + calibration { + speed: 4.2 + acceleration: -1.87 + command: -26.0 + } + calibration { + speed: 4.2 + acceleration: -1.3 + command: -25.0 + } + calibration { + speed: 4.2 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 4.2 + acceleration: -0.54 + command: -23.0 + } + calibration { + speed: 4.2 + acceleration: -0.23 + command: -20.0 + } + calibration { + speed: 4.2 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 4.2 + acceleration: -0.2 + command: -15.0 + } + calibration { + speed: 4.2 + acceleration: -0.17 + command: 15.0 + } + calibration { + speed: 4.2 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 4.2 + acceleration: -0.05 + command: 17.0 + } + calibration { + speed: 4.2 + acceleration: 0.39 + command: 22.0 + } + calibration { + speed: 4.2 + acceleration: 0.97 + command: 25.0 + } + calibration { + speed: 4.2 + acceleration: 1.52 + command: 27.0 + } + calibration { + speed: 4.2 + acceleration: 2.27 + command: 30.0 + } + calibration { + speed: 4.2 + acceleration: 3.03 + command: 35.0 + } + calibration { + speed: 4.2 + acceleration: 3.36 + command: 60.0 + } + calibration { + speed: 4.2 + acceleration: 3.39 + command: 45.0 + } + calibration { + speed: 4.2 + acceleration: 3.43 + command: 40.0 + } + calibration { + speed: 4.2 + acceleration: 3.44 + command: 50.0 + } + calibration { + speed: 4.2 + acceleration: 3.49 + command: 55.0 + } + calibration { + speed: 4.4 + acceleration: -8.74 + command: -33.0 + } + calibration { + speed: 4.4 + acceleration: -5.19 + command: -32.0 + } + calibration { + speed: 4.4 + acceleration: -4.69 + command: -31.0 + } + calibration { + speed: 4.4 + acceleration: -4.12 + command: -30.0 + } + calibration { + speed: 4.4 + acceleration: -3.31 + command: -29.0 + } + calibration { + speed: 4.4 + acceleration: -2.78 + command: -28.0 + } + calibration { + speed: 4.4 + acceleration: -2.32 + command: -27.0 + } + calibration { + speed: 4.4 + acceleration: -1.88 + command: -26.0 + } + calibration { + speed: 4.4 + acceleration: -1.29 + command: -25.0 + } + calibration { + speed: 4.4 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 4.4 + acceleration: -0.54 + command: -23.0 + } + calibration { + speed: 4.4 + acceleration: -0.22 + command: -20.0 + } + calibration { + speed: 4.4 + acceleration: -0.2 + command: -17.0 + } + calibration { + speed: 4.4 + acceleration: -0.19 + command: 0.0 + } + calibration { + speed: 4.4 + acceleration: -0.15 + command: -13.0 + } + calibration { + speed: 4.4 + acceleration: -0.06 + command: 17.0 + } + calibration { + speed: 4.4 + acceleration: 0.36 + command: 22.0 + } + calibration { + speed: 4.4 + acceleration: 0.89 + command: 25.0 + } + calibration { + speed: 4.4 + acceleration: 1.41 + command: 27.0 + } + calibration { + speed: 4.4 + acceleration: 2.13 + command: 30.0 + } + calibration { + speed: 4.4 + acceleration: 2.97 + command: 35.0 + } + calibration { + speed: 4.4 + acceleration: 3.38 + command: 60.0 + } + calibration { + speed: 4.4 + acceleration: 3.39 + command: 40.0 + } + calibration { + speed: 4.4 + acceleration: 3.4 + command: 45.0 + } + calibration { + speed: 4.4 + acceleration: 3.47 + command: 50.0 + } + calibration { + speed: 4.4 + acceleration: 3.5 + command: 55.0 + } + calibration { + speed: 4.6 + acceleration: -8.75 + command: -33.0 + } + calibration { + speed: 4.6 + acceleration: -5.22 + command: -32.0 + } + calibration { + speed: 4.6 + acceleration: -4.67 + command: -31.0 + } + calibration { + speed: 4.6 + acceleration: -4.08 + command: -30.0 + } + calibration { + speed: 4.6 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 4.6 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 4.6 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 4.6 + acceleration: -1.87 + command: -26.0 + } + calibration { + speed: 4.6 + acceleration: -1.29 + command: -25.0 + } + calibration { + speed: 4.6 + acceleration: -0.87 + command: -24.0 + } + calibration { + speed: 4.6 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 4.6 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 4.6 + acceleration: -0.21 + command: -15.0 + } + calibration { + speed: 4.6 + acceleration: -0.19 + command: -17.0 + } + calibration { + speed: 4.6 + acceleration: -0.16 + command: 1.0 + } + calibration { + speed: 4.6 + acceleration: -0.08 + command: 17.0 + } + calibration { + speed: 4.6 + acceleration: 0.32 + command: 22.0 + } + calibration { + speed: 4.6 + acceleration: 0.81 + command: 25.0 + } + calibration { + speed: 4.6 + acceleration: 1.29 + command: 27.0 + } + calibration { + speed: 4.6 + acceleration: 1.98 + command: 30.0 + } + calibration { + speed: 4.6 + acceleration: 2.87 + command: 35.0 + } + calibration { + speed: 4.6 + acceleration: 3.35 + command: 40.0 + } + calibration { + speed: 4.6 + acceleration: 3.39 + command: 45.0 + } + calibration { + speed: 4.6 + acceleration: 3.42 + command: 60.0 + } + calibration { + speed: 4.6 + acceleration: 3.5 + command: 50.0 + } + calibration { + speed: 4.6 + acceleration: 3.51 + command: 55.0 + } + calibration { + speed: 4.8 + acceleration: -8.76 + command: -33.0 + } + calibration { + speed: 4.8 + acceleration: -5.23 + command: -32.0 + } + calibration { + speed: 4.8 + acceleration: -4.64 + command: -31.0 + } + calibration { + speed: 4.8 + acceleration: -4.04 + command: -30.0 + } + calibration { + speed: 4.8 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 4.8 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 4.8 + acceleration: -2.32 + command: -27.0 + } + calibration { + speed: 4.8 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 4.8 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 4.8 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 4.8 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 4.8 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 4.8 + acceleration: -0.22 + command: -16.0 + } + calibration { + speed: 4.8 + acceleration: -0.16 + command: 15.0 + } + calibration { + speed: 4.8 + acceleration: -0.15 + command: -13.0 + } + calibration { + speed: 4.8 + acceleration: -0.09 + command: 17.0 + } + calibration { + speed: 4.8 + acceleration: 0.34 + command: 22.0 + } + calibration { + speed: 4.8 + acceleration: 0.71 + command: 25.0 + } + calibration { + speed: 4.8 + acceleration: 1.17 + command: 27.0 + } + calibration { + speed: 4.8 + acceleration: 1.82 + command: 30.0 + } + calibration { + speed: 4.8 + acceleration: 2.8 + command: 35.0 + } + calibration { + speed: 4.8 + acceleration: 3.3 + command: 40.0 + } + calibration { + speed: 4.8 + acceleration: 3.37 + command: 45.0 + } + calibration { + speed: 4.8 + acceleration: 3.46 + command: 60.0 + } + calibration { + speed: 4.8 + acceleration: 3.51 + command: 52.5 + } + calibration { + speed: 5.0 + acceleration: -8.77 + command: -33.0 + } + calibration { + speed: 5.0 + acceleration: -5.24 + command: -32.0 + } + calibration { + speed: 5.0 + acceleration: -4.6 + command: -31.0 + } + calibration { + speed: 5.0 + acceleration: -4.01 + command: -30.0 + } + calibration { + speed: 5.0 + acceleration: -3.31 + command: -29.0 + } + calibration { + speed: 5.0 + acceleration: -2.81 + command: -28.0 + } + calibration { + speed: 5.0 + acceleration: -2.32 + command: -27.0 + } + calibration { + speed: 5.0 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 5.0 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 5.0 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 5.0 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 5.0 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 5.0 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 5.0 + acceleration: -0.19 + command: -17.0 + } + calibration { + speed: 5.0 + acceleration: -0.17 + command: 1.0 + } + calibration { + speed: 5.0 + acceleration: -0.07 + command: 17.0 + } + calibration { + speed: 5.0 + acceleration: 0.32 + command: 22.0 + } + calibration { + speed: 5.0 + acceleration: 0.65 + command: 25.0 + } + calibration { + speed: 5.0 + acceleration: 1.08 + command: 27.0 + } + calibration { + speed: 5.0 + acceleration: 1.69 + command: 30.0 + } + calibration { + speed: 5.0 + acceleration: 2.68 + command: 35.0 + } + calibration { + speed: 5.0 + acceleration: 3.25 + command: 40.0 + } + calibration { + speed: 5.0 + acceleration: 3.34 + command: 45.0 + } + calibration { + speed: 5.0 + acceleration: 3.49 + command: 60.0 + } + calibration { + speed: 5.0 + acceleration: 3.5 + command: 50.0 + } + calibration { + speed: 5.0 + acceleration: 3.52 + command: 55.0 + } + calibration { + speed: 5.2 + acceleration: -8.78 + command: -33.0 + } + calibration { + speed: 5.2 + acceleration: -5.22 + command: -32.0 + } + calibration { + speed: 5.2 + acceleration: -4.55 + command: -31.0 + } + calibration { + speed: 5.2 + acceleration: -3.99 + command: -30.0 + } + calibration { + speed: 5.2 + acceleration: -3.31 + command: -29.0 + } + calibration { + speed: 5.2 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 5.2 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 5.2 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 5.2 + acceleration: -1.3 + command: -25.0 + } + calibration { + speed: 5.2 + acceleration: -0.88 + command: -24.0 + } + calibration { + speed: 5.2 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 5.2 + acceleration: -0.27 + command: -20.0 + } + calibration { + speed: 5.2 + acceleration: -0.2 + command: -15.0 + } + calibration { + speed: 5.2 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 5.2 + acceleration: -0.16 + command: -17.0 + } + calibration { + speed: 5.2 + acceleration: -0.14 + command: 15.0 + } + calibration { + speed: 5.2 + acceleration: -0.11 + command: 17.0 + } + calibration { + speed: 5.2 + acceleration: 0.32 + command: 22.0 + } + calibration { + speed: 5.2 + acceleration: 0.59 + command: 25.0 + } + calibration { + speed: 5.2 + acceleration: 1.0 + command: 27.0 + } + calibration { + speed: 5.2 + acceleration: 1.59 + command: 30.0 + } + calibration { + speed: 5.2 + acceleration: 2.57 + command: 35.0 + } + calibration { + speed: 5.2 + acceleration: 3.19 + command: 40.0 + } + calibration { + speed: 5.2 + acceleration: 3.3 + command: 45.0 + } + calibration { + speed: 5.2 + acceleration: 3.47 + command: 50.0 + } + calibration { + speed: 5.2 + acceleration: 3.51 + command: 60.0 + } + calibration { + speed: 5.2 + acceleration: 3.53 + command: 55.0 + } + calibration { + speed: 5.4 + acceleration: -8.78 + command: -33.0 + } + calibration { + speed: 5.4 + acceleration: -5.2 + command: -32.0 + } + calibration { + speed: 5.4 + acceleration: -4.52 + command: -31.0 + } + calibration { + speed: 5.4 + acceleration: -3.99 + command: -30.0 + } + calibration { + speed: 5.4 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 5.4 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 5.4 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 5.4 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 5.4 + acceleration: -1.3 + command: -25.0 + } + calibration { + speed: 5.4 + acceleration: -0.89 + command: -24.0 + } + calibration { + speed: 5.4 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 5.4 + acceleration: -0.26 + command: -20.0 + } + calibration { + speed: 5.4 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 5.4 + acceleration: -0.2 + command: -17.0 + } + calibration { + speed: 5.4 + acceleration: -0.17 + command: 1.0 + } + calibration { + speed: 5.4 + acceleration: -0.09 + command: 17.0 + } + calibration { + speed: 5.4 + acceleration: 0.28 + command: 22.0 + } + calibration { + speed: 5.4 + acceleration: 0.59 + command: 25.0 + } + calibration { + speed: 5.4 + acceleration: 0.95 + command: 27.0 + } + calibration { + speed: 5.4 + acceleration: 1.5 + command: 30.0 + } + calibration { + speed: 5.4 + acceleration: 2.49 + command: 35.0 + } + calibration { + speed: 5.4 + acceleration: 3.13 + command: 40.0 + } + calibration { + speed: 5.4 + acceleration: 3.26 + command: 45.0 + } + calibration { + speed: 5.4 + acceleration: 3.45 + command: 50.0 + } + calibration { + speed: 5.4 + acceleration: 3.52 + command: 60.0 + } + calibration { + speed: 5.4 + acceleration: 3.53 + command: 55.0 + } + calibration { + speed: 5.6 + acceleration: -8.78 + command: -33.0 + } + calibration { + speed: 5.6 + acceleration: -5.15 + command: -32.0 + } + calibration { + speed: 5.6 + acceleration: -4.5 + command: -31.0 + } + calibration { + speed: 5.6 + acceleration: -4.0 + command: -30.0 + } + calibration { + speed: 5.6 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 5.6 + acceleration: -2.78 + command: -28.0 + } + calibration { + speed: 5.6 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 5.6 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 5.6 + acceleration: -1.3 + command: -25.0 + } + calibration { + speed: 5.6 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 5.6 + acceleration: -0.56 + command: -23.0 + } + calibration { + speed: 5.6 + acceleration: -0.25 + command: -20.0 + } + calibration { + speed: 5.6 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 5.6 + acceleration: -0.2 + command: -17.0 + } + calibration { + speed: 5.6 + acceleration: -0.17 + command: 1.0 + } + calibration { + speed: 5.6 + acceleration: -0.13 + command: 17.0 + } + calibration { + speed: 5.6 + acceleration: 0.27 + command: 22.0 + } + calibration { + speed: 5.6 + acceleration: 0.55 + command: 25.0 + } + calibration { + speed: 5.6 + acceleration: 0.91 + command: 27.0 + } + calibration { + speed: 5.6 + acceleration: 1.41 + command: 30.0 + } + calibration { + speed: 5.6 + acceleration: 2.42 + command: 35.0 + } + calibration { + speed: 5.6 + acceleration: 3.07 + command: 40.0 + } + calibration { + speed: 5.6 + acceleration: 3.22 + command: 45.0 + } + calibration { + speed: 5.6 + acceleration: 3.41 + command: 50.0 + } + calibration { + speed: 5.6 + acceleration: 3.52 + command: 60.0 + } + calibration { + speed: 5.6 + acceleration: 3.54 + command: 55.0 + } + calibration { + speed: 5.8 + acceleration: -8.78 + command: -33.0 + } + calibration { + speed: 5.8 + acceleration: -5.11 + command: -32.0 + } + calibration { + speed: 5.8 + acceleration: -4.5 + command: -31.0 + } + calibration { + speed: 5.8 + acceleration: -4.02 + command: -30.0 + } + calibration { + speed: 5.8 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 5.8 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 5.8 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 5.8 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 5.8 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 5.8 + acceleration: -0.9 + command: -24.0 + } + calibration { + speed: 5.8 + acceleration: -0.58 + command: -23.0 + } + calibration { + speed: 5.8 + acceleration: -0.27 + command: -20.0 + } + calibration { + speed: 5.8 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 5.8 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 5.8 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 5.8 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 5.8 + acceleration: -0.12 + command: 17.0 + } + calibration { + speed: 5.8 + acceleration: 0.28 + command: 22.0 + } + calibration { + speed: 5.8 + acceleration: 0.52 + command: 25.0 + } + calibration { + speed: 5.8 + acceleration: 0.86 + command: 27.0 + } + calibration { + speed: 5.8 + acceleration: 1.35 + command: 30.0 + } + calibration { + speed: 5.8 + acceleration: 2.35 + command: 35.0 + } + calibration { + speed: 5.8 + acceleration: 3.0 + command: 40.0 + } + calibration { + speed: 5.8 + acceleration: 3.18 + command: 45.0 + } + calibration { + speed: 5.8 + acceleration: 3.38 + command: 50.0 + } + calibration { + speed: 5.8 + acceleration: 3.51 + command: 60.0 + } + calibration { + speed: 5.8 + acceleration: 3.54 + command: 55.0 + } + calibration { + speed: 6.0 + acceleration: -8.77 + command: -33.0 + } + calibration { + speed: 6.0 + acceleration: -5.07 + command: -32.0 + } + calibration { + speed: 6.0 + acceleration: -4.51 + command: -31.0 + } + calibration { + speed: 6.0 + acceleration: -4.02 + command: -30.0 + } + calibration { + speed: 6.0 + acceleration: -3.32 + command: -29.0 + } + calibration { + speed: 6.0 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 6.0 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 6.0 + acceleration: -1.84 + command: -26.0 + } + calibration { + speed: 6.0 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 6.0 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.0 + acceleration: -0.58 + command: -23.0 + } + calibration { + speed: 6.0 + acceleration: -0.26 + command: -20.0 + } + calibration { + speed: 6.0 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 6.0 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 6.0 + acceleration: -0.19 + command: 15.0 + } + calibration { + speed: 6.0 + acceleration: -0.14 + command: 17.0 + } + calibration { + speed: 6.0 + acceleration: 0.25 + command: 22.0 + } + calibration { + speed: 6.0 + acceleration: 0.53 + command: 25.0 + } + calibration { + speed: 6.0 + acceleration: 0.83 + command: 27.0 + } + calibration { + speed: 6.0 + acceleration: 1.3 + command: 30.0 + } + calibration { + speed: 6.0 + acceleration: 2.28 + command: 35.0 + } + calibration { + speed: 6.0 + acceleration: 2.94 + command: 40.0 + } + calibration { + speed: 6.0 + acceleration: 3.14 + command: 45.0 + } + calibration { + speed: 6.0 + acceleration: 3.34 + command: 50.0 + } + calibration { + speed: 6.0 + acceleration: 3.49 + command: 60.0 + } + calibration { + speed: 6.0 + acceleration: 3.54 + command: 55.0 + } + calibration { + speed: 6.2 + acceleration: -8.75 + command: -33.0 + } + calibration { + speed: 6.2 + acceleration: -5.05 + command: -32.0 + } + calibration { + speed: 6.2 + acceleration: -4.52 + command: -31.0 + } + calibration { + speed: 6.2 + acceleration: -4.01 + command: -30.0 + } + calibration { + speed: 6.2 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 6.2 + acceleration: -2.81 + command: -28.0 + } + calibration { + speed: 6.2 + acceleration: -2.33 + command: -27.0 + } + calibration { + speed: 6.2 + acceleration: -1.84 + command: -26.0 + } + calibration { + speed: 6.2 + acceleration: -1.31 + command: -25.0 + } + calibration { + speed: 6.2 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.2 + acceleration: -0.57 + command: -23.0 + } + calibration { + speed: 6.2 + acceleration: -0.32 + command: -20.0 + } + calibration { + speed: 6.2 + acceleration: -0.24 + command: -13.0 + } + calibration { + speed: 6.2 + acceleration: -0.23 + command: -16.0 + } + calibration { + speed: 6.2 + acceleration: -0.2 + command: 15.0 + } + calibration { + speed: 6.2 + acceleration: -0.13 + command: 17.0 + } + calibration { + speed: 6.2 + acceleration: 0.27 + command: 22.0 + } + calibration { + speed: 6.2 + acceleration: 0.49 + command: 25.0 + } + calibration { + speed: 6.2 + acceleration: 0.77 + command: 27.0 + } + calibration { + speed: 6.2 + acceleration: 1.24 + command: 30.0 + } + calibration { + speed: 6.2 + acceleration: 2.2 + command: 35.0 + } + calibration { + speed: 6.2 + acceleration: 2.88 + command: 40.0 + } + calibration { + speed: 6.2 + acceleration: 3.08 + command: 45.0 + } + calibration { + speed: 6.2 + acceleration: 3.29 + command: 50.0 + } + calibration { + speed: 6.2 + acceleration: 3.48 + command: 60.0 + } + calibration { + speed: 6.2 + acceleration: 3.51 + command: 55.0 + } + calibration { + speed: 6.4 + acceleration: -8.72 + command: -33.0 + } + calibration { + speed: 6.4 + acceleration: -5.03 + command: -32.0 + } + calibration { + speed: 6.4 + acceleration: -4.53 + command: -31.0 + } + calibration { + speed: 6.4 + acceleration: -4.01 + command: -30.0 + } + calibration { + speed: 6.4 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 6.4 + acceleration: -2.81 + command: -28.0 + } + calibration { + speed: 6.4 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 6.4 + acceleration: -1.85 + command: -26.0 + } + calibration { + speed: 6.4 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 6.4 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.4 + acceleration: -0.59 + command: -23.0 + } + calibration { + speed: 6.4 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 6.4 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 6.4 + acceleration: -0.22 + command: -17.0 + } + calibration { + speed: 6.4 + acceleration: -0.21 + command: -13.0 + } + calibration { + speed: 6.4 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 6.4 + acceleration: -0.14 + command: 17.0 + } + calibration { + speed: 6.4 + acceleration: 0.25 + command: 22.0 + } + calibration { + speed: 6.4 + acceleration: 0.47 + command: 25.0 + } + calibration { + speed: 6.4 + acceleration: 0.76 + command: 27.0 + } + calibration { + speed: 6.4 + acceleration: 1.19 + command: 30.0 + } + calibration { + speed: 6.4 + acceleration: 2.13 + command: 35.0 + } + calibration { + speed: 6.4 + acceleration: 2.8 + command: 40.0 + } + calibration { + speed: 6.4 + acceleration: 3.02 + command: 45.0 + } + calibration { + speed: 6.4 + acceleration: 3.24 + command: 50.0 + } + calibration { + speed: 6.4 + acceleration: 3.46 + command: 57.5 + } + calibration { + speed: 6.6 + acceleration: -8.69 + command: -33.0 + } + calibration { + speed: 6.6 + acceleration: -5.03 + command: -32.0 + } + calibration { + speed: 6.6 + acceleration: -4.55 + command: -31.0 + } + calibration { + speed: 6.6 + acceleration: -4.0 + command: -30.0 + } + calibration { + speed: 6.6 + acceleration: -3.32 + command: -29.0 + } + calibration { + speed: 6.6 + acceleration: -2.8 + command: -28.0 + } + calibration { + speed: 6.6 + acceleration: -2.35 + command: -27.0 + } + calibration { + speed: 6.6 + acceleration: -1.86 + command: -26.0 + } + calibration { + speed: 6.6 + acceleration: -1.33 + command: -25.0 + } + calibration { + speed: 6.6 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.6 + acceleration: -0.58 + command: -23.0 + } + calibration { + speed: 6.6 + acceleration: -0.28 + command: -20.0 + } + calibration { + speed: 6.6 + acceleration: -0.24 + command: -15.0 + } + calibration { + speed: 6.6 + acceleration: -0.22 + command: -17.0 + } + calibration { + speed: 6.6 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 6.6 + acceleration: -0.18 + command: 15.0 + } + calibration { + speed: 6.6 + acceleration: -0.15 + command: 17.0 + } + calibration { + speed: 6.6 + acceleration: 0.24 + command: 22.0 + } + calibration { + speed: 6.6 + acceleration: 0.46 + command: 25.0 + } + calibration { + speed: 6.6 + acceleration: 0.72 + command: 27.0 + } + calibration { + speed: 6.6 + acceleration: 1.14 + command: 30.0 + } + calibration { + speed: 6.6 + acceleration: 2.07 + command: 35.0 + } + calibration { + speed: 6.6 + acceleration: 2.73 + command: 40.0 + } + calibration { + speed: 6.6 + acceleration: 2.94 + command: 45.0 + } + calibration { + speed: 6.6 + acceleration: 3.18 + command: 50.0 + } + calibration { + speed: 6.6 + acceleration: 3.42 + command: 55.0 + } + calibration { + speed: 6.6 + acceleration: 3.44 + command: 60.0 + } + calibration { + speed: 6.8 + acceleration: -8.64 + command: -33.0 + } + calibration { + speed: 6.8 + acceleration: -5.04 + command: -32.0 + } + calibration { + speed: 6.8 + acceleration: -4.56 + command: -31.0 + } + calibration { + speed: 6.8 + acceleration: -3.99 + command: -30.0 + } + calibration { + speed: 6.8 + acceleration: -3.31 + command: -29.0 + } + calibration { + speed: 6.8 + acceleration: -2.78 + command: -28.0 + } + calibration { + speed: 6.8 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 6.8 + acceleration: -1.87 + command: -26.0 + } + calibration { + speed: 6.8 + acceleration: -1.32 + command: -25.0 + } + calibration { + speed: 6.8 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 6.8 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 6.8 + acceleration: -0.28 + command: -20.0 + } + calibration { + speed: 6.8 + acceleration: -0.25 + command: -15.0 + } + calibration { + speed: 6.8 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 6.8 + acceleration: -0.2 + command: 1.0 + } + calibration { + speed: 6.8 + acceleration: -0.15 + command: 17.0 + } + calibration { + speed: 6.8 + acceleration: 0.16 + command: 22.0 + } + calibration { + speed: 6.8 + acceleration: 0.47 + command: 25.0 + } + calibration { + speed: 6.8 + acceleration: 0.71 + command: 27.0 + } + calibration { + speed: 6.8 + acceleration: 1.11 + command: 30.0 + } + calibration { + speed: 6.8 + acceleration: 2.02 + command: 35.0 + } + calibration { + speed: 6.8 + acceleration: 2.66 + command: 40.0 + } + calibration { + speed: 6.8 + acceleration: 2.88 + command: 45.0 + } + calibration { + speed: 6.8 + acceleration: 3.13 + command: 50.0 + } + calibration { + speed: 6.8 + acceleration: 3.38 + command: 55.0 + } + calibration { + speed: 6.8 + acceleration: 3.41 + command: 60.0 + } + calibration { + speed: 7.0 + acceleration: -8.61 + command: -33.0 + } + calibration { + speed: 7.0 + acceleration: -5.04 + command: -32.0 + } + calibration { + speed: 7.0 + acceleration: -4.57 + command: -31.0 + } + calibration { + speed: 7.0 + acceleration: -3.99 + command: -30.0 + } + calibration { + speed: 7.0 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 7.0 + acceleration: -2.76 + command: -28.0 + } + calibration { + speed: 7.0 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 7.0 + acceleration: -1.88 + command: -26.0 + } + calibration { + speed: 7.0 + acceleration: -1.33 + command: -25.0 + } + calibration { + speed: 7.0 + acceleration: -0.91 + command: -24.0 + } + calibration { + speed: 7.0 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 7.0 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 7.0 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 7.0 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 7.0 + acceleration: -0.2 + command: 15.0 + } + calibration { + speed: 7.0 + acceleration: -0.17 + command: -13.0 + } + calibration { + speed: 7.0 + acceleration: -0.16 + command: 17.0 + } + calibration { + speed: 7.0 + acceleration: 0.21 + command: 22.0 + } + calibration { + speed: 7.0 + acceleration: 0.47 + command: 25.0 + } + calibration { + speed: 7.0 + acceleration: 0.69 + command: 27.0 + } + calibration { + speed: 7.0 + acceleration: 1.08 + command: 30.0 + } + calibration { + speed: 7.0 + acceleration: 1.97 + command: 35.0 + } + calibration { + speed: 7.0 + acceleration: 2.59 + command: 40.0 + } + calibration { + speed: 7.0 + acceleration: 2.83 + command: 45.0 + } + calibration { + speed: 7.0 + acceleration: 3.08 + command: 50.0 + } + calibration { + speed: 7.0 + acceleration: 3.34 + command: 55.0 + } + calibration { + speed: 7.0 + acceleration: 3.37 + command: 60.0 + } + calibration { + speed: 7.2 + acceleration: -8.59 + command: -33.0 + } + calibration { + speed: 7.2 + acceleration: -5.05 + command: -32.0 + } + calibration { + speed: 7.2 + acceleration: -4.58 + command: -31.0 + } + calibration { + speed: 7.2 + acceleration: -3.99 + command: -30.0 + } + calibration { + speed: 7.2 + acceleration: -3.29 + command: -29.0 + } + calibration { + speed: 7.2 + acceleration: -2.77 + command: -28.0 + } + calibration { + speed: 7.2 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 7.2 + acceleration: -1.89 + command: -26.0 + } + calibration { + speed: 7.2 + acceleration: -1.33 + command: -25.0 + } + calibration { + speed: 7.2 + acceleration: -0.92 + command: -24.0 + } + calibration { + speed: 7.2 + acceleration: -0.62 + command: -23.0 + } + calibration { + speed: 7.2 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 7.2 + acceleration: -0.24 + command: -15.0 + } + calibration { + speed: 7.2 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 7.2 + acceleration: -0.2 + command: 15.0 + } + calibration { + speed: 7.2 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 7.2 + acceleration: -0.15 + command: 17.0 + } + calibration { + speed: 7.2 + acceleration: 0.18 + command: 22.0 + } + calibration { + speed: 7.2 + acceleration: 0.44 + command: 25.0 + } + calibration { + speed: 7.2 + acceleration: 0.66 + command: 27.0 + } + calibration { + speed: 7.2 + acceleration: 1.04 + command: 30.0 + } + calibration { + speed: 7.2 + acceleration: 1.9 + command: 35.0 + } + calibration { + speed: 7.2 + acceleration: 2.52 + command: 40.0 + } + calibration { + speed: 7.2 + acceleration: 2.78 + command: 45.0 + } + calibration { + speed: 7.2 + acceleration: 3.03 + command: 50.0 + } + calibration { + speed: 7.2 + acceleration: 3.29 + command: 55.0 + } + calibration { + speed: 7.2 + acceleration: 3.33 + command: 60.0 + } + calibration { + speed: 7.4 + acceleration: -8.61 + command: -33.0 + } + calibration { + speed: 7.4 + acceleration: -5.04 + command: -32.0 + } + calibration { + speed: 7.4 + acceleration: -4.59 + command: -31.0 + } + calibration { + speed: 7.4 + acceleration: -4.0 + command: -30.0 + } + calibration { + speed: 7.4 + acceleration: -3.3 + command: -29.0 + } + calibration { + speed: 7.4 + acceleration: -2.78 + command: -28.0 + } + calibration { + speed: 7.4 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 7.4 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 7.4 + acceleration: -1.33 + command: -25.0 + } + calibration { + speed: 7.4 + acceleration: -0.92 + command: -24.0 + } + calibration { + speed: 7.4 + acceleration: -0.62 + command: -23.0 + } + calibration { + speed: 7.4 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 7.4 + acceleration: -0.25 + command: -16.0 + } + calibration { + speed: 7.4 + acceleration: -0.22 + command: 15.0 + } + calibration { + speed: 7.4 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 7.4 + acceleration: -0.16 + command: 17.0 + } + calibration { + speed: 7.4 + acceleration: 0.21 + command: 22.0 + } + calibration { + speed: 7.4 + acceleration: 0.42 + command: 25.0 + } + calibration { + speed: 7.4 + acceleration: 0.65 + command: 27.0 + } + calibration { + speed: 7.4 + acceleration: 1.0 + command: 30.0 + } + calibration { + speed: 7.4 + acceleration: 1.81 + command: 35.0 + } + calibration { + speed: 7.4 + acceleration: 2.44 + command: 40.0 + } + calibration { + speed: 7.4 + acceleration: 2.72 + command: 45.0 + } + calibration { + speed: 7.4 + acceleration: 2.99 + command: 50.0 + } + calibration { + speed: 7.4 + acceleration: 3.25 + command: 55.0 + } + calibration { + speed: 7.4 + acceleration: 3.29 + command: 60.0 + } + calibration { + speed: 7.6 + acceleration: -8.66 + command: -33.0 + } + calibration { + speed: 7.6 + acceleration: -5.03 + command: -32.0 + } + calibration { + speed: 7.6 + acceleration: -4.59 + command: -31.0 + } + calibration { + speed: 7.6 + acceleration: -4.0 + command: -30.0 + } + calibration { + speed: 7.6 + acceleration: -3.31 + command: -29.0 + } + calibration { + speed: 7.6 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 7.6 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 7.6 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 7.6 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 7.6 + acceleration: -0.92 + command: -24.0 + } + calibration { + speed: 7.6 + acceleration: -0.61 + command: -23.0 + } + calibration { + speed: 7.6 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 7.6 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 7.6 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 7.6 + acceleration: -0.23 + command: 15.0 + } + calibration { + speed: 7.6 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 7.6 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 7.6 + acceleration: 0.17 + command: 22.0 + } + calibration { + speed: 7.6 + acceleration: 0.41 + command: 25.0 + } + calibration { + speed: 7.6 + acceleration: 0.62 + command: 27.0 + } + calibration { + speed: 7.6 + acceleration: 0.98 + command: 30.0 + } + calibration { + speed: 7.6 + acceleration: 1.76 + command: 35.0 + } + calibration { + speed: 7.6 + acceleration: 2.37 + command: 40.0 + } + calibration { + speed: 7.6 + acceleration: 2.66 + command: 45.0 + } + calibration { + speed: 7.6 + acceleration: 2.93 + command: 50.0 + } + calibration { + speed: 7.6 + acceleration: 3.21 + command: 55.0 + } + calibration { + speed: 7.6 + acceleration: 3.25 + command: 60.0 + } + calibration { + speed: 7.8 + acceleration: -8.77 + command: -33.0 + } + calibration { + speed: 7.8 + acceleration: -5.01 + command: -32.0 + } + calibration { + speed: 7.8 + acceleration: -4.57 + command: -31.0 + } + calibration { + speed: 7.8 + acceleration: -3.99 + command: -30.0 + } + calibration { + speed: 7.8 + acceleration: -3.32 + command: -29.0 + } + calibration { + speed: 7.8 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 7.8 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 7.8 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 7.8 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 7.8 + acceleration: -0.93 + command: -24.0 + } + calibration { + speed: 7.8 + acceleration: -0.62 + command: -23.0 + } + calibration { + speed: 7.8 + acceleration: -0.28 + command: -20.0 + } + calibration { + speed: 7.8 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 7.8 + acceleration: -0.25 + command: -17.0 + } + calibration { + speed: 7.8 + acceleration: -0.23 + command: 15.0 + } + calibration { + speed: 7.8 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 7.8 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 7.8 + acceleration: 0.14 + command: 22.0 + } + calibration { + speed: 7.8 + acceleration: 0.42 + command: 25.0 + } + calibration { + speed: 7.8 + acceleration: 0.6 + command: 27.0 + } + calibration { + speed: 7.8 + acceleration: 0.95 + command: 30.0 + } + calibration { + speed: 7.8 + acceleration: 1.73 + command: 35.0 + } + calibration { + speed: 7.8 + acceleration: 2.3 + command: 40.0 + } + calibration { + speed: 7.8 + acceleration: 2.59 + command: 45.0 + } + calibration { + speed: 7.8 + acceleration: 2.88 + command: 50.0 + } + calibration { + speed: 7.8 + acceleration: 3.15 + command: 55.0 + } + calibration { + speed: 7.8 + acceleration: 3.21 + command: 60.0 + } + calibration { + speed: 8.0 + acceleration: -8.87 + command: -33.0 + } + calibration { + speed: 8.0 + acceleration: -5.0 + command: -32.0 + } + calibration { + speed: 8.0 + acceleration: -4.54 + command: -31.0 + } + calibration { + speed: 8.0 + acceleration: -3.98 + command: -30.0 + } + calibration { + speed: 8.0 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 8.0 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 8.0 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 8.0 + acceleration: -1.9 + command: -26.0 + } + calibration { + speed: 8.0 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 8.0 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 8.0 + acceleration: -0.62 + command: -23.0 + } + calibration { + speed: 8.0 + acceleration: -0.28 + command: -20.0 + } + calibration { + speed: 8.0 + acceleration: -0.26 + command: 0.0 + } + calibration { + speed: 8.0 + acceleration: -0.25 + command: -17.0 + } + calibration { + speed: 8.0 + acceleration: -0.18 + command: 2.0 + } + calibration { + speed: 8.0 + acceleration: 0.17 + command: 22.0 + } + calibration { + speed: 8.0 + acceleration: 0.4 + command: 25.0 + } + calibration { + speed: 8.0 + acceleration: 0.57 + command: 27.0 + } + calibration { + speed: 8.0 + acceleration: 0.94 + command: 30.0 + } + calibration { + speed: 8.0 + acceleration: 1.7 + command: 35.0 + } + calibration { + speed: 8.0 + acceleration: 2.24 + command: 40.0 + } + calibration { + speed: 8.0 + acceleration: 2.52 + command: 45.0 + } + calibration { + speed: 8.0 + acceleration: 2.82 + command: 50.0 + } + calibration { + speed: 8.0 + acceleration: 3.08 + command: 55.0 + } + calibration { + speed: 8.0 + acceleration: 3.17 + command: 60.0 + } + calibration { + speed: 8.2 + acceleration: -8.99 + command: -33.0 + } + calibration { + speed: 8.2 + acceleration: -5.0 + command: -32.0 + } + calibration { + speed: 8.2 + acceleration: -4.5 + command: -31.0 + } + calibration { + speed: 8.2 + acceleration: -3.98 + command: -30.0 + } + calibration { + speed: 8.2 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 8.2 + acceleration: -2.79 + command: -28.0 + } + calibration { + speed: 8.2 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 8.2 + acceleration: -1.91 + command: -26.0 + } + calibration { + speed: 8.2 + acceleration: -1.34 + command: -25.0 + } + calibration { + speed: 8.2 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 8.2 + acceleration: -0.64 + command: -23.0 + } + calibration { + speed: 8.2 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 8.2 + acceleration: -0.28 + command: -15.0 + } + calibration { + speed: 8.2 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 8.2 + acceleration: -0.24 + command: 15.0 + } + calibration { + speed: 8.2 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 8.2 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 8.2 + acceleration: -0.04 + command: 20.0 + } + calibration { + speed: 8.2 + acceleration: 0.17 + command: 22.0 + } + calibration { + speed: 8.2 + acceleration: 0.38 + command: 25.0 + } + calibration { + speed: 8.2 + acceleration: 0.55 + command: 27.0 + } + calibration { + speed: 8.2 + acceleration: 0.9 + command: 30.0 + } + calibration { + speed: 8.2 + acceleration: 1.64 + command: 35.0 + } + calibration { + speed: 8.2 + acceleration: 2.19 + command: 40.0 + } + calibration { + speed: 8.2 + acceleration: 2.46 + command: 45.0 + } + calibration { + speed: 8.2 + acceleration: 2.77 + command: 50.0 + } + calibration { + speed: 8.2 + acceleration: 3.03 + command: 55.0 + } + calibration { + speed: 8.2 + acceleration: 3.14 + command: 60.0 + } + calibration { + speed: 8.4 + acceleration: -9.11 + command: -33.0 + } + calibration { + speed: 8.4 + acceleration: -5.01 + command: -32.0 + } + calibration { + speed: 8.4 + acceleration: -4.47 + command: -31.0 + } + calibration { + speed: 8.4 + acceleration: -3.97 + command: -30.0 + } + calibration { + speed: 8.4 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 8.4 + acceleration: -2.81 + command: -28.0 + } + calibration { + speed: 8.4 + acceleration: -2.34 + command: -27.0 + } + calibration { + speed: 8.4 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 8.4 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 8.4 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 8.4 + acceleration: -0.65 + command: -23.0 + } + calibration { + speed: 8.4 + acceleration: -0.28 + command: -20.0 + } + calibration { + speed: 8.4 + acceleration: -0.27 + command: -15.0 + } + calibration { + speed: 8.4 + acceleration: -0.25 + command: -17.0 + } + calibration { + speed: 8.4 + acceleration: -0.24 + command: 15.0 + } + calibration { + speed: 8.4 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 8.4 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 8.4 + acceleration: -0.08 + command: 20.0 + } + calibration { + speed: 8.4 + acceleration: 0.12 + command: 22.0 + } + calibration { + speed: 8.4 + acceleration: 0.36 + command: 25.0 + } + calibration { + speed: 8.4 + acceleration: 0.54 + command: 27.0 + } + calibration { + speed: 8.4 + acceleration: 0.85 + command: 30.0 + } + calibration { + speed: 8.4 + acceleration: 1.57 + command: 35.0 + } + calibration { + speed: 8.4 + acceleration: 2.13 + command: 40.0 + } + calibration { + speed: 8.4 + acceleration: 2.41 + command: 45.0 + } + calibration { + speed: 8.4 + acceleration: 2.71 + command: 50.0 + } + calibration { + speed: 8.4 + acceleration: 2.97 + command: 55.0 + } + calibration { + speed: 8.4 + acceleration: 3.11 + command: 60.0 + } + calibration { + speed: 8.6 + acceleration: -9.23 + command: -33.0 + } + calibration { + speed: 8.6 + acceleration: -5.03 + command: -32.0 + } + calibration { + speed: 8.6 + acceleration: -4.46 + command: -31.0 + } + calibration { + speed: 8.6 + acceleration: -3.97 + command: -30.0 + } + calibration { + speed: 8.6 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 8.6 + acceleration: -2.83 + command: -28.0 + } + calibration { + speed: 8.6 + acceleration: -2.35 + command: -27.0 + } + calibration { + speed: 8.6 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 8.6 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 8.6 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 8.6 + acceleration: -0.64 + command: -23.0 + } + calibration { + speed: 8.6 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 8.6 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 8.6 + acceleration: -0.25 + command: 15.0 + } + calibration { + speed: 8.6 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 8.6 + acceleration: -0.22 + command: -13.0 + } + calibration { + speed: 8.6 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 8.6 + acceleration: -0.07 + command: 20.0 + } + calibration { + speed: 8.6 + acceleration: 0.15 + command: 22.0 + } + calibration { + speed: 8.6 + acceleration: 0.34 + command: 25.0 + } + calibration { + speed: 8.6 + acceleration: 0.51 + command: 27.0 + } + calibration { + speed: 8.6 + acceleration: 0.86 + command: 30.0 + } + calibration { + speed: 8.6 + acceleration: 1.5 + command: 35.0 + } + calibration { + speed: 8.6 + acceleration: 2.08 + command: 40.0 + } + calibration { + speed: 8.6 + acceleration: 2.36 + command: 45.0 + } + calibration { + speed: 8.6 + acceleration: 2.66 + command: 50.0 + } + calibration { + speed: 8.6 + acceleration: 2.92 + command: 55.0 + } + calibration { + speed: 8.6 + acceleration: 3.08 + command: 60.0 + } + calibration { + speed: 8.8 + acceleration: -9.34 + command: -33.0 + } + calibration { + speed: 8.8 + acceleration: -5.05 + command: -32.0 + } + calibration { + speed: 8.8 + acceleration: -4.47 + command: -31.0 + } + calibration { + speed: 8.8 + acceleration: -3.96 + command: -30.0 + } + calibration { + speed: 8.8 + acceleration: -3.31 + command: -29.0 + } + calibration { + speed: 8.8 + acceleration: -2.86 + command: -28.0 + } + calibration { + speed: 8.8 + acceleration: -2.35 + command: -27.0 + } + calibration { + speed: 8.8 + acceleration: -1.92 + command: -26.0 + } + calibration { + speed: 8.8 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 8.8 + acceleration: -0.94 + command: -24.0 + } + calibration { + speed: 8.8 + acceleration: -0.64 + command: -23.0 + } + calibration { + speed: 8.8 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 8.8 + acceleration: -0.28 + command: -15.0 + } + calibration { + speed: 8.8 + acceleration: -0.26 + command: 15.0 + } + calibration { + speed: 8.8 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 8.8 + acceleration: -0.17 + command: 17.0 + } + calibration { + speed: 8.8 + acceleration: -0.08 + command: 20.0 + } + calibration { + speed: 8.8 + acceleration: 0.11 + command: 22.0 + } + calibration { + speed: 8.8 + acceleration: 0.3 + command: 25.0 + } + calibration { + speed: 8.8 + acceleration: 0.5 + command: 27.0 + } + calibration { + speed: 8.8 + acceleration: 0.82 + command: 30.0 + } + calibration { + speed: 8.8 + acceleration: 1.47 + command: 35.0 + } + calibration { + speed: 8.8 + acceleration: 2.03 + command: 40.0 + } + calibration { + speed: 8.8 + acceleration: 2.31 + command: 45.0 + } + calibration { + speed: 8.8 + acceleration: 2.61 + command: 50.0 + } + calibration { + speed: 8.8 + acceleration: 2.89 + command: 55.0 + } + calibration { + speed: 8.8 + acceleration: 3.05 + command: 60.0 + } + calibration { + speed: 9.0 + acceleration: -9.44 + command: -33.0 + } + calibration { + speed: 9.0 + acceleration: -5.05 + command: -32.0 + } + calibration { + speed: 9.0 + acceleration: -4.5 + command: -31.0 + } + calibration { + speed: 9.0 + acceleration: -3.92 + command: -30.0 + } + calibration { + speed: 9.0 + acceleration: -3.29 + command: -29.0 + } + calibration { + speed: 9.0 + acceleration: -2.88 + command: -28.0 + } + calibration { + speed: 9.0 + acceleration: -2.36 + command: -27.0 + } + calibration { + speed: 9.0 + acceleration: -1.91 + command: -26.0 + } + calibration { + speed: 9.0 + acceleration: -1.35 + command: -25.0 + } + calibration { + speed: 9.0 + acceleration: -0.95 + command: -24.0 + } + calibration { + speed: 9.0 + acceleration: -0.64 + command: -23.0 + } + calibration { + speed: 9.0 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 9.0 + acceleration: -0.27 + command: -15.0 + } + calibration { + speed: 9.0 + acceleration: -0.23 + command: -1.0 + } + calibration { + speed: 9.0 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 9.0 + acceleration: -0.18 + command: 17.0 + } + calibration { + speed: 9.0 + acceleration: -0.06 + command: 20.0 + } + calibration { + speed: 9.0 + acceleration: 0.11 + command: 22.0 + } + calibration { + speed: 9.0 + acceleration: 0.34 + command: 25.0 + } + calibration { + speed: 9.0 + acceleration: 0.47 + command: 27.0 + } + calibration { + speed: 9.0 + acceleration: 0.79 + command: 30.0 + } + calibration { + speed: 9.0 + acceleration: 1.43 + command: 35.0 + } + calibration { + speed: 9.0 + acceleration: 1.98 + command: 40.0 + } + calibration { + speed: 9.0 + acceleration: 2.26 + command: 45.0 + } + calibration { + speed: 9.0 + acceleration: 2.56 + command: 50.0 + } + calibration { + speed: 9.0 + acceleration: 2.84 + command: 55.0 + } + calibration { + speed: 9.0 + acceleration: 3.01 + command: 60.0 + } + calibration { + speed: 9.2 + acceleration: -9.49 + command: -33.0 + } + calibration { + speed: 9.2 + acceleration: -5.02 + command: -32.0 + } + calibration { + speed: 9.2 + acceleration: -4.53 + command: -31.0 + } + calibration { + speed: 9.2 + acceleration: -3.88 + command: -30.0 + } + calibration { + speed: 9.2 + acceleration: -3.27 + command: -29.0 + } + calibration { + speed: 9.2 + acceleration: -2.88 + command: -28.0 + } + calibration { + speed: 9.2 + acceleration: -2.37 + command: -27.0 + } + calibration { + speed: 9.2 + acceleration: -1.93 + command: -26.0 + } + calibration { + speed: 9.2 + acceleration: -1.36 + command: -25.0 + } + calibration { + speed: 9.2 + acceleration: -0.96 + command: -24.0 + } + calibration { + speed: 9.2 + acceleration: -0.66 + command: -23.0 + } + calibration { + speed: 9.2 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 9.2 + acceleration: -0.27 + command: -15.0 + } + calibration { + speed: 9.2 + acceleration: -0.25 + command: -17.0 + } + calibration { + speed: 9.2 + acceleration: -0.24 + command: 15.0 + } + calibration { + speed: 9.2 + acceleration: -0.21 + command: -13.0 + } + calibration { + speed: 9.2 + acceleration: -0.18 + command: 17.0 + } + calibration { + speed: 9.2 + acceleration: -0.09 + command: 20.0 + } + calibration { + speed: 9.2 + acceleration: 0.12 + command: 22.0 + } + calibration { + speed: 9.2 + acceleration: 0.31 + command: 25.0 + } + calibration { + speed: 9.2 + acceleration: 0.43 + command: 27.0 + } + calibration { + speed: 9.2 + acceleration: 0.76 + command: 30.0 + } + calibration { + speed: 9.2 + acceleration: 1.38 + command: 35.0 + } + calibration { + speed: 9.2 + acceleration: 1.93 + command: 40.0 + } + calibration { + speed: 9.2 + acceleration: 2.21 + command: 45.0 + } + calibration { + speed: 9.2 + acceleration: 2.52 + command: 50.0 + } + calibration { + speed: 9.2 + acceleration: 2.79 + command: 55.0 + } + calibration { + speed: 9.2 + acceleration: 2.96 + command: 60.0 + } + calibration { + speed: 9.4 + acceleration: -9.5 + command: -33.0 + } + calibration { + speed: 9.4 + acceleration: -4.95 + command: -32.0 + } + calibration { + speed: 9.4 + acceleration: -4.52 + command: -31.0 + } + calibration { + speed: 9.4 + acceleration: -3.79 + command: -30.0 + } + calibration { + speed: 9.4 + acceleration: -3.27 + command: -29.0 + } + calibration { + speed: 9.4 + acceleration: -2.87 + command: -28.0 + } + calibration { + speed: 9.4 + acceleration: -2.38 + command: -27.0 + } + calibration { + speed: 9.4 + acceleration: -1.95 + command: -26.0 + } + calibration { + speed: 9.4 + acceleration: -1.37 + command: -25.0 + } + calibration { + speed: 9.4 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 9.4 + acceleration: -0.66 + command: -23.0 + } + calibration { + speed: 9.4 + acceleration: -0.3 + command: -20.0 + } + calibration { + speed: 9.4 + acceleration: -0.27 + command: 15.0 + } + calibration { + speed: 9.4 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 9.4 + acceleration: -0.25 + command: -15.0 + } + calibration { + speed: 9.4 + acceleration: -0.18 + command: 17.0 + } + calibration { + speed: 9.4 + acceleration: -0.12 + command: 20.0 + } + calibration { + speed: 9.4 + acceleration: 0.08 + command: 22.0 + } + calibration { + speed: 9.4 + acceleration: 0.3 + command: 25.0 + } + calibration { + speed: 9.4 + acceleration: 0.42 + command: 27.0 + } + calibration { + speed: 9.4 + acceleration: 0.72 + command: 30.0 + } + calibration { + speed: 9.4 + acceleration: 1.35 + command: 35.0 + } + calibration { + speed: 9.4 + acceleration: 1.88 + command: 40.0 + } + calibration { + speed: 9.4 + acceleration: 2.16 + command: 45.0 + } + calibration { + speed: 9.4 + acceleration: 2.48 + command: 50.0 + } + calibration { + speed: 9.4 + acceleration: 2.74 + command: 55.0 + } + calibration { + speed: 9.4 + acceleration: 2.91 + command: 60.0 + } + calibration { + speed: 9.6 + acceleration: -9.43 + command: -33.0 + } + calibration { + speed: 9.6 + acceleration: -4.88 + command: -32.0 + } + calibration { + speed: 9.6 + acceleration: -4.49 + command: -31.0 + } + calibration { + speed: 9.6 + acceleration: -3.66 + command: -30.0 + } + calibration { + speed: 9.6 + acceleration: -3.29 + command: -29.0 + } + calibration { + speed: 9.6 + acceleration: -2.84 + command: -28.0 + } + calibration { + speed: 9.6 + acceleration: -2.38 + command: -27.0 + } + calibration { + speed: 9.6 + acceleration: -1.96 + command: -26.0 + } + calibration { + speed: 9.6 + acceleration: -1.37 + command: -25.0 + } + calibration { + speed: 9.6 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 9.6 + acceleration: -0.67 + command: -23.0 + } + calibration { + speed: 9.6 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 9.6 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 9.6 + acceleration: -0.25 + command: 15.0 + } + calibration { + speed: 9.6 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 9.6 + acceleration: -0.23 + command: -13.0 + } + calibration { + speed: 9.6 + acceleration: -0.18 + command: 17.0 + } + calibration { + speed: 9.6 + acceleration: -0.09 + command: 20.0 + } + calibration { + speed: 9.6 + acceleration: 0.06 + command: 22.0 + } + calibration { + speed: 9.6 + acceleration: 0.27 + command: 25.0 + } + calibration { + speed: 9.6 + acceleration: 0.4 + command: 27.0 + } + calibration { + speed: 9.6 + acceleration: 0.69 + command: 30.0 + } + calibration { + speed: 9.6 + acceleration: 1.31 + command: 35.0 + } + calibration { + speed: 9.6 + acceleration: 1.84 + command: 40.0 + } + calibration { + speed: 9.6 + acceleration: 2.12 + command: 45.0 + } + calibration { + speed: 9.6 + acceleration: 2.43 + command: 50.0 + } + calibration { + speed: 9.6 + acceleration: 2.68 + command: 55.0 + } + calibration { + speed: 9.6 + acceleration: 2.87 + command: 60.0 + } + calibration { + speed: 9.8 + acceleration: -9.17 + command: -33.0 + } + calibration { + speed: 9.8 + acceleration: -4.82 + command: -32.0 + } + calibration { + speed: 9.8 + acceleration: -4.44 + command: -31.0 + } + calibration { + speed: 9.8 + acceleration: -3.6 + command: -30.0 + } + calibration { + speed: 9.8 + acceleration: -3.32 + command: -29.0 + } + calibration { + speed: 9.8 + acceleration: -2.83 + command: -28.0 + } + calibration { + speed: 9.8 + acceleration: -2.38 + command: -27.0 + } + calibration { + speed: 9.8 + acceleration: -1.97 + command: -26.0 + } + calibration { + speed: 9.8 + acceleration: -1.38 + command: -25.0 + } + calibration { + speed: 9.8 + acceleration: -0.98 + command: -24.0 + } + calibration { + speed: 9.8 + acceleration: -0.68 + command: -23.0 + } + calibration { + speed: 9.8 + acceleration: -0.32 + command: -20.0 + } + calibration { + speed: 9.8 + acceleration: -0.29 + command: 15.0 + } + calibration { + speed: 9.8 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 9.8 + acceleration: -0.25 + command: -13.0 + } + calibration { + speed: 9.8 + acceleration: -0.24 + command: -17.0 + } + calibration { + speed: 9.8 + acceleration: -0.18 + command: 17.0 + } + calibration { + speed: 9.8 + acceleration: -0.1 + command: 20.0 + } + calibration { + speed: 9.8 + acceleration: 0.04 + command: 22.0 + } + calibration { + speed: 9.8 + acceleration: 0.28 + command: 25.0 + } + calibration { + speed: 9.8 + acceleration: 0.4 + command: 27.0 + } + calibration { + speed: 9.8 + acceleration: 0.65 + command: 30.0 + } + calibration { + speed: 9.8 + acceleration: 1.27 + command: 35.0 + } + calibration { + speed: 9.8 + acceleration: 1.79 + command: 40.0 + } + calibration { + speed: 9.8 + acceleration: 2.08 + command: 45.0 + } + calibration { + speed: 9.8 + acceleration: 2.39 + command: 50.0 + } + calibration { + speed: 9.8 + acceleration: 2.63 + command: 55.0 + } + calibration { + speed: 9.8 + acceleration: 2.82 + command: 60.0 + } + calibration { + speed: 10.0 + acceleration: -8.69 + command: -33.0 + } + calibration { + speed: 10.0 + acceleration: -4.8 + command: -32.0 + } + calibration { + speed: 10.0 + acceleration: -4.35 + command: -31.0 + } + calibration { + speed: 10.0 + acceleration: -3.89 + command: -30.0 + } + calibration { + speed: 10.0 + acceleration: -3.33 + command: -29.0 + } + calibration { + speed: 10.0 + acceleration: -2.82 + command: -28.0 + } + calibration { + speed: 10.0 + acceleration: -2.38 + command: -27.0 + } + calibration { + speed: 10.0 + acceleration: -1.96 + command: -26.0 + } + calibration { + speed: 10.0 + acceleration: -1.4 + command: -25.0 + } + calibration { + speed: 10.0 + acceleration: -0.97 + command: -24.0 + } + calibration { + speed: 10.0 + acceleration: -0.68 + command: -23.0 + } + calibration { + speed: 10.0 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 10.0 + acceleration: -0.27 + command: -15.0 + } + calibration { + speed: 10.0 + acceleration: -0.25 + command: 15.0 + } + calibration { + speed: 10.0 + acceleration: -0.24 + command: -13.0 + } + calibration { + speed: 10.0 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 10.0 + acceleration: -0.2 + command: 17.0 + } + calibration { + speed: 10.0 + acceleration: -0.09 + command: 20.0 + } + calibration { + speed: 10.0 + acceleration: 0.27 + command: 25.0 + } + calibration { + speed: 10.0 + acceleration: 0.39 + command: 27.0 + } + calibration { + speed: 10.0 + acceleration: 0.63 + command: 30.0 + } + calibration { + speed: 10.0 + acceleration: 1.27 + command: 35.0 + } + calibration { + speed: 10.0 + acceleration: 1.75 + command: 40.0 + } + calibration { + speed: 10.0 + acceleration: 2.03 + command: 45.0 + } + calibration { + speed: 10.0 + acceleration: 2.35 + command: 50.0 + } + calibration { + speed: 10.0 + acceleration: 2.59 + command: 55.0 + } + calibration { + speed: 10.0 + acceleration: 2.79 + command: 60.0 + } + } +} +trajectory_period: 0.1 +chassis_period: 0.01 +localization_period: 0.01 diff --git a/apollo_control/conf/lincoln_062845.pb.txt b/apollo_control/conf/lincoln_062845.pb.txt new file mode 100644 index 0000000..c39b3ae --- /dev/null +++ b/apollo_control/conf/lincoln_062845.pb.txt @@ -0,0 +1,6680 @@ +control_period: 0.01 +max_planning_interval_sec: 0.2 +max_planning_delay_threshold: 4.0 +action: STOP +soft_estop_brake: 50.0 +active_controllers: LAT_CONTROLLER +active_controllers: LON_CONTROLLER +max_steering_percentage_allowed: 100 +max_status_interval_sec: 0.1 +lat_controller_conf { + ts: 0.01 + preview_window: 0 + cf: 155494.663 + cr: 155494.663 + wheelbase: 2.85 + mass_fl: 520 + mass_fr: 520 + mass_rl: 520 + mass_rr: 520 + eps: 0.01 + matrix_q: 0.02 + matrix_q: 0.0 + matrix_q: 0.4 + matrix_q: 0.0 + cutoff_freq: 10 + mean_filter_window_size: 10 + steer_transmission_ratio: 16 + steer_single_direction_max_degree: 470 + max_iteration: 150 +} +lon_controller_conf { + ts: 0.01 + brake_deadzone: 15.5 + throttle_deadzone: 18.0 + speed_controller_input_limit: 2.0 + station_error_limit: 2.0 + preview_window: 15.0 + standstill_acceleration: -3.0 + station_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 0.8 + ki: 0.0 + kd: 0.0 + } + low_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 3.0 + ki: 0.0 + kd: 0.0 + } + high_speed_pid_conf { + integrator_enable: true + integrator_saturation_level: 0.3 + kp: 1.0 + ki: 0.3 + kd: 0.0 + } + switch_speed: 2.0 + throttle_filter_conf { + cutoff_freq: 10 + } + brake_filter_conf { + cutoff_freq: 10 + } + acceleration_filter_conf { + cutoff_freq: 5 + } + calibration_table { + calibration { + speed: 0.0 + acceleration: -4.65 + command: -35.0 + } + calibration { + speed: 0.0 + acceleration: -3.85 + command: -33.0 + } + calibration { + speed: 0.0 + acceleration: -3.48 + command: -32.0 + } + calibration { + speed: 0.0 + acceleration: -3.13 + command: -31.0 + } + calibration { + speed: 0.0 + acceleration: -2.8 + command: -30.0 + } + calibration { + speed: 0.0 + acceleration: -2.53 + command: -29.0 + } + calibration { + speed: 0.0 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 0.0 + acceleration: -1.7 + command: -27.0 + } + calibration { + speed: 0.0 + acceleration: -1.19 + command: -26.0 + } + calibration { + speed: 0.0 + acceleration: -0.65 + command: -25.0 + } + calibration { + speed: 0.0 + acceleration: -0.3 + command: -24.0 + } + calibration { + speed: 0.0 + acceleration: 0.1 + command: -22.0 + } + calibration { + speed: 0.0 + acceleration: 0.31 + command: -20.0 + } + calibration { + speed: 0.0 + acceleration: 0.34 + command: -17.0 + } + calibration { + speed: 0.0 + acceleration: 0.36 + command: -15.0 + } + calibration { + speed: 0.0 + acceleration: 0.38 + command: -15.0 + } + calibration { + speed: 0.0 + acceleration: 0.84 + command: 20.0 + } + calibration { + speed: 0.0 + acceleration: 0.97 + command: 22.0 + } + calibration { + speed: 0.0 + acceleration: 1.39 + command: 25.0 + } + calibration { + speed: 0.0 + acceleration: 1.46 + command: 27.0 + } + calibration { + speed: 0.0 + acceleration: 1.53 + command: 30.0 + } + calibration { + speed: 0.0 + acceleration: 1.6 + command: 35.0 + } + calibration { + speed: 0.0 + acceleration: 1.69 + command: 40.0 + } + calibration { + speed: 0.0 + acceleration: 1.72 + command: 45.0 + } + calibration { + speed: 0.0 + acceleration: 1.88 + command: 50.0 + } + calibration { + speed: 0.0 + acceleration: 1.96 + command: 55.0 + } + calibration { + speed: 0.2 + acceleration: -4.95 + command: -35.0 + } + calibration { + speed: 0.2 + acceleration: -3.99 + command: -33.0 + } + calibration { + speed: 0.2 + acceleration: -3.61 + command: -32.0 + } + calibration { + speed: 0.2 + acceleration: -3.25 + command: -31.0 + } + calibration { + speed: 0.2 + acceleration: -2.86 + command: -30.0 + } + calibration { + speed: 0.2 + acceleration: -2.57 + command: -29.0 + } + calibration { + speed: 0.2 + acceleration: -2.24 + command: -28.0 + } + calibration { + speed: 0.2 + acceleration: -1.71 + command: -27.0 + } + calibration { + speed: 0.2 + acceleration: -1.2 + command: -26.0 + } + calibration { + speed: 0.2 + acceleration: -0.65 + command: -25.0 + } + calibration { + speed: 0.2 + acceleration: -0.3 + command: -24.0 + } + calibration { + speed: 0.2 + acceleration: 0.1 + command: -22.0 + } + calibration { + speed: 0.2 + acceleration: 0.31 + command: -13.0 + } + calibration { + speed: 0.2 + acceleration: 0.34 + command: -20.0 + } + calibration { + speed: 0.2 + acceleration: 0.36 + command: -15.0 + } + calibration { + speed: 0.2 + acceleration: 0.38 + command: -17.0 + } + calibration { + speed: 0.2 + acceleration: 0.84 + command: 20.0 + } + calibration { + speed: 0.2 + acceleration: 0.98 + command: 22.0 + } + calibration { + speed: 0.2 + acceleration: 1.42 + command: 25.0 + } + calibration { + speed: 0.2 + acceleration: 1.51 + command: 27.0 + } + calibration { + speed: 0.2 + acceleration: 1.58 + command: 30.0 + } + calibration { + speed: 0.2 + acceleration: 1.67 + command: 35.0 + } + calibration { + speed: 0.2 + acceleration: 1.77 + command: 40.0 + } + calibration { + speed: 0.2 + acceleration: 1.82 + command: 45.0 + } + calibration { + speed: 0.2 + acceleration: 1.99 + command: 50.0 + } + calibration { + speed: 0.2 + acceleration: 2.08 + command: 55.0 + } + calibration { + speed: 0.4 + acceleration: -6.23 + command: -35.0 + } + calibration { + speed: 0.4 + acceleration: -4.63 + command: -33.0 + } + calibration { + speed: 0.4 + acceleration: -4.18 + command: -32.0 + } + calibration { + speed: 0.4 + acceleration: -3.79 + command: -31.0 + } + calibration { + speed: 0.4 + acceleration: -3.23 + command: -30.0 + } + calibration { + speed: 0.4 + acceleration: -2.87 + command: -29.0 + } + calibration { + speed: 0.4 + acceleration: -2.35 + command: -28.0 + } + calibration { + speed: 0.4 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 0.4 + acceleration: -1.22 + command: -26.0 + } + calibration { + speed: 0.4 + acceleration: -0.64 + command: -25.0 + } + calibration { + speed: 0.4 + acceleration: -0.34 + command: -24.0 + } + calibration { + speed: 0.4 + acceleration: -0.08 + command: -23.0 + } + calibration { + speed: 0.4 + acceleration: 0.11 + command: -22.0 + } + calibration { + speed: 0.4 + acceleration: 0.32 + command: -13.0 + } + calibration { + speed: 0.4 + acceleration: 0.34 + command: -17.5 + } + calibration { + speed: 0.4 + acceleration: 0.38 + command: -17.0 + } + calibration { + speed: 0.4 + acceleration: 0.91 + command: 20.0 + } + calibration { + speed: 0.4 + acceleration: 1.05 + command: 22.0 + } + calibration { + speed: 0.4 + acceleration: 1.51 + command: 25.0 + } + calibration { + speed: 0.4 + acceleration: 1.67 + command: 27.0 + } + calibration { + speed: 0.4 + acceleration: 1.75 + command: 30.0 + } + calibration { + speed: 0.4 + acceleration: 1.86 + command: 35.0 + } + calibration { + speed: 0.4 + acceleration: 2.0 + command: 40.0 + } + calibration { + speed: 0.4 + acceleration: 2.08 + command: 45.0 + } + calibration { + speed: 0.4 + acceleration: 2.28 + command: 50.0 + } + calibration { + speed: 0.4 + acceleration: 2.35 + command: 55.0 + } + calibration { + speed: 0.6 + acceleration: -7.72 + command: -35.0 + } + calibration { + speed: 0.6 + acceleration: -5.35 + command: -33.0 + } + calibration { + speed: 0.6 + acceleration: -4.89 + command: -32.0 + } + calibration { + speed: 0.6 + acceleration: -4.29 + command: -31.0 + } + calibration { + speed: 0.6 + acceleration: -3.54 + command: -30.0 + } + calibration { + speed: 0.6 + acceleration: -3.05 + command: -29.0 + } + calibration { + speed: 0.6 + acceleration: -2.4 + command: -28.0 + } + calibration { + speed: 0.6 + acceleration: -1.83 + command: -27.0 + } + calibration { + speed: 0.6 + acceleration: -1.26 + command: -26.0 + } + calibration { + speed: 0.6 + acceleration: -0.66 + command: -25.0 + } + calibration { + speed: 0.6 + acceleration: -0.39 + command: -24.0 + } + calibration { + speed: 0.6 + acceleration: -0.13 + command: -23.0 + } + calibration { + speed: 0.6 + acceleration: 0.08 + command: -22.0 + } + calibration { + speed: 0.6 + acceleration: 0.27 + command: -13.0 + } + calibration { + speed: 0.6 + acceleration: 0.32 + command: -15.0 + } + calibration { + speed: 0.6 + acceleration: 0.33 + command: -17.0 + } + calibration { + speed: 0.6 + acceleration: 0.34 + command: -20.0 + } + calibration { + speed: 0.6 + acceleration: 0.96 + command: 20.0 + } + calibration { + speed: 0.6 + acceleration: 1.14 + command: 22.0 + } + calibration { + speed: 0.6 + acceleration: 1.65 + command: 25.0 + } + calibration { + speed: 0.6 + acceleration: 1.85 + command: 27.0 + } + calibration { + speed: 0.6 + acceleration: 1.94 + command: 30.0 + } + calibration { + speed: 0.6 + acceleration: 2.08 + command: 35.0 + } + calibration { + speed: 0.6 + acceleration: 2.21 + command: 40.0 + } + calibration { + speed: 0.6 + acceleration: 2.3 + command: 45.0 + } + calibration { + speed: 0.6 + acceleration: 2.48 + command: 50.0 + } + calibration { + speed: 0.6 + acceleration: 2.57 + command: 55.0 + } + calibration { + speed: 0.8 + acceleration: -8.33 + command: -35.0 + } + calibration { + speed: 0.8 + acceleration: -5.59 + command: -33.0 + } + calibration { + speed: 0.8 + acceleration: -5.03 + command: -32.0 + } + calibration { + speed: 0.8 + acceleration: -4.33 + command: -31.0 + } + calibration { + speed: 0.8 + acceleration: -3.53 + command: -30.0 + } + calibration { + speed: 0.8 + acceleration: -2.98 + command: -29.0 + } + calibration { + speed: 0.8 + acceleration: -2.35 + command: -28.0 + } + calibration { + speed: 0.8 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 0.8 + acceleration: -1.25 + command: -26.0 + } + calibration { + speed: 0.8 + acceleration: -0.68 + command: -25.0 + } + calibration { + speed: 0.8 + acceleration: -0.43 + command: -24.0 + } + calibration { + speed: 0.8 + acceleration: -0.09 + command: -23.0 + } + calibration { + speed: 0.8 + acceleration: 0.03 + command: -22.0 + } + calibration { + speed: 0.8 + acceleration: 0.22 + command: -13.0 + } + calibration { + speed: 0.8 + acceleration: 0.25 + command: -20.0 + } + calibration { + speed: 0.8 + acceleration: 0.29 + command: -15.0 + } + calibration { + speed: 0.8 + acceleration: 0.31 + command: -17.0 + } + calibration { + speed: 0.8 + acceleration: 0.98 + command: 20.0 + } + calibration { + speed: 0.8 + acceleration: 1.18 + command: 22.0 + } + calibration { + speed: 0.8 + acceleration: 1.77 + command: 25.0 + } + calibration { + speed: 0.8 + acceleration: 2.04 + command: 27.0 + } + calibration { + speed: 0.8 + acceleration: 2.13 + command: 30.0 + } + calibration { + speed: 0.8 + acceleration: 2.26 + command: 35.0 + } + calibration { + speed: 0.8 + acceleration: 2.41 + command: 40.0 + } + calibration { + speed: 0.8 + acceleration: 2.48 + command: 45.0 + } + calibration { + speed: 0.8 + acceleration: 2.62 + command: 50.0 + } + calibration { + speed: 0.8 + acceleration: 2.67 + command: 55.0 + } + calibration { + speed: 1.0 + acceleration: -8.54 + command: -35.0 + } + calibration { + speed: 1.0 + acceleration: -5.49 + command: -33.0 + } + calibration { + speed: 1.0 + acceleration: -4.92 + command: -32.0 + } + calibration { + speed: 1.0 + acceleration: -4.17 + command: -31.0 + } + calibration { + speed: 1.0 + acceleration: -3.43 + command: -30.0 + } + calibration { + speed: 1.0 + acceleration: -2.9 + command: -29.0 + } + calibration { + speed: 1.0 + acceleration: -2.33 + command: -28.0 + } + calibration { + speed: 1.0 + acceleration: -1.82 + command: -27.0 + } + calibration { + speed: 1.0 + acceleration: -1.25 + command: -26.0 + } + calibration { + speed: 1.0 + acceleration: -0.71 + command: -25.0 + } + calibration { + speed: 1.0 + acceleration: -0.44 + command: -24.0 + } + calibration { + speed: 1.0 + acceleration: -0.12 + command: -23.0 + } + calibration { + speed: 1.0 + acceleration: 0.17 + command: -13.0 + } + calibration { + speed: 1.0 + acceleration: 0.21 + command: -20.0 + } + calibration { + speed: 1.0 + acceleration: 0.25 + command: -16.0 + } + calibration { + speed: 1.0 + acceleration: 0.99 + command: 20.0 + } + calibration { + speed: 1.0 + acceleration: 1.22 + command: 22.0 + } + calibration { + speed: 1.0 + acceleration: 1.86 + command: 25.0 + } + calibration { + speed: 1.0 + acceleration: 2.21 + command: 27.0 + } + calibration { + speed: 1.0 + acceleration: 2.27 + command: 30.0 + } + calibration { + speed: 1.0 + acceleration: 2.45 + command: 35.0 + } + calibration { + speed: 1.0 + acceleration: 2.6 + command: 40.0 + } + calibration { + speed: 1.0 + acceleration: 2.64 + command: 45.0 + } + calibration { + speed: 1.0 + acceleration: 2.74 + command: 50.0 + } + calibration { + speed: 1.0 + acceleration: 2.75 + command: 55.0 + } + calibration { + speed: 1.2 + acceleration: -8.52 + command: -35.0 + } + calibration { + speed: 1.2 + acceleration: -5.31 + command: -33.0 + } + calibration { + speed: 1.2 + acceleration: -4.7 + command: -32.0 + } + calibration { + speed: 1.2 + acceleration: -4.01 + command: -31.0 + } + calibration { + speed: 1.2 + acceleration: -3.38 + command: -30.0 + } + calibration { + speed: 1.2 + acceleration: -2.87 + command: -29.0 + } + calibration { + speed: 1.2 + acceleration: -2.32 + command: -28.0 + } + calibration { + speed: 1.2 + acceleration: -1.82 + command: -27.0 + } + calibration { + speed: 1.2 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 1.2 + acceleration: -0.71 + command: -25.0 + } + calibration { + speed: 1.2 + acceleration: -0.45 + command: -24.0 + } + calibration { + speed: 1.2 + acceleration: -0.17 + command: -23.0 + } + calibration { + speed: 1.2 + acceleration: 0.13 + command: -20.0 + } + calibration { + speed: 1.2 + acceleration: 0.14 + command: -13.0 + } + calibration { + speed: 1.2 + acceleration: 0.17 + command: -15.0 + } + calibration { + speed: 1.2 + acceleration: 0.18 + command: -17.0 + } + calibration { + speed: 1.2 + acceleration: 0.98 + command: 20.0 + } + calibration { + speed: 1.2 + acceleration: 1.25 + command: 22.0 + } + calibration { + speed: 1.2 + acceleration: 1.92 + command: 25.0 + } + calibration { + speed: 1.2 + acceleration: 2.29 + command: 27.0 + } + calibration { + speed: 1.2 + acceleration: 2.39 + command: 30.0 + } + calibration { + speed: 1.2 + acceleration: 2.62 + command: 35.0 + } + calibration { + speed: 1.2 + acceleration: 2.76 + command: 40.0 + } + calibration { + speed: 1.2 + acceleration: 2.79 + command: 45.0 + } + calibration { + speed: 1.2 + acceleration: 2.84 + command: 52.5 + } + calibration { + speed: 1.4 + acceleration: -8.35 + command: -35.0 + } + calibration { + speed: 1.4 + acceleration: -5.14 + command: -33.0 + } + calibration { + speed: 1.4 + acceleration: -4.55 + command: -32.0 + } + calibration { + speed: 1.4 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 1.4 + acceleration: -3.37 + command: -30.0 + } + calibration { + speed: 1.4 + acceleration: -2.88 + command: -29.0 + } + calibration { + speed: 1.4 + acceleration: -2.29 + command: -28.0 + } + calibration { + speed: 1.4 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 1.4 + acceleration: -1.23 + command: -26.0 + } + calibration { + speed: 1.4 + acceleration: -0.69 + command: -25.0 + } + calibration { + speed: 1.4 + acceleration: -0.48 + command: -24.0 + } + calibration { + speed: 1.4 + acceleration: -0.23 + command: -23.0 + } + calibration { + speed: 1.4 + acceleration: 0.08 + command: -13.0 + } + calibration { + speed: 1.4 + acceleration: 0.11 + command: -17.0 + } + calibration { + speed: 1.4 + acceleration: 0.12 + command: -17.5 + } + calibration { + speed: 1.4 + acceleration: 0.96 + command: 20.0 + } + calibration { + speed: 1.4 + acceleration: 1.24 + command: 22.0 + } + calibration { + speed: 1.4 + acceleration: 1.96 + command: 25.0 + } + calibration { + speed: 1.4 + acceleration: 2.37 + command: 27.0 + } + calibration { + speed: 1.4 + acceleration: 2.48 + command: 30.0 + } + calibration { + speed: 1.4 + acceleration: 2.75 + command: 35.0 + } + calibration { + speed: 1.4 + acceleration: 2.9 + command: 40.0 + } + calibration { + speed: 1.4 + acceleration: 2.93 + command: 45.0 + } + calibration { + speed: 1.4 + acceleration: 2.95 + command: 55.0 + } + calibration { + speed: 1.4 + acceleration: 2.96 + command: 50.0 + } + calibration { + speed: 1.6 + acceleration: -8.12 + command: -35.0 + } + calibration { + speed: 1.6 + acceleration: -5.03 + command: -33.0 + } + calibration { + speed: 1.6 + acceleration: -4.47 + command: -32.0 + } + calibration { + speed: 1.6 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 1.6 + acceleration: -3.37 + command: -30.0 + } + calibration { + speed: 1.6 + acceleration: -2.88 + command: -29.0 + } + calibration { + speed: 1.6 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 1.6 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 1.6 + acceleration: -1.19 + command: -26.0 + } + calibration { + speed: 1.6 + acceleration: -0.68 + command: -25.0 + } + calibration { + speed: 1.6 + acceleration: -0.55 + command: -24.0 + } + calibration { + speed: 1.6 + acceleration: -0.26 + command: -23.0 + } + calibration { + speed: 1.6 + acceleration: -0.13 + command: -22.0 + } + calibration { + speed: 1.6 + acceleration: 0.0 + command: -20.0 + } + calibration { + speed: 1.6 + acceleration: 0.02 + command: -15.0 + } + calibration { + speed: 1.6 + acceleration: 0.04 + command: -13.0 + } + calibration { + speed: 1.6 + acceleration: 0.07 + command: -17.0 + } + calibration { + speed: 1.6 + acceleration: 0.93 + command: 20.0 + } + calibration { + speed: 1.6 + acceleration: 1.22 + command: 22.0 + } + calibration { + speed: 1.6 + acceleration: 2.0 + command: 25.0 + } + calibration { + speed: 1.6 + acceleration: 2.42 + command: 27.0 + } + calibration { + speed: 1.6 + acceleration: 2.56 + command: 30.0 + } + calibration { + speed: 1.6 + acceleration: 2.81 + command: 35.0 + } + calibration { + speed: 1.6 + acceleration: 3.01 + command: 40.0 + } + calibration { + speed: 1.6 + acceleration: 3.03 + command: 45.0 + } + calibration { + speed: 1.6 + acceleration: 3.06 + command: 55.0 + } + calibration { + speed: 1.6 + acceleration: 3.07 + command: 50.0 + } + calibration { + speed: 1.8 + acceleration: -7.96 + command: -35.0 + } + calibration { + speed: 1.8 + acceleration: -4.99 + command: -33.0 + } + calibration { + speed: 1.8 + acceleration: -4.48 + command: -32.0 + } + calibration { + speed: 1.8 + acceleration: -3.96 + command: -31.0 + } + calibration { + speed: 1.8 + acceleration: -3.36 + command: -30.0 + } + calibration { + speed: 1.8 + acceleration: -2.85 + command: -29.0 + } + calibration { + speed: 1.8 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 1.8 + acceleration: -1.75 + command: -27.0 + } + calibration { + speed: 1.8 + acceleration: -1.19 + command: -26.0 + } + calibration { + speed: 1.8 + acceleration: -0.74 + command: -25.0 + } + calibration { + speed: 1.8 + acceleration: -0.55 + command: -24.0 + } + calibration { + speed: 1.8 + acceleration: -0.28 + command: -23.0 + } + calibration { + speed: 1.8 + acceleration: -0.17 + command: -22.0 + } + calibration { + speed: 1.8 + acceleration: -0.03 + command: -17.0 + } + calibration { + speed: 1.8 + acceleration: -0.01 + command: -17.5 + } + calibration { + speed: 1.8 + acceleration: 0.0 + command: -13.0 + } + calibration { + speed: 1.8 + acceleration: 0.88 + command: 20.0 + } + calibration { + speed: 1.8 + acceleration: 1.19 + command: 22.0 + } + calibration { + speed: 1.8 + acceleration: 2.01 + command: 25.0 + } + calibration { + speed: 1.8 + acceleration: 2.46 + command: 27.0 + } + calibration { + speed: 1.8 + acceleration: 2.62 + command: 30.0 + } + calibration { + speed: 1.8 + acceleration: 2.87 + command: 35.0 + } + calibration { + speed: 1.8 + acceleration: 3.09 + command: 40.0 + } + calibration { + speed: 1.8 + acceleration: 3.12 + command: 45.0 + } + calibration { + speed: 1.8 + acceleration: 3.16 + command: 50.0 + } + calibration { + speed: 1.8 + acceleration: 3.17 + command: 55.0 + } + calibration { + speed: 2.0 + acceleration: -7.78 + command: -35.0 + } + calibration { + speed: 2.0 + acceleration: -5.03 + command: -33.0 + } + calibration { + speed: 2.0 + acceleration: -4.53 + command: -32.0 + } + calibration { + speed: 2.0 + acceleration: -4.0 + command: -31.0 + } + calibration { + speed: 2.0 + acceleration: -3.34 + command: -30.0 + } + calibration { + speed: 2.0 + acceleration: -2.81 + command: -29.0 + } + calibration { + speed: 2.0 + acceleration: -2.28 + command: -28.0 + } + calibration { + speed: 2.0 + acceleration: -1.69 + command: -27.0 + } + calibration { + speed: 2.0 + acceleration: -1.14 + command: -26.0 + } + calibration { + speed: 2.0 + acceleration: -0.79 + command: -25.0 + } + calibration { + speed: 2.0 + acceleration: -0.53 + command: -24.0 + } + calibration { + speed: 2.0 + acceleration: -0.3 + command: -23.0 + } + calibration { + speed: 2.0 + acceleration: -0.2 + command: -22.0 + } + calibration { + speed: 2.0 + acceleration: -0.1 + command: -17.0 + } + calibration { + speed: 2.0 + acceleration: -0.09 + command: -20.0 + } + calibration { + speed: 2.0 + acceleration: -0.08 + command: -15.0 + } + calibration { + speed: 2.0 + acceleration: -0.07 + command: -13.0 + } + calibration { + speed: 2.0 + acceleration: 0.8 + command: 20.0 + } + calibration { + speed: 2.0 + acceleration: 1.13 + command: 22.0 + } + calibration { + speed: 2.0 + acceleration: 2.0 + command: 25.0 + } + calibration { + speed: 2.0 + acceleration: 2.46 + command: 27.0 + } + calibration { + speed: 2.0 + acceleration: 2.66 + command: 30.0 + } + calibration { + speed: 2.0 + acceleration: 2.93 + command: 35.0 + } + calibration { + speed: 2.0 + acceleration: 3.16 + command: 40.0 + } + calibration { + speed: 2.0 + acceleration: 3.18 + command: 45.0 + } + calibration { + speed: 2.0 + acceleration: 3.23 + command: 50.0 + } + calibration { + speed: 2.0 + acceleration: 3.25 + command: 55.0 + } + calibration { + speed: 2.2 + acceleration: -7.7 + command: -35.0 + } + calibration { + speed: 2.2 + acceleration: -5.11 + command: -33.0 + } + calibration { + speed: 2.2 + acceleration: -4.61 + command: -32.0 + } + calibration { + speed: 2.2 + acceleration: -4.03 + command: -31.0 + } + calibration { + speed: 2.2 + acceleration: -3.32 + command: -30.0 + } + calibration { + speed: 2.2 + acceleration: -2.79 + command: -29.0 + } + calibration { + speed: 2.2 + acceleration: -2.29 + command: -28.0 + } + calibration { + speed: 2.2 + acceleration: -1.68 + command: -27.0 + } + calibration { + speed: 2.2 + acceleration: -1.11 + command: -26.0 + } + calibration { + speed: 2.2 + acceleration: -0.81 + command: -25.0 + } + calibration { + speed: 2.2 + acceleration: -0.52 + command: -24.0 + } + calibration { + speed: 2.2 + acceleration: -0.31 + command: -23.0 + } + calibration { + speed: 2.2 + acceleration: -0.23 + command: -22.0 + } + calibration { + speed: 2.2 + acceleration: -0.15 + command: -15.0 + } + calibration { + speed: 2.2 + acceleration: -0.13 + command: -16.6666666667 + } + calibration { + speed: 2.2 + acceleration: 0.71 + command: 20.0 + } + calibration { + speed: 2.2 + acceleration: 1.05 + command: 22.0 + } + calibration { + speed: 2.2 + acceleration: 1.94 + command: 25.0 + } + calibration { + speed: 2.2 + acceleration: 2.44 + command: 27.0 + } + calibration { + speed: 2.2 + acceleration: 2.68 + command: 30.0 + } + calibration { + speed: 2.2 + acceleration: 2.98 + command: 35.0 + } + calibration { + speed: 2.2 + acceleration: 3.22 + command: 40.0 + } + calibration { + speed: 2.2 + acceleration: 3.23 + command: 45.0 + } + calibration { + speed: 2.2 + acceleration: 3.27 + command: 50.0 + } + calibration { + speed: 2.2 + acceleration: 3.29 + command: 55.0 + } + calibration { + speed: 2.4 + acceleration: -7.66 + command: -35.0 + } + calibration { + speed: 2.4 + acceleration: -5.18 + command: -33.0 + } + calibration { + speed: 2.4 + acceleration: -4.65 + command: -32.0 + } + calibration { + speed: 2.4 + acceleration: -4.02 + command: -31.0 + } + calibration { + speed: 2.4 + acceleration: -3.31 + command: -30.0 + } + calibration { + speed: 2.4 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 2.4 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 2.4 + acceleration: -1.69 + command: -27.0 + } + calibration { + speed: 2.4 + acceleration: -1.21 + command: -26.0 + } + calibration { + speed: 2.4 + acceleration: -0.78 + command: -25.0 + } + calibration { + speed: 2.4 + acceleration: -0.52 + command: -24.0 + } + calibration { + speed: 2.4 + acceleration: -0.31 + command: -23.0 + } + calibration { + speed: 2.4 + acceleration: -0.23 + command: -22.0 + } + calibration { + speed: 2.4 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 2.4 + acceleration: -0.15 + command: -16.0 + } + calibration { + speed: 2.4 + acceleration: -0.14 + command: -20.0 + } + calibration { + speed: 2.4 + acceleration: 0.62 + command: 20.0 + } + calibration { + speed: 2.4 + acceleration: 0.95 + command: 22.0 + } + calibration { + speed: 2.4 + acceleration: 1.84 + command: 25.0 + } + calibration { + speed: 2.4 + acceleration: 2.38 + command: 27.0 + } + calibration { + speed: 2.4 + acceleration: 2.69 + command: 30.0 + } + calibration { + speed: 2.4 + acceleration: 3.02 + command: 35.0 + } + calibration { + speed: 2.4 + acceleration: 3.25 + command: 40.0 + } + calibration { + speed: 2.4 + acceleration: 3.27 + command: 45.0 + } + calibration { + speed: 2.4 + acceleration: 3.3 + command: 50.0 + } + calibration { + speed: 2.4 + acceleration: 3.31 + command: 55.0 + } + calibration { + speed: 2.6 + acceleration: -7.65 + command: -35.0 + } + calibration { + speed: 2.6 + acceleration: -5.23 + command: -33.0 + } + calibration { + speed: 2.6 + acceleration: -4.66 + command: -32.0 + } + calibration { + speed: 2.6 + acceleration: -4.0 + command: -31.0 + } + calibration { + speed: 2.6 + acceleration: -3.31 + command: -30.0 + } + calibration { + speed: 2.6 + acceleration: -2.81 + command: -29.0 + } + calibration { + speed: 2.6 + acceleration: -2.2 + command: -28.0 + } + calibration { + speed: 2.6 + acceleration: -1.66 + command: -27.0 + } + calibration { + speed: 2.6 + acceleration: -1.25 + command: -26.0 + } + calibration { + speed: 2.6 + acceleration: -0.8 + command: -25.0 + } + calibration { + speed: 2.6 + acceleration: -0.51 + command: -24.0 + } + calibration { + speed: 2.6 + acceleration: -0.31 + command: -23.0 + } + calibration { + speed: 2.6 + acceleration: -0.22 + command: -22.0 + } + calibration { + speed: 2.6 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 2.6 + acceleration: -0.15 + command: -18.5 + } + calibration { + speed: 2.6 + acceleration: -0.14 + command: -15.0 + } + calibration { + speed: 2.6 + acceleration: 0.51 + command: 20.0 + } + calibration { + speed: 2.6 + acceleration: 0.84 + command: 22.0 + } + calibration { + speed: 2.6 + acceleration: 1.73 + command: 25.0 + } + calibration { + speed: 2.6 + acceleration: 2.32 + command: 27.0 + } + calibration { + speed: 2.6 + acceleration: 2.69 + command: 30.0 + } + calibration { + speed: 2.6 + acceleration: 3.06 + command: 35.0 + } + calibration { + speed: 2.6 + acceleration: 3.27 + command: 40.0 + } + calibration { + speed: 2.6 + acceleration: 3.3 + command: 45.0 + } + calibration { + speed: 2.6 + acceleration: 3.31 + command: 55.0 + } + calibration { + speed: 2.6 + acceleration: 3.32 + command: 50.0 + } + calibration { + speed: 2.8 + acceleration: -7.68 + command: -35.0 + } + calibration { + speed: 2.8 + acceleration: -5.25 + command: -33.0 + } + calibration { + speed: 2.8 + acceleration: -4.63 + command: -32.0 + } + calibration { + speed: 2.8 + acceleration: -4.0 + command: -31.0 + } + calibration { + speed: 2.8 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 2.8 + acceleration: -2.85 + command: -29.0 + } + calibration { + speed: 2.8 + acceleration: -2.14 + command: -28.0 + } + calibration { + speed: 2.8 + acceleration: -1.66 + command: -27.0 + } + calibration { + speed: 2.8 + acceleration: -1.23 + command: -26.0 + } + calibration { + speed: 2.8 + acceleration: -0.8 + command: -25.0 + } + calibration { + speed: 2.8 + acceleration: -0.53 + command: -24.0 + } + calibration { + speed: 2.8 + acceleration: -0.31 + command: -23.0 + } + calibration { + speed: 2.8 + acceleration: -0.23 + command: -22.0 + } + calibration { + speed: 2.8 + acceleration: -0.15 + command: -17.0 + } + calibration { + speed: 2.8 + acceleration: -0.14 + command: -17.5 + } + calibration { + speed: 2.8 + acceleration: -0.12 + command: -13.0 + } + calibration { + speed: 2.8 + acceleration: 0.46 + command: 20.0 + } + calibration { + speed: 2.8 + acceleration: 0.76 + command: 22.0 + } + calibration { + speed: 2.8 + acceleration: 1.65 + command: 25.0 + } + calibration { + speed: 2.8 + acceleration: 2.26 + command: 27.0 + } + calibration { + speed: 2.8 + acceleration: 2.7 + command: 30.0 + } + calibration { + speed: 2.8 + acceleration: 3.09 + command: 35.0 + } + calibration { + speed: 2.8 + acceleration: 3.29 + command: 40.0 + } + calibration { + speed: 2.8 + acceleration: 3.31 + command: 50.0 + } + calibration { + speed: 2.8 + acceleration: 3.33 + command: 50.0 + } + calibration { + speed: 3.0 + acceleration: -7.71 + command: -35.0 + } + calibration { + speed: 3.0 + acceleration: -5.23 + command: -33.0 + } + calibration { + speed: 3.0 + acceleration: -4.6 + command: -32.0 + } + calibration { + speed: 3.0 + acceleration: -4.02 + command: -31.0 + } + calibration { + speed: 3.0 + acceleration: -3.35 + command: -30.0 + } + calibration { + speed: 3.0 + acceleration: -2.88 + command: -29.0 + } + calibration { + speed: 3.0 + acceleration: -2.14 + command: -28.0 + } + calibration { + speed: 3.0 + acceleration: -1.73 + command: -27.0 + } + calibration { + speed: 3.0 + acceleration: -1.23 + command: -26.0 + } + calibration { + speed: 3.0 + acceleration: -0.81 + command: -25.0 + } + calibration { + speed: 3.0 + acceleration: -0.53 + command: -24.0 + } + calibration { + speed: 3.0 + acceleration: -0.32 + command: -23.0 + } + calibration { + speed: 3.0 + acceleration: -0.23 + command: -22.0 + } + calibration { + speed: 3.0 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 3.0 + acceleration: -0.15 + command: -15.0 + } + calibration { + speed: 3.0 + acceleration: -0.14 + command: -18.5 + } + calibration { + speed: 3.0 + acceleration: 0.42 + command: 20.0 + } + calibration { + speed: 3.0 + acceleration: 0.7 + command: 22.0 + } + calibration { + speed: 3.0 + acceleration: 1.57 + command: 25.0 + } + calibration { + speed: 3.0 + acceleration: 2.2 + command: 27.0 + } + calibration { + speed: 3.0 + acceleration: 2.71 + command: 30.0 + } + calibration { + speed: 3.0 + acceleration: 3.12 + command: 35.0 + } + calibration { + speed: 3.0 + acceleration: 3.3 + command: 55.0 + } + calibration { + speed: 3.0 + acceleration: 3.31 + command: 42.5 + } + calibration { + speed: 3.0 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 3.2 + acceleration: -7.75 + command: -35.0 + } + calibration { + speed: 3.2 + acceleration: -5.2 + command: -33.0 + } + calibration { + speed: 3.2 + acceleration: -4.57 + command: -32.0 + } + calibration { + speed: 3.2 + acceleration: -4.04 + command: -31.0 + } + calibration { + speed: 3.2 + acceleration: -3.37 + command: -30.0 + } + calibration { + speed: 3.2 + acceleration: -2.86 + command: -29.0 + } + calibration { + speed: 3.2 + acceleration: -2.18 + command: -28.0 + } + calibration { + speed: 3.2 + acceleration: -1.78 + command: -27.0 + } + calibration { + speed: 3.2 + acceleration: -1.23 + command: -26.0 + } + calibration { + speed: 3.2 + acceleration: -0.8 + command: -25.0 + } + calibration { + speed: 3.2 + acceleration: -0.52 + command: -24.0 + } + calibration { + speed: 3.2 + acceleration: -0.29 + command: -23.0 + } + calibration { + speed: 3.2 + acceleration: -0.21 + command: -22.0 + } + calibration { + speed: 3.2 + acceleration: -0.17 + command: -13.0 + } + calibration { + speed: 3.2 + acceleration: -0.16 + command: -15.0 + } + calibration { + speed: 3.2 + acceleration: -0.15 + command: -17.0 + } + calibration { + speed: 3.2 + acceleration: -0.13 + command: -20.0 + } + calibration { + speed: 3.2 + acceleration: 0.37 + command: 20.0 + } + calibration { + speed: 3.2 + acceleration: 0.63 + command: 22.0 + } + calibration { + speed: 3.2 + acceleration: 1.5 + command: 25.0 + } + calibration { + speed: 3.2 + acceleration: 2.13 + command: 27.0 + } + calibration { + speed: 3.2 + acceleration: 2.7 + command: 30.0 + } + calibration { + speed: 3.2 + acceleration: 3.13 + command: 35.0 + } + calibration { + speed: 3.2 + acceleration: 3.3 + command: 55.0 + } + calibration { + speed: 3.2 + acceleration: 3.31 + command: 45.0 + } + calibration { + speed: 3.2 + acceleration: 3.33 + command: 40.0 + } + calibration { + speed: 3.2 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 3.4 + acceleration: -7.78 + command: -35.0 + } + calibration { + speed: 3.4 + acceleration: -5.15 + command: -33.0 + } + calibration { + speed: 3.4 + acceleration: -4.55 + command: -32.0 + } + calibration { + speed: 3.4 + acceleration: -4.06 + command: -31.0 + } + calibration { + speed: 3.4 + acceleration: -3.38 + command: -30.0 + } + calibration { + speed: 3.4 + acceleration: -2.81 + command: -29.0 + } + calibration { + speed: 3.4 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 3.4 + acceleration: -1.79 + command: -27.0 + } + calibration { + speed: 3.4 + acceleration: -1.24 + command: -26.0 + } + calibration { + speed: 3.4 + acceleration: -0.81 + command: -25.0 + } + calibration { + speed: 3.4 + acceleration: -0.52 + command: -24.0 + } + calibration { + speed: 3.4 + acceleration: -0.32 + command: -23.0 + } + calibration { + speed: 3.4 + acceleration: -0.22 + command: -22.0 + } + calibration { + speed: 3.4 + acceleration: -0.16 + command: -20.0 + } + calibration { + speed: 3.4 + acceleration: -0.15 + command: -15.0 + } + calibration { + speed: 3.4 + acceleration: 0.34 + command: 20.0 + } + calibration { + speed: 3.4 + acceleration: 0.57 + command: 22.0 + } + calibration { + speed: 3.4 + acceleration: 1.42 + command: 25.0 + } + calibration { + speed: 3.4 + acceleration: 2.03 + command: 27.0 + } + calibration { + speed: 3.4 + acceleration: 2.67 + command: 30.0 + } + calibration { + speed: 3.4 + acceleration: 3.14 + command: 35.0 + } + calibration { + speed: 3.4 + acceleration: 3.29 + command: 50.0 + } + calibration { + speed: 3.4 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 3.4 + acceleration: 3.36 + command: 40.0 + } + calibration { + speed: 3.6 + acceleration: -7.78 + command: -35.0 + } + calibration { + speed: 3.6 + acceleration: -5.11 + command: -33.0 + } + calibration { + speed: 3.6 + acceleration: -4.54 + command: -32.0 + } + calibration { + speed: 3.6 + acceleration: -4.08 + command: -31.0 + } + calibration { + speed: 3.6 + acceleration: -3.37 + command: -30.0 + } + calibration { + speed: 3.6 + acceleration: -2.74 + command: -29.0 + } + calibration { + speed: 3.6 + acceleration: -2.23 + command: -28.0 + } + calibration { + speed: 3.6 + acceleration: -1.78 + command: -27.0 + } + calibration { + speed: 3.6 + acceleration: -1.25 + command: -26.0 + } + calibration { + speed: 3.6 + acceleration: -0.82 + command: -25.0 + } + calibration { + speed: 3.6 + acceleration: -0.53 + command: -24.0 + } + calibration { + speed: 3.6 + acceleration: -0.3 + command: -23.0 + } + calibration { + speed: 3.6 + acceleration: -0.23 + command: -22.0 + } + calibration { + speed: 3.6 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 3.6 + acceleration: -0.16 + command: -17.0 + } + calibration { + speed: 3.6 + acceleration: -0.15 + command: -16.5 + } + calibration { + speed: 3.6 + acceleration: 0.31 + command: 20.0 + } + calibration { + speed: 3.6 + acceleration: 0.52 + command: 22.0 + } + calibration { + speed: 3.6 + acceleration: 1.32 + command: 25.0 + } + calibration { + speed: 3.6 + acceleration: 1.92 + command: 27.0 + } + calibration { + speed: 3.6 + acceleration: 2.58 + command: 30.0 + } + calibration { + speed: 3.6 + acceleration: 3.12 + command: 35.0 + } + calibration { + speed: 3.6 + acceleration: 3.28 + command: 45.0 + } + calibration { + speed: 3.6 + acceleration: 3.29 + command: 55.0 + } + calibration { + speed: 3.6 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 3.6 + acceleration: 3.37 + command: 40.0 + } + calibration { + speed: 3.8 + acceleration: -7.77 + command: -35.0 + } + calibration { + speed: 3.8 + acceleration: -5.09 + command: -33.0 + } + calibration { + speed: 3.8 + acceleration: -4.56 + command: -32.0 + } + calibration { + speed: 3.8 + acceleration: -4.06 + command: -31.0 + } + calibration { + speed: 3.8 + acceleration: -3.34 + command: -30.0 + } + calibration { + speed: 3.8 + acceleration: -2.71 + command: -29.0 + } + calibration { + speed: 3.8 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 3.8 + acceleration: -1.78 + command: -27.0 + } + calibration { + speed: 3.8 + acceleration: -1.27 + command: -26.0 + } + calibration { + speed: 3.8 + acceleration: -0.82 + command: -25.0 + } + calibration { + speed: 3.8 + acceleration: -0.54 + command: -24.0 + } + calibration { + speed: 3.8 + acceleration: -0.31 + command: -23.0 + } + calibration { + speed: 3.8 + acceleration: -0.26 + command: -22.0 + } + calibration { + speed: 3.8 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 3.8 + acceleration: -0.15 + command: -17.5 + } + calibration { + speed: 3.8 + acceleration: 0.28 + command: 20.0 + } + calibration { + speed: 3.8 + acceleration: 0.5 + command: 22.0 + } + calibration { + speed: 3.8 + acceleration: 1.23 + command: 25.0 + } + calibration { + speed: 3.8 + acceleration: 1.83 + command: 27.0 + } + calibration { + speed: 3.8 + acceleration: 2.47 + command: 30.0 + } + calibration { + speed: 3.8 + acceleration: 3.09 + command: 35.0 + } + calibration { + speed: 3.8 + acceleration: 3.28 + command: 45.0 + } + calibration { + speed: 3.8 + acceleration: 3.29 + command: 55.0 + } + calibration { + speed: 3.8 + acceleration: 3.34 + command: 50.0 + } + calibration { + speed: 3.8 + acceleration: 3.37 + command: 40.0 + } + calibration { + speed: 4.0 + acceleration: -7.75 + command: -35.0 + } + calibration { + speed: 4.0 + acceleration: -5.08 + command: -33.0 + } + calibration { + speed: 4.0 + acceleration: -4.59 + command: -32.0 + } + calibration { + speed: 4.0 + acceleration: -4.01 + command: -31.0 + } + calibration { + speed: 4.0 + acceleration: -3.31 + command: -30.0 + } + calibration { + speed: 4.0 + acceleration: -2.72 + command: -29.0 + } + calibration { + speed: 4.0 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 4.0 + acceleration: -1.79 + command: -27.0 + } + calibration { + speed: 4.0 + acceleration: -1.25 + command: -26.0 + } + calibration { + speed: 4.0 + acceleration: -0.85 + command: -25.0 + } + calibration { + speed: 4.0 + acceleration: -0.54 + command: -24.0 + } + calibration { + speed: 4.0 + acceleration: -0.31 + command: -23.0 + } + calibration { + speed: 4.0 + acceleration: -0.24 + command: -22.0 + } + calibration { + speed: 4.0 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 4.0 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 4.0 + acceleration: -0.15 + command: -20.0 + } + calibration { + speed: 4.0 + acceleration: -0.13 + command: -13.0 + } + calibration { + speed: 4.0 + acceleration: 0.22 + command: 20.0 + } + calibration { + speed: 4.0 + acceleration: 0.46 + command: 22.0 + } + calibration { + speed: 4.0 + acceleration: 1.16 + command: 25.0 + } + calibration { + speed: 4.0 + acceleration: 1.73 + command: 27.0 + } + calibration { + speed: 4.0 + acceleration: 2.35 + command: 30.0 + } + calibration { + speed: 4.0 + acceleration: 3.04 + command: 35.0 + } + calibration { + speed: 4.0 + acceleration: 3.29 + command: 55.0 + } + calibration { + speed: 4.0 + acceleration: 3.3 + command: 45.0 + } + calibration { + speed: 4.0 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 4.0 + acceleration: 3.36 + command: 40.0 + } + calibration { + speed: 4.2 + acceleration: -7.7 + command: -35.0 + } + calibration { + speed: 4.2 + acceleration: -5.09 + command: -33.0 + } + calibration { + speed: 4.2 + acceleration: -4.63 + command: -32.0 + } + calibration { + speed: 4.2 + acceleration: -3.98 + command: -31.0 + } + calibration { + speed: 4.2 + acceleration: -3.29 + command: -30.0 + } + calibration { + speed: 4.2 + acceleration: -2.75 + command: -29.0 + } + calibration { + speed: 4.2 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 4.2 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 4.2 + acceleration: -1.26 + command: -26.0 + } + calibration { + speed: 4.2 + acceleration: -0.81 + command: -25.0 + } + calibration { + speed: 4.2 + acceleration: -0.55 + command: -24.0 + } + calibration { + speed: 4.2 + acceleration: -0.33 + command: -23.0 + } + calibration { + speed: 4.2 + acceleration: -0.21 + command: -22.0 + } + calibration { + speed: 4.2 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 4.2 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 4.2 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 4.2 + acceleration: -0.15 + command: -20.0 + } + calibration { + speed: 4.2 + acceleration: 0.21 + command: 20.0 + } + calibration { + speed: 4.2 + acceleration: 0.42 + command: 22.0 + } + calibration { + speed: 4.2 + acceleration: 1.06 + command: 25.0 + } + calibration { + speed: 4.2 + acceleration: 1.62 + command: 27.0 + } + calibration { + speed: 4.2 + acceleration: 2.23 + command: 30.0 + } + calibration { + speed: 4.2 + acceleration: 2.97 + command: 35.0 + } + calibration { + speed: 4.2 + acceleration: 3.32 + command: 47.5 + } + calibration { + speed: 4.2 + acceleration: 3.34 + command: 45.0 + } + calibration { + speed: 4.2 + acceleration: 3.36 + command: 50.0 + } + calibration { + speed: 4.4 + acceleration: -7.65 + command: -35.0 + } + calibration { + speed: 4.4 + acceleration: -5.12 + command: -33.0 + } + calibration { + speed: 4.4 + acceleration: -4.65 + command: -32.0 + } + calibration { + speed: 4.4 + acceleration: -3.94 + command: -31.0 + } + calibration { + speed: 4.4 + acceleration: -3.29 + command: -30.0 + } + calibration { + speed: 4.4 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 4.4 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 4.4 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 4.4 + acceleration: -1.29 + command: -26.0 + } + calibration { + speed: 4.4 + acceleration: -0.84 + command: -25.0 + } + calibration { + speed: 4.4 + acceleration: -0.53 + command: -24.0 + } + calibration { + speed: 4.4 + acceleration: -0.32 + command: -23.0 + } + calibration { + speed: 4.4 + acceleration: -0.23 + command: -22.0 + } + calibration { + speed: 4.4 + acceleration: -0.19 + command: -15.0 + } + calibration { + speed: 4.4 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 4.4 + acceleration: -0.16 + command: -20.0 + } + calibration { + speed: 4.4 + acceleration: -0.14 + command: -13.0 + } + calibration { + speed: 4.4 + acceleration: 0.19 + command: 20.0 + } + calibration { + speed: 4.4 + acceleration: 0.38 + command: 22.0 + } + calibration { + speed: 4.4 + acceleration: 0.98 + command: 25.0 + } + calibration { + speed: 4.4 + acceleration: 1.5 + command: 27.0 + } + calibration { + speed: 4.4 + acceleration: 2.11 + command: 30.0 + } + calibration { + speed: 4.4 + acceleration: 2.88 + command: 35.0 + } + calibration { + speed: 4.4 + acceleration: 3.29 + command: 40.0 + } + calibration { + speed: 4.4 + acceleration: 3.35 + command: 55.0 + } + calibration { + speed: 4.4 + acceleration: 3.38 + command: 45.0 + } + calibration { + speed: 4.4 + acceleration: 3.39 + command: 50.0 + } + calibration { + speed: 4.6 + acceleration: -7.62 + command: -35.0 + } + calibration { + speed: 4.6 + acceleration: -5.16 + command: -33.0 + } + calibration { + speed: 4.6 + acceleration: -4.65 + command: -32.0 + } + calibration { + speed: 4.6 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 4.6 + acceleration: -3.32 + command: -30.0 + } + calibration { + speed: 4.6 + acceleration: -2.79 + command: -29.0 + } + calibration { + speed: 4.6 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 4.6 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 4.6 + acceleration: -1.29 + command: -26.0 + } + calibration { + speed: 4.6 + acceleration: -0.85 + command: -25.0 + } + calibration { + speed: 4.6 + acceleration: -0.55 + command: -24.0 + } + calibration { + speed: 4.6 + acceleration: -0.33 + command: -23.0 + } + calibration { + speed: 4.6 + acceleration: -0.26 + command: -22.0 + } + calibration { + speed: 4.6 + acceleration: -0.17 + command: -16.0 + } + calibration { + speed: 4.6 + acceleration: -0.16 + command: -17.0 + } + calibration { + speed: 4.6 + acceleration: 0.15 + command: 20.0 + } + calibration { + speed: 4.6 + acceleration: 0.34 + command: 22.0 + } + calibration { + speed: 4.6 + acceleration: 0.88 + command: 25.0 + } + calibration { + speed: 4.6 + acceleration: 1.4 + command: 27.0 + } + calibration { + speed: 4.6 + acceleration: 1.98 + command: 30.0 + } + calibration { + speed: 4.6 + acceleration: 2.82 + command: 35.0 + } + calibration { + speed: 4.6 + acceleration: 3.24 + command: 40.0 + } + calibration { + speed: 4.6 + acceleration: 3.4 + command: 50.0 + } + calibration { + speed: 4.6 + acceleration: 3.42 + command: 50.0 + } + calibration { + speed: 4.8 + acceleration: -7.6 + command: -35.0 + } + calibration { + speed: 4.8 + acceleration: -5.19 + command: -33.0 + } + calibration { + speed: 4.8 + acceleration: -4.64 + command: -32.0 + } + calibration { + speed: 4.8 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 4.8 + acceleration: -3.34 + command: -30.0 + } + calibration { + speed: 4.8 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 4.8 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 4.8 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 4.8 + acceleration: -1.27 + command: -26.0 + } + calibration { + speed: 4.8 + acceleration: -0.83 + command: -25.0 + } + calibration { + speed: 4.8 + acceleration: -0.55 + command: -24.0 + } + calibration { + speed: 4.8 + acceleration: -0.33 + command: -23.0 + } + calibration { + speed: 4.8 + acceleration: -0.26 + command: -22.0 + } + calibration { + speed: 4.8 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 4.8 + acceleration: -0.18 + command: -17.5 + } + calibration { + speed: 4.8 + acceleration: -0.16 + command: -17.0 + } + calibration { + speed: 4.8 + acceleration: 0.16 + command: 20.0 + } + calibration { + speed: 4.8 + acceleration: 0.33 + command: 22.0 + } + calibration { + speed: 4.8 + acceleration: 0.79 + command: 25.0 + } + calibration { + speed: 4.8 + acceleration: 1.29 + command: 27.0 + } + calibration { + speed: 4.8 + acceleration: 1.84 + command: 30.0 + } + calibration { + speed: 4.8 + acceleration: 2.73 + command: 35.0 + } + calibration { + speed: 4.8 + acceleration: 3.2 + command: 40.0 + } + calibration { + speed: 4.8 + acceleration: 3.39 + command: 45.0 + } + calibration { + speed: 4.8 + acceleration: 3.44 + command: 50.0 + } + calibration { + speed: 4.8 + acceleration: 3.45 + command: 55.0 + } + calibration { + speed: 5.0 + acceleration: -7.59 + command: -35.0 + } + calibration { + speed: 5.0 + acceleration: -5.2 + command: -33.0 + } + calibration { + speed: 5.0 + acceleration: -4.61 + command: -32.0 + } + calibration { + speed: 5.0 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 5.0 + acceleration: -3.35 + command: -30.0 + } + calibration { + speed: 5.0 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 5.0 + acceleration: -2.23 + command: -28.0 + } + calibration { + speed: 5.0 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 5.0 + acceleration: -1.29 + command: -26.0 + } + calibration { + speed: 5.0 + acceleration: -0.84 + command: -25.0 + } + calibration { + speed: 5.0 + acceleration: -0.55 + command: -24.0 + } + calibration { + speed: 5.0 + acceleration: -0.32 + command: -23.0 + } + calibration { + speed: 5.0 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 5.0 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 5.0 + acceleration: -0.17 + command: -15.0 + } + calibration { + speed: 5.0 + acceleration: -0.16 + command: -20.0 + } + calibration { + speed: 5.0 + acceleration: 0.17 + command: 20.0 + } + calibration { + speed: 5.0 + acceleration: 0.32 + command: 22.0 + } + calibration { + speed: 5.0 + acceleration: 0.73 + command: 25.0 + } + calibration { + speed: 5.0 + acceleration: 1.17 + command: 27.0 + } + calibration { + speed: 5.0 + acceleration: 1.7 + command: 30.0 + } + calibration { + speed: 5.0 + acceleration: 2.64 + command: 35.0 + } + calibration { + speed: 5.0 + acceleration: 3.15 + command: 40.0 + } + calibration { + speed: 5.0 + acceleration: 3.36 + command: 45.0 + } + calibration { + speed: 5.0 + acceleration: 3.46 + command: 50.0 + } + calibration { + speed: 5.0 + acceleration: 3.48 + command: 55.0 + } + calibration { + speed: 5.2 + acceleration: -7.59 + command: -35.0 + } + calibration { + speed: 5.2 + acceleration: -5.2 + command: -33.0 + } + calibration { + speed: 5.2 + acceleration: -4.57 + command: -32.0 + } + calibration { + speed: 5.2 + acceleration: -3.94 + command: -31.0 + } + calibration { + speed: 5.2 + acceleration: -3.35 + command: -30.0 + } + calibration { + speed: 5.2 + acceleration: -2.77 + command: -29.0 + } + calibration { + speed: 5.2 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 5.2 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 5.2 + acceleration: -1.29 + command: -26.0 + } + calibration { + speed: 5.2 + acceleration: -0.84 + command: -25.0 + } + calibration { + speed: 5.2 + acceleration: -0.57 + command: -24.0 + } + calibration { + speed: 5.2 + acceleration: -0.33 + command: -23.0 + } + calibration { + speed: 5.2 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 5.2 + acceleration: -0.21 + command: -15.0 + } + calibration { + speed: 5.2 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 5.2 + acceleration: -0.17 + command: -18.5 + } + calibration { + speed: 5.2 + acceleration: 0.17 + command: 20.0 + } + calibration { + speed: 5.2 + acceleration: 0.31 + command: 22.0 + } + calibration { + speed: 5.2 + acceleration: 0.69 + command: 25.0 + } + calibration { + speed: 5.2 + acceleration: 1.12 + command: 27.0 + } + calibration { + speed: 5.2 + acceleration: 1.57 + command: 30.0 + } + calibration { + speed: 5.2 + acceleration: 2.54 + command: 35.0 + } + calibration { + speed: 5.2 + acceleration: 3.11 + command: 40.0 + } + calibration { + speed: 5.2 + acceleration: 3.31 + command: 45.0 + } + calibration { + speed: 5.2 + acceleration: 3.45 + command: 50.0 + } + calibration { + speed: 5.2 + acceleration: 3.52 + command: 55.0 + } + calibration { + speed: 5.4 + acceleration: -7.61 + command: -35.0 + } + calibration { + speed: 5.4 + acceleration: -5.18 + command: -33.0 + } + calibration { + speed: 5.4 + acceleration: -4.55 + command: -32.0 + } + calibration { + speed: 5.4 + acceleration: -3.94 + command: -31.0 + } + calibration { + speed: 5.4 + acceleration: -3.33 + command: -30.0 + } + calibration { + speed: 5.4 + acceleration: -2.77 + command: -29.0 + } + calibration { + speed: 5.4 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 5.4 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 5.4 + acceleration: -1.27 + command: -26.0 + } + calibration { + speed: 5.4 + acceleration: -0.84 + command: -25.0 + } + calibration { + speed: 5.4 + acceleration: -0.56 + command: -24.0 + } + calibration { + speed: 5.4 + acceleration: -0.33 + command: -23.0 + } + calibration { + speed: 5.4 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 5.4 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 5.4 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 5.4 + acceleration: -0.16 + command: -20.0 + } + calibration { + speed: 5.4 + acceleration: -0.14 + command: -13.0 + } + calibration { + speed: 5.4 + acceleration: 0.15 + command: 20.0 + } + calibration { + speed: 5.4 + acceleration: 0.29 + command: 22.0 + } + calibration { + speed: 5.4 + acceleration: 0.66 + command: 25.0 + } + calibration { + speed: 5.4 + acceleration: 1.04 + command: 27.0 + } + calibration { + speed: 5.4 + acceleration: 1.5 + command: 30.0 + } + calibration { + speed: 5.4 + acceleration: 2.45 + command: 35.0 + } + calibration { + speed: 5.4 + acceleration: 3.05 + command: 40.0 + } + calibration { + speed: 5.4 + acceleration: 3.26 + command: 45.0 + } + calibration { + speed: 5.4 + acceleration: 3.42 + command: 50.0 + } + calibration { + speed: 5.4 + acceleration: 3.52 + command: 55.0 + } + calibration { + speed: 5.6 + acceleration: -7.64 + command: -35.0 + } + calibration { + speed: 5.6 + acceleration: -5.16 + command: -33.0 + } + calibration { + speed: 5.6 + acceleration: -4.53 + command: -32.0 + } + calibration { + speed: 5.6 + acceleration: -3.93 + command: -31.0 + } + calibration { + speed: 5.6 + acceleration: -3.32 + command: -30.0 + } + calibration { + speed: 5.6 + acceleration: -2.79 + command: -29.0 + } + calibration { + speed: 5.6 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 5.6 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 5.6 + acceleration: -1.29 + command: -26.0 + } + calibration { + speed: 5.6 + acceleration: -0.85 + command: -25.0 + } + calibration { + speed: 5.6 + acceleration: -0.58 + command: -24.0 + } + calibration { + speed: 5.6 + acceleration: -0.34 + command: -23.0 + } + calibration { + speed: 5.6 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 5.6 + acceleration: -0.2 + command: -16.0 + } + calibration { + speed: 5.6 + acceleration: -0.18 + command: -17.0 + } + calibration { + speed: 5.6 + acceleration: 0.18 + command: 20.0 + } + calibration { + speed: 5.6 + acceleration: 0.27 + command: 22.0 + } + calibration { + speed: 5.6 + acceleration: 0.61 + command: 25.0 + } + calibration { + speed: 5.6 + acceleration: 0.98 + command: 27.0 + } + calibration { + speed: 5.6 + acceleration: 1.44 + command: 30.0 + } + calibration { + speed: 5.6 + acceleration: 2.37 + command: 35.0 + } + calibration { + speed: 5.6 + acceleration: 3.0 + command: 40.0 + } + calibration { + speed: 5.6 + acceleration: 3.21 + command: 45.0 + } + calibration { + speed: 5.6 + acceleration: 3.38 + command: 50.0 + } + calibration { + speed: 5.6 + acceleration: 3.51 + command: 55.0 + } + calibration { + speed: 5.8 + acceleration: -7.67 + command: -35.0 + } + calibration { + speed: 5.8 + acceleration: -5.12 + command: -33.0 + } + calibration { + speed: 5.8 + acceleration: -4.52 + command: -32.0 + } + calibration { + speed: 5.8 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 5.8 + acceleration: -3.31 + command: -30.0 + } + calibration { + speed: 5.8 + acceleration: -2.82 + command: -29.0 + } + calibration { + speed: 5.8 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 5.8 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 5.8 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 5.8 + acceleration: -0.86 + command: -25.0 + } + calibration { + speed: 5.8 + acceleration: -0.58 + command: -24.0 + } + calibration { + speed: 5.8 + acceleration: -0.35 + command: -23.0 + } + calibration { + speed: 5.8 + acceleration: -0.29 + command: -22.0 + } + calibration { + speed: 5.8 + acceleration: -0.2 + command: -20.0 + } + calibration { + speed: 5.8 + acceleration: -0.17 + command: -16.0 + } + calibration { + speed: 5.8 + acceleration: -0.16 + command: -13.0 + } + calibration { + speed: 5.8 + acceleration: 0.12 + command: 20.0 + } + calibration { + speed: 5.8 + acceleration: 0.29 + command: 22.0 + } + calibration { + speed: 5.8 + acceleration: 0.59 + command: 25.0 + } + calibration { + speed: 5.8 + acceleration: 0.95 + command: 27.0 + } + calibration { + speed: 5.8 + acceleration: 1.39 + command: 30.0 + } + calibration { + speed: 5.8 + acceleration: 2.3 + command: 35.0 + } + calibration { + speed: 5.8 + acceleration: 2.94 + command: 40.0 + } + calibration { + speed: 5.8 + acceleration: 3.16 + command: 45.0 + } + calibration { + speed: 5.8 + acceleration: 3.35 + command: 50.0 + } + calibration { + speed: 5.8 + acceleration: 3.5 + command: 55.0 + } + calibration { + speed: 6.0 + acceleration: -7.69 + command: -35.0 + } + calibration { + speed: 6.0 + acceleration: -5.1 + command: -33.0 + } + calibration { + speed: 6.0 + acceleration: -4.52 + command: -32.0 + } + calibration { + speed: 6.0 + acceleration: -3.91 + command: -31.0 + } + calibration { + speed: 6.0 + acceleration: -3.31 + command: -30.0 + } + calibration { + speed: 6.0 + acceleration: -2.84 + command: -29.0 + } + calibration { + speed: 6.0 + acceleration: -2.22 + command: -28.0 + } + calibration { + speed: 6.0 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 6.0 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 6.0 + acceleration: -0.84 + command: -25.0 + } + calibration { + speed: 6.0 + acceleration: -0.58 + command: -24.0 + } + calibration { + speed: 6.0 + acceleration: -0.36 + command: -23.0 + } + calibration { + speed: 6.0 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 6.0 + acceleration: -0.21 + command: -20.0 + } + calibration { + speed: 6.0 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 6.0 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 6.0 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 6.0 + acceleration: 0.18 + command: 20.0 + } + calibration { + speed: 6.0 + acceleration: 0.28 + command: 22.0 + } + calibration { + speed: 6.0 + acceleration: 0.56 + command: 25.0 + } + calibration { + speed: 6.0 + acceleration: 0.92 + command: 27.0 + } + calibration { + speed: 6.0 + acceleration: 1.32 + command: 30.0 + } + calibration { + speed: 6.0 + acceleration: 2.23 + command: 35.0 + } + calibration { + speed: 6.0 + acceleration: 2.87 + command: 40.0 + } + calibration { + speed: 6.0 + acceleration: 3.12 + command: 45.0 + } + calibration { + speed: 6.0 + acceleration: 3.31 + command: 50.0 + } + calibration { + speed: 6.0 + acceleration: 3.46 + command: 55.0 + } + calibration { + speed: 6.2 + acceleration: -7.73 + command: -35.0 + } + calibration { + speed: 6.2 + acceleration: -5.08 + command: -33.0 + } + calibration { + speed: 6.2 + acceleration: -4.53 + command: -32.0 + } + calibration { + speed: 6.2 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 6.2 + acceleration: -3.3 + command: -30.0 + } + calibration { + speed: 6.2 + acceleration: -2.84 + command: -29.0 + } + calibration { + speed: 6.2 + acceleration: -2.23 + command: -28.0 + } + calibration { + speed: 6.2 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 6.2 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 6.2 + acceleration: -0.85 + command: -25.0 + } + calibration { + speed: 6.2 + acceleration: -0.59 + command: -24.0 + } + calibration { + speed: 6.2 + acceleration: -0.38 + command: -23.0 + } + calibration { + speed: 6.2 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 6.2 + acceleration: -0.21 + command: -16.5 + } + calibration { + speed: 6.2 + acceleration: -0.18 + command: -15.0 + } + calibration { + speed: 6.2 + acceleration: -0.17 + command: -17.0 + } + calibration { + speed: 6.2 + acceleration: 0.17 + command: 20.0 + } + calibration { + speed: 6.2 + acceleration: 0.28 + command: 22.0 + } + calibration { + speed: 6.2 + acceleration: 0.55 + command: 25.0 + } + calibration { + speed: 6.2 + acceleration: 0.87 + command: 27.0 + } + calibration { + speed: 6.2 + acceleration: 1.25 + command: 30.0 + } + calibration { + speed: 6.2 + acceleration: 2.16 + command: 35.0 + } + calibration { + speed: 6.2 + acceleration: 2.81 + command: 40.0 + } + calibration { + speed: 6.2 + acceleration: 3.07 + command: 45.0 + } + calibration { + speed: 6.2 + acceleration: 3.27 + command: 50.0 + } + calibration { + speed: 6.2 + acceleration: 3.42 + command: 55.0 + } + calibration { + speed: 6.4 + acceleration: -7.75 + command: -35.0 + } + calibration { + speed: 6.4 + acceleration: -5.07 + command: -33.0 + } + calibration { + speed: 6.4 + acceleration: -4.54 + command: -32.0 + } + calibration { + speed: 6.4 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 6.4 + acceleration: -3.3 + command: -30.0 + } + calibration { + speed: 6.4 + acceleration: -2.84 + command: -29.0 + } + calibration { + speed: 6.4 + acceleration: -2.23 + command: -28.0 + } + calibration { + speed: 6.4 + acceleration: -1.8 + command: -27.0 + } + calibration { + speed: 6.4 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 6.4 + acceleration: -0.86 + command: -25.0 + } + calibration { + speed: 6.4 + acceleration: -0.6 + command: -24.0 + } + calibration { + speed: 6.4 + acceleration: -0.38 + command: -23.0 + } + calibration { + speed: 6.4 + acceleration: -0.27 + command: -22.0 + } + calibration { + speed: 6.4 + acceleration: -0.2 + command: -17.5 + } + calibration { + speed: 6.4 + acceleration: -0.19 + command: -17.0 + } + calibration { + speed: 6.4 + acceleration: -0.17 + command: -13.0 + } + calibration { + speed: 6.4 + acceleration: 0.15 + command: 20.0 + } + calibration { + speed: 6.4 + acceleration: 0.26 + command: 22.0 + } + calibration { + speed: 6.4 + acceleration: 0.52 + command: 25.0 + } + calibration { + speed: 6.4 + acceleration: 0.82 + command: 27.0 + } + calibration { + speed: 6.4 + acceleration: 1.2 + command: 30.0 + } + calibration { + speed: 6.4 + acceleration: 2.09 + command: 35.0 + } + calibration { + speed: 6.4 + acceleration: 2.74 + command: 40.0 + } + calibration { + speed: 6.4 + acceleration: 3.01 + command: 45.0 + } + calibration { + speed: 6.4 + acceleration: 3.23 + command: 50.0 + } + calibration { + speed: 6.4 + acceleration: 3.36 + command: 55.0 + } + calibration { + speed: 6.6 + acceleration: -7.76 + command: -35.0 + } + calibration { + speed: 6.6 + acceleration: -5.06 + command: -33.0 + } + calibration { + speed: 6.6 + acceleration: -4.55 + command: -32.0 + } + calibration { + speed: 6.6 + acceleration: -3.93 + command: -31.0 + } + calibration { + speed: 6.6 + acceleration: -3.3 + command: -30.0 + } + calibration { + speed: 6.6 + acceleration: -2.83 + command: -29.0 + } + calibration { + speed: 6.6 + acceleration: -2.23 + command: -28.0 + } + calibration { + speed: 6.6 + acceleration: -1.81 + command: -27.0 + } + calibration { + speed: 6.6 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 6.6 + acceleration: -0.87 + command: -25.0 + } + calibration { + speed: 6.6 + acceleration: -0.6 + command: -24.0 + } + calibration { + speed: 6.6 + acceleration: -0.38 + command: -23.0 + } + calibration { + speed: 6.6 + acceleration: -0.3 + command: -22.0 + } + calibration { + speed: 6.6 + acceleration: -0.21 + command: -18.5 + } + calibration { + speed: 6.6 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 6.6 + acceleration: -0.19 + command: -15.0 + } + calibration { + speed: 6.6 + acceleration: 0.11 + command: 20.0 + } + calibration { + speed: 6.6 + acceleration: 0.25 + command: 22.0 + } + calibration { + speed: 6.6 + acceleration: 0.51 + command: 25.0 + } + calibration { + speed: 6.6 + acceleration: 0.81 + command: 27.0 + } + calibration { + speed: 6.6 + acceleration: 1.15 + command: 30.0 + } + calibration { + speed: 6.6 + acceleration: 2.01 + command: 35.0 + } + calibration { + speed: 6.6 + acceleration: 2.67 + command: 40.0 + } + calibration { + speed: 6.6 + acceleration: 2.95 + command: 45.0 + } + calibration { + speed: 6.6 + acceleration: 3.17 + command: 50.0 + } + calibration { + speed: 6.6 + acceleration: 3.3 + command: 55.0 + } + calibration { + speed: 6.8 + acceleration: -7.76 + command: -35.0 + } + calibration { + speed: 6.8 + acceleration: -5.06 + command: -33.0 + } + calibration { + speed: 6.8 + acceleration: -4.56 + command: -32.0 + } + calibration { + speed: 6.8 + acceleration: -3.94 + command: -31.0 + } + calibration { + speed: 6.8 + acceleration: -3.29 + command: -30.0 + } + calibration { + speed: 6.8 + acceleration: -2.83 + command: -29.0 + } + calibration { + speed: 6.8 + acceleration: -2.23 + command: -28.0 + } + calibration { + speed: 6.8 + acceleration: -1.82 + command: -27.0 + } + calibration { + speed: 6.8 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 6.8 + acceleration: -0.87 + command: -25.0 + } + calibration { + speed: 6.8 + acceleration: -0.62 + command: -24.0 + } + calibration { + speed: 6.8 + acceleration: -0.38 + command: -23.0 + } + calibration { + speed: 6.8 + acceleration: -0.31 + command: -22.0 + } + calibration { + speed: 6.8 + acceleration: -0.22 + command: -20.0 + } + calibration { + speed: 6.8 + acceleration: -0.21 + command: -14.0 + } + calibration { + speed: 6.8 + acceleration: -0.2 + command: -17.0 + } + calibration { + speed: 6.8 + acceleration: 0.12 + command: 20.0 + } + calibration { + speed: 6.8 + acceleration: 0.25 + command: 22.0 + } + calibration { + speed: 6.8 + acceleration: 0.5 + command: 25.0 + } + calibration { + speed: 6.8 + acceleration: 0.77 + command: 27.0 + } + calibration { + speed: 6.8 + acceleration: 1.13 + command: 30.0 + } + calibration { + speed: 6.8 + acceleration: 1.94 + command: 35.0 + } + calibration { + speed: 6.8 + acceleration: 2.6 + command: 40.0 + } + calibration { + speed: 6.8 + acceleration: 2.88 + command: 45.0 + } + calibration { + speed: 6.8 + acceleration: 3.13 + command: 50.0 + } + calibration { + speed: 6.8 + acceleration: 3.23 + command: 55.0 + } + calibration { + speed: 7.0 + acceleration: -7.75 + command: -35.0 + } + calibration { + speed: 7.0 + acceleration: -5.05 + command: -33.0 + } + calibration { + speed: 7.0 + acceleration: -4.56 + command: -32.0 + } + calibration { + speed: 7.0 + acceleration: -3.96 + command: -31.0 + } + calibration { + speed: 7.0 + acceleration: -3.3 + command: -30.0 + } + calibration { + speed: 7.0 + acceleration: -2.83 + command: -29.0 + } + calibration { + speed: 7.0 + acceleration: -2.24 + command: -28.0 + } + calibration { + speed: 7.0 + acceleration: -1.83 + command: -27.0 + } + calibration { + speed: 7.0 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 7.0 + acceleration: -0.87 + command: -25.0 + } + calibration { + speed: 7.0 + acceleration: -0.64 + command: -24.0 + } + calibration { + speed: 7.0 + acceleration: -0.38 + command: -23.0 + } + calibration { + speed: 7.0 + acceleration: -0.31 + command: -22.0 + } + calibration { + speed: 7.0 + acceleration: -0.24 + command: -20.0 + } + calibration { + speed: 7.0 + acceleration: -0.2 + command: -16.0 + } + calibration { + speed: 7.0 + acceleration: -0.19 + command: -13.0 + } + calibration { + speed: 7.0 + acceleration: 0.09 + command: 20.0 + } + calibration { + speed: 7.0 + acceleration: 0.23 + command: 22.0 + } + calibration { + speed: 7.0 + acceleration: 0.47 + command: 25.0 + } + calibration { + speed: 7.0 + acceleration: 0.77 + command: 27.0 + } + calibration { + speed: 7.0 + acceleration: 1.08 + command: 30.0 + } + calibration { + speed: 7.0 + acceleration: 1.87 + command: 35.0 + } + calibration { + speed: 7.0 + acceleration: 2.53 + command: 40.0 + } + calibration { + speed: 7.0 + acceleration: 2.83 + command: 45.0 + } + calibration { + speed: 7.0 + acceleration: 3.07 + command: 50.0 + } + calibration { + speed: 7.0 + acceleration: 3.17 + command: 55.0 + } + calibration { + speed: 7.2 + acceleration: -7.73 + command: -35.0 + } + calibration { + speed: 7.2 + acceleration: -5.03 + command: -33.0 + } + calibration { + speed: 7.2 + acceleration: -4.56 + command: -32.0 + } + calibration { + speed: 7.2 + acceleration: -3.96 + command: -31.0 + } + calibration { + speed: 7.2 + acceleration: -3.31 + command: -30.0 + } + calibration { + speed: 7.2 + acceleration: -2.83 + command: -29.0 + } + calibration { + speed: 7.2 + acceleration: -2.24 + command: -28.0 + } + calibration { + speed: 7.2 + acceleration: -1.83 + command: -27.0 + } + calibration { + speed: 7.2 + acceleration: -1.31 + command: -26.0 + } + calibration { + speed: 7.2 + acceleration: -0.86 + command: -25.0 + } + calibration { + speed: 7.2 + acceleration: -0.66 + command: -24.0 + } + calibration { + speed: 7.2 + acceleration: -0.36 + command: -23.0 + } + calibration { + speed: 7.2 + acceleration: -0.32 + command: -22.0 + } + calibration { + speed: 7.2 + acceleration: -0.26 + command: -20.0 + } + calibration { + speed: 7.2 + acceleration: -0.22 + command: -13.0 + } + calibration { + speed: 7.2 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 7.2 + acceleration: -0.2 + command: -15.0 + } + calibration { + speed: 7.2 + acceleration: 0.11 + command: 20.0 + } + calibration { + speed: 7.2 + acceleration: 0.22 + command: 22.0 + } + calibration { + speed: 7.2 + acceleration: 0.47 + command: 25.0 + } + calibration { + speed: 7.2 + acceleration: 0.74 + command: 27.0 + } + calibration { + speed: 7.2 + acceleration: 1.05 + command: 30.0 + } + calibration { + speed: 7.2 + acceleration: 1.82 + command: 35.0 + } + calibration { + speed: 7.2 + acceleration: 2.46 + command: 40.0 + } + calibration { + speed: 7.2 + acceleration: 2.77 + command: 45.0 + } + calibration { + speed: 7.2 + acceleration: 3.02 + command: 50.0 + } + calibration { + speed: 7.2 + acceleration: 3.11 + command: 55.0 + } + calibration { + speed: 7.4 + acceleration: -7.7 + command: -35.0 + } + calibration { + speed: 7.4 + acceleration: -5.0 + command: -33.0 + } + calibration { + speed: 7.4 + acceleration: -4.55 + command: -32.0 + } + calibration { + speed: 7.4 + acceleration: -3.97 + command: -31.0 + } + calibration { + speed: 7.4 + acceleration: -3.31 + command: -30.0 + } + calibration { + speed: 7.4 + acceleration: -2.83 + command: -29.0 + } + calibration { + speed: 7.4 + acceleration: -2.24 + command: -28.0 + } + calibration { + speed: 7.4 + acceleration: -1.82 + command: -27.0 + } + calibration { + speed: 7.4 + acceleration: -1.32 + command: -26.0 + } + calibration { + speed: 7.4 + acceleration: -0.86 + command: -25.0 + } + calibration { + speed: 7.4 + acceleration: -0.63 + command: -24.0 + } + calibration { + speed: 7.4 + acceleration: -0.38 + command: -23.0 + } + calibration { + speed: 7.4 + acceleration: -0.32 + command: -22.0 + } + calibration { + speed: 7.4 + acceleration: -0.23 + command: -18.5 + } + calibration { + speed: 7.4 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 7.4 + acceleration: -0.2 + command: -13.0 + } + calibration { + speed: 7.4 + acceleration: 0.12 + command: 20.0 + } + calibration { + speed: 7.4 + acceleration: 0.2 + command: 22.0 + } + calibration { + speed: 7.4 + acceleration: 0.45 + command: 25.0 + } + calibration { + speed: 7.4 + acceleration: 0.72 + command: 27.0 + } + calibration { + speed: 7.4 + acceleration: 1.01 + command: 30.0 + } + calibration { + speed: 7.4 + acceleration: 1.77 + command: 35.0 + } + calibration { + speed: 7.4 + acceleration: 2.38 + command: 40.0 + } + calibration { + speed: 7.4 + acceleration: 2.7 + command: 45.0 + } + calibration { + speed: 7.4 + acceleration: 2.97 + command: 50.0 + } + calibration { + speed: 7.4 + acceleration: 3.04 + command: 55.0 + } + calibration { + speed: 7.6 + acceleration: -7.67 + command: -35.0 + } + calibration { + speed: 7.6 + acceleration: -4.97 + command: -33.0 + } + calibration { + speed: 7.6 + acceleration: -4.52 + command: -32.0 + } + calibration { + speed: 7.6 + acceleration: -3.98 + command: -31.0 + } + calibration { + speed: 7.6 + acceleration: -3.31 + command: -30.0 + } + calibration { + speed: 7.6 + acceleration: -2.82 + command: -29.0 + } + calibration { + speed: 7.6 + acceleration: -2.24 + command: -28.0 + } + calibration { + speed: 7.6 + acceleration: -1.82 + command: -27.0 + } + calibration { + speed: 7.6 + acceleration: -1.33 + command: -26.0 + } + calibration { + speed: 7.6 + acceleration: -0.91 + command: -25.0 + } + calibration { + speed: 7.6 + acceleration: -0.64 + command: -24.0 + } + calibration { + speed: 7.6 + acceleration: -0.36 + command: -23.0 + } + calibration { + speed: 7.6 + acceleration: -0.31 + command: -22.0 + } + calibration { + speed: 7.6 + acceleration: -0.24 + command: -16.5 + } + calibration { + speed: 7.6 + acceleration: -0.23 + command: -16.0 + } + calibration { + speed: 7.6 + acceleration: 0.07 + command: 20.0 + } + calibration { + speed: 7.6 + acceleration: 0.21 + command: 22.0 + } + calibration { + speed: 7.6 + acceleration: 0.43 + command: 25.0 + } + calibration { + speed: 7.6 + acceleration: 0.7 + command: 27.0 + } + calibration { + speed: 7.6 + acceleration: 0.97 + command: 30.0 + } + calibration { + speed: 7.6 + acceleration: 1.72 + command: 35.0 + } + calibration { + speed: 7.6 + acceleration: 2.32 + command: 40.0 + } + calibration { + speed: 7.6 + acceleration: 2.64 + command: 45.0 + } + calibration { + speed: 7.6 + acceleration: 2.92 + command: 50.0 + } + calibration { + speed: 7.6 + acceleration: 2.99 + command: 55.0 + } + calibration { + speed: 7.8 + acceleration: -7.64 + command: -35.0 + } + calibration { + speed: 7.8 + acceleration: -4.96 + command: -33.0 + } + calibration { + speed: 7.8 + acceleration: -4.49 + command: -32.0 + } + calibration { + speed: 7.8 + acceleration: -3.97 + command: -31.0 + } + calibration { + speed: 7.8 + acceleration: -3.3 + command: -30.0 + } + calibration { + speed: 7.8 + acceleration: -2.81 + command: -29.0 + } + calibration { + speed: 7.8 + acceleration: -2.25 + command: -28.0 + } + calibration { + speed: 7.8 + acceleration: -1.83 + command: -27.0 + } + calibration { + speed: 7.8 + acceleration: -1.33 + command: -26.0 + } + calibration { + speed: 7.8 + acceleration: -0.9 + command: -25.0 + } + calibration { + speed: 7.8 + acceleration: -0.64 + command: -24.0 + } + calibration { + speed: 7.8 + acceleration: -0.4 + command: -23.0 + } + calibration { + speed: 7.8 + acceleration: -0.32 + command: -22.0 + } + calibration { + speed: 7.8 + acceleration: -0.24 + command: -14.0 + } + calibration { + speed: 7.8 + acceleration: -0.22 + command: -20.0 + } + calibration { + speed: 7.8 + acceleration: -0.2 + command: -17.0 + } + calibration { + speed: 7.8 + acceleration: 0.07 + command: 20.0 + } + calibration { + speed: 7.8 + acceleration: 0.17 + command: 22.0 + } + calibration { + speed: 7.8 + acceleration: 0.42 + command: 25.0 + } + calibration { + speed: 7.8 + acceleration: 0.66 + command: 27.0 + } + calibration { + speed: 7.8 + acceleration: 0.95 + command: 30.0 + } + calibration { + speed: 7.8 + acceleration: 1.66 + command: 35.0 + } + calibration { + speed: 7.8 + acceleration: 2.26 + command: 40.0 + } + calibration { + speed: 7.8 + acceleration: 2.58 + command: 45.0 + } + calibration { + speed: 7.8 + acceleration: 2.86 + command: 50.0 + } + calibration { + speed: 7.8 + acceleration: 2.92 + command: 55.0 + } + calibration { + speed: 8.0 + acceleration: -7.63 + command: -35.0 + } + calibration { + speed: 8.0 + acceleration: -4.96 + command: -33.0 + } + calibration { + speed: 8.0 + acceleration: -4.46 + command: -32.0 + } + calibration { + speed: 8.0 + acceleration: -3.96 + command: -31.0 + } + calibration { + speed: 8.0 + acceleration: -3.29 + command: -30.0 + } + calibration { + speed: 8.0 + acceleration: -2.79 + command: -29.0 + } + calibration { + speed: 8.0 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 8.0 + acceleration: -1.85 + command: -27.0 + } + calibration { + speed: 8.0 + acceleration: -1.33 + command: -26.0 + } + calibration { + speed: 8.0 + acceleration: -0.9 + command: -25.0 + } + calibration { + speed: 8.0 + acceleration: -0.64 + command: -24.0 + } + calibration { + speed: 8.0 + acceleration: -0.4 + command: -23.0 + } + calibration { + speed: 8.0 + acceleration: -0.34 + command: -22.0 + } + calibration { + speed: 8.0 + acceleration: -0.23 + command: -20.0 + } + calibration { + speed: 8.0 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 8.0 + acceleration: -0.21 + command: -17.0 + } + calibration { + speed: 8.0 + acceleration: -0.18 + command: -13.0 + } + calibration { + speed: 8.0 + acceleration: 0.03 + command: 20.0 + } + calibration { + speed: 8.0 + acceleration: 0.16 + command: 22.0 + } + calibration { + speed: 8.0 + acceleration: 0.39 + command: 25.0 + } + calibration { + speed: 8.0 + acceleration: 0.64 + command: 27.0 + } + calibration { + speed: 8.0 + acceleration: 0.9 + command: 30.0 + } + calibration { + speed: 8.0 + acceleration: 1.61 + command: 35.0 + } + calibration { + speed: 8.0 + acceleration: 2.21 + command: 40.0 + } + calibration { + speed: 8.0 + acceleration: 2.53 + command: 45.0 + } + calibration { + speed: 8.0 + acceleration: 2.81 + command: 50.0 + } + calibration { + speed: 8.0 + acceleration: 2.88 + command: 55.0 + } + calibration { + speed: 8.2 + acceleration: -7.64 + command: -35.0 + } + calibration { + speed: 8.2 + acceleration: -4.99 + command: -33.0 + } + calibration { + speed: 8.2 + acceleration: -4.44 + command: -32.0 + } + calibration { + speed: 8.2 + acceleration: -3.94 + command: -31.0 + } + calibration { + speed: 8.2 + acceleration: -3.28 + command: -30.0 + } + calibration { + speed: 8.2 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 8.2 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 8.2 + acceleration: -1.86 + command: -27.0 + } + calibration { + speed: 8.2 + acceleration: -1.34 + command: -26.0 + } + calibration { + speed: 8.2 + acceleration: -0.89 + command: -25.0 + } + calibration { + speed: 8.2 + acceleration: -0.63 + command: -24.0 + } + calibration { + speed: 8.2 + acceleration: -0.4 + command: -23.0 + } + calibration { + speed: 8.2 + acceleration: -0.33 + command: -22.0 + } + calibration { + speed: 8.2 + acceleration: -0.24 + command: -20.0 + } + calibration { + speed: 8.2 + acceleration: -0.23 + command: -13.0 + } + calibration { + speed: 8.2 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 8.2 + acceleration: -0.2 + command: -17.0 + } + calibration { + speed: 8.2 + acceleration: 0.05 + command: 20.0 + } + calibration { + speed: 8.2 + acceleration: 0.12 + command: 22.0 + } + calibration { + speed: 8.2 + acceleration: 0.4 + command: 25.0 + } + calibration { + speed: 8.2 + acceleration: 0.64 + command: 27.0 + } + calibration { + speed: 8.2 + acceleration: 0.9 + command: 30.0 + } + calibration { + speed: 8.2 + acceleration: 1.56 + command: 35.0 + } + calibration { + speed: 8.2 + acceleration: 2.15 + command: 40.0 + } + calibration { + speed: 8.2 + acceleration: 2.48 + command: 45.0 + } + calibration { + speed: 8.2 + acceleration: 2.76 + command: 50.0 + } + calibration { + speed: 8.2 + acceleration: 2.83 + command: 55.0 + } + calibration { + speed: 8.4 + acceleration: -7.66 + command: -35.0 + } + calibration { + speed: 8.4 + acceleration: -5.05 + command: -33.0 + } + calibration { + speed: 8.4 + acceleration: -4.43 + command: -32.0 + } + calibration { + speed: 8.4 + acceleration: -3.9 + command: -31.0 + } + calibration { + speed: 8.4 + acceleration: -3.28 + command: -30.0 + } + calibration { + speed: 8.4 + acceleration: -2.79 + command: -29.0 + } + calibration { + speed: 8.4 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 8.4 + acceleration: -1.85 + command: -27.0 + } + calibration { + speed: 8.4 + acceleration: -1.37 + command: -26.0 + } + calibration { + speed: 8.4 + acceleration: -0.89 + command: -25.0 + } + calibration { + speed: 8.4 + acceleration: -0.68 + command: -24.0 + } + calibration { + speed: 8.4 + acceleration: -0.42 + command: -23.0 + } + calibration { + speed: 8.4 + acceleration: -0.34 + command: -22.0 + } + calibration { + speed: 8.4 + acceleration: -0.26 + command: -20.0 + } + calibration { + speed: 8.4 + acceleration: -0.24 + command: -13.0 + } + calibration { + speed: 8.4 + acceleration: -0.22 + command: -16.0 + } + calibration { + speed: 8.4 + acceleration: 0.04 + command: 20.0 + } + calibration { + speed: 8.4 + acceleration: 0.16 + command: 22.0 + } + calibration { + speed: 8.4 + acceleration: 0.4 + command: 25.0 + } + calibration { + speed: 8.4 + acceleration: 0.59 + command: 27.0 + } + calibration { + speed: 8.4 + acceleration: 0.87 + command: 30.0 + } + calibration { + speed: 8.4 + acceleration: 1.51 + command: 35.0 + } + calibration { + speed: 8.4 + acceleration: 2.09 + command: 40.0 + } + calibration { + speed: 8.4 + acceleration: 2.44 + command: 45.0 + } + calibration { + speed: 8.4 + acceleration: 2.71 + command: 50.0 + } + calibration { + speed: 8.4 + acceleration: 2.79 + command: 55.0 + } + calibration { + speed: 8.6 + acceleration: -7.7 + command: -35.0 + } + calibration { + speed: 8.6 + acceleration: -5.08 + command: -33.0 + } + calibration { + speed: 8.6 + acceleration: -4.45 + command: -32.0 + } + calibration { + speed: 8.6 + acceleration: -3.87 + command: -31.0 + } + calibration { + speed: 8.6 + acceleration: -3.29 + command: -30.0 + } + calibration { + speed: 8.6 + acceleration: -2.82 + command: -29.0 + } + calibration { + speed: 8.6 + acceleration: -2.25 + command: -28.0 + } + calibration { + speed: 8.6 + acceleration: -1.85 + command: -27.0 + } + calibration { + speed: 8.6 + acceleration: -1.35 + command: -26.0 + } + calibration { + speed: 8.6 + acceleration: -0.93 + command: -25.0 + } + calibration { + speed: 8.6 + acceleration: -0.66 + command: -24.0 + } + calibration { + speed: 8.6 + acceleration: -0.4 + command: -23.0 + } + calibration { + speed: 8.6 + acceleration: -0.33 + command: -22.0 + } + calibration { + speed: 8.6 + acceleration: -0.27 + command: -15.0 + } + calibration { + speed: 8.6 + acceleration: -0.26 + command: -16.5 + } + calibration { + speed: 8.6 + acceleration: -0.23 + command: -17.0 + } + calibration { + speed: 8.6 + acceleration: 0.1 + command: 22.0 + } + calibration { + speed: 8.6 + acceleration: 0.36 + command: 25.0 + } + calibration { + speed: 8.6 + acceleration: 0.58 + command: 27.0 + } + calibration { + speed: 8.6 + acceleration: 0.82 + command: 30.0 + } + calibration { + speed: 8.6 + acceleration: 1.47 + command: 35.0 + } + calibration { + speed: 8.6 + acceleration: 2.04 + command: 40.0 + } + calibration { + speed: 8.6 + acceleration: 2.38 + command: 45.0 + } + calibration { + speed: 8.6 + acceleration: 2.66 + command: 50.0 + } + calibration { + speed: 8.6 + acceleration: 2.74 + command: 55.0 + } + calibration { + speed: 8.8 + acceleration: -7.78 + command: -35.0 + } + calibration { + speed: 8.8 + acceleration: -5.11 + command: -33.0 + } + calibration { + speed: 8.8 + acceleration: -4.49 + command: -32.0 + } + calibration { + speed: 8.8 + acceleration: -3.85 + command: -31.0 + } + calibration { + speed: 8.8 + acceleration: -3.31 + command: -30.0 + } + calibration { + speed: 8.8 + acceleration: -2.86 + command: -29.0 + } + calibration { + speed: 8.8 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 8.8 + acceleration: -1.85 + command: -27.0 + } + calibration { + speed: 8.8 + acceleration: -1.34 + command: -26.0 + } + calibration { + speed: 8.8 + acceleration: -0.91 + command: -25.0 + } + calibration { + speed: 8.8 + acceleration: -0.7 + command: -24.0 + } + calibration { + speed: 8.8 + acceleration: -0.41 + command: -23.0 + } + calibration { + speed: 8.8 + acceleration: -0.31 + command: -22.0 + } + calibration { + speed: 8.8 + acceleration: -0.27 + command: -20.0 + } + calibration { + speed: 8.8 + acceleration: -0.24 + command: -15.0 + } + calibration { + speed: 8.8 + acceleration: -0.22 + command: -15.0 + } + calibration { + speed: 8.8 + acceleration: 0.09 + command: 22.0 + } + calibration { + speed: 8.8 + acceleration: 0.38 + command: 25.0 + } + calibration { + speed: 8.8 + acceleration: 0.55 + command: 27.0 + } + calibration { + speed: 8.8 + acceleration: 0.8 + command: 30.0 + } + calibration { + speed: 8.8 + acceleration: 1.44 + command: 35.0 + } + calibration { + speed: 8.8 + acceleration: 1.98 + command: 40.0 + } + calibration { + speed: 8.8 + acceleration: 2.31 + command: 45.0 + } + calibration { + speed: 8.8 + acceleration: 2.61 + command: 50.0 + } + calibration { + speed: 8.8 + acceleration: 2.69 + command: 55.0 + } + calibration { + speed: 9.0 + acceleration: -7.84 + command: -35.0 + } + calibration { + speed: 9.0 + acceleration: -5.08 + command: -33.0 + } + calibration { + speed: 9.0 + acceleration: -4.53 + command: -32.0 + } + calibration { + speed: 9.0 + acceleration: -3.86 + command: -31.0 + } + calibration { + speed: 9.0 + acceleration: -3.31 + command: -30.0 + } + calibration { + speed: 9.0 + acceleration: -2.88 + command: -29.0 + } + calibration { + speed: 9.0 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 9.0 + acceleration: -1.86 + command: -27.0 + } + calibration { + speed: 9.0 + acceleration: -1.39 + command: -26.0 + } + calibration { + speed: 9.0 + acceleration: -0.92 + command: -25.0 + } + calibration { + speed: 9.0 + acceleration: -0.67 + command: -24.0 + } + calibration { + speed: 9.0 + acceleration: -0.45 + command: -23.0 + } + calibration { + speed: 9.0 + acceleration: -0.36 + command: -22.0 + } + calibration { + speed: 9.0 + acceleration: -0.27 + command: -20.0 + } + calibration { + speed: 9.0 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 9.0 + acceleration: -0.25 + command: -15.0 + } + calibration { + speed: 9.0 + acceleration: 0.08 + command: 22.0 + } + calibration { + speed: 9.0 + acceleration: 0.32 + command: 25.0 + } + calibration { + speed: 9.0 + acceleration: 0.51 + command: 27.0 + } + calibration { + speed: 9.0 + acceleration: 0.76 + command: 30.0 + } + calibration { + speed: 9.0 + acceleration: 1.38 + command: 35.0 + } + calibration { + speed: 9.0 + acceleration: 1.93 + command: 40.0 + } + calibration { + speed: 9.0 + acceleration: 2.26 + command: 45.0 + } + calibration { + speed: 9.0 + acceleration: 2.56 + command: 50.0 + } + calibration { + speed: 9.0 + acceleration: 2.63 + command: 55.0 + } + calibration { + speed: 9.2 + acceleration: -7.9 + command: -35.0 + } + calibration { + speed: 9.2 + acceleration: -5.01 + command: -33.0 + } + calibration { + speed: 9.2 + acceleration: -4.54 + command: -32.0 + } + calibration { + speed: 9.2 + acceleration: -3.89 + command: -31.0 + } + calibration { + speed: 9.2 + acceleration: -3.25 + command: -30.0 + } + calibration { + speed: 9.2 + acceleration: -2.86 + command: -29.0 + } + calibration { + speed: 9.2 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 9.2 + acceleration: -1.87 + command: -27.0 + } + calibration { + speed: 9.2 + acceleration: -1.37 + command: -26.0 + } + calibration { + speed: 9.2 + acceleration: -0.91 + command: -25.0 + } + calibration { + speed: 9.2 + acceleration: -0.64 + command: -24.0 + } + calibration { + speed: 9.2 + acceleration: -0.42 + command: -23.0 + } + calibration { + speed: 9.2 + acceleration: -0.36 + command: -22.0 + } + calibration { + speed: 9.2 + acceleration: -0.28 + command: -20.0 + } + calibration { + speed: 9.2 + acceleration: -0.27 + command: -17.0 + } + calibration { + speed: 9.2 + acceleration: -0.26 + command: -13.0 + } + calibration { + speed: 9.2 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 9.2 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 9.2 + acceleration: 0.34 + command: 25.0 + } + calibration { + speed: 9.2 + acceleration: 0.52 + command: 27.0 + } + calibration { + speed: 9.2 + acceleration: 0.75 + command: 30.0 + } + calibration { + speed: 9.2 + acceleration: 1.33 + command: 35.0 + } + calibration { + speed: 9.2 + acceleration: 1.88 + command: 40.0 + } + calibration { + speed: 9.2 + acceleration: 2.21 + command: 45.0 + } + calibration { + speed: 9.2 + acceleration: 2.51 + command: 50.0 + } + calibration { + speed: 9.2 + acceleration: 2.56 + command: 55.0 + } + calibration { + speed: 9.4 + acceleration: -7.95 + command: -35.0 + } + calibration { + speed: 9.4 + acceleration: -4.89 + command: -33.0 + } + calibration { + speed: 9.4 + acceleration: -4.52 + command: -32.0 + } + calibration { + speed: 9.4 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 9.4 + acceleration: -3.15 + command: -30.0 + } + calibration { + speed: 9.4 + acceleration: -2.82 + command: -29.0 + } + calibration { + speed: 9.4 + acceleration: -2.26 + command: -28.0 + } + calibration { + speed: 9.4 + acceleration: -1.87 + command: -27.0 + } + calibration { + speed: 9.4 + acceleration: -1.38 + command: -26.0 + } + calibration { + speed: 9.4 + acceleration: -0.92 + command: -25.0 + } + calibration { + speed: 9.4 + acceleration: -0.66 + command: -24.0 + } + calibration { + speed: 9.4 + acceleration: -0.43 + command: -23.0 + } + calibration { + speed: 9.4 + acceleration: -0.38 + command: -22.0 + } + calibration { + speed: 9.4 + acceleration: -0.31 + command: -20.0 + } + calibration { + speed: 9.4 + acceleration: -0.28 + command: -13.0 + } + calibration { + speed: 9.4 + acceleration: -0.26 + command: -17.0 + } + calibration { + speed: 9.4 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 9.4 + acceleration: 0.06 + command: 22.0 + } + calibration { + speed: 9.4 + acceleration: 0.32 + command: 25.0 + } + calibration { + speed: 9.4 + acceleration: 0.49 + command: 27.0 + } + calibration { + speed: 9.4 + acceleration: 0.72 + command: 30.0 + } + calibration { + speed: 9.4 + acceleration: 1.29 + command: 35.0 + } + calibration { + speed: 9.4 + acceleration: 1.83 + command: 40.0 + } + calibration { + speed: 9.4 + acceleration: 2.17 + command: 45.0 + } + calibration { + speed: 9.4 + acceleration: 2.46 + command: 50.0 + } + calibration { + speed: 9.4 + acceleration: 2.5 + command: 55.0 + } + calibration { + speed: 9.6 + acceleration: -8.0 + command: -35.0 + } + calibration { + speed: 9.6 + acceleration: -4.78 + command: -33.0 + } + calibration { + speed: 9.6 + acceleration: -4.4 + command: -32.0 + } + calibration { + speed: 9.6 + acceleration: -3.95 + command: -31.0 + } + calibration { + speed: 9.6 + acceleration: -3.01 + command: -30.0 + } + calibration { + speed: 9.6 + acceleration: -2.79 + command: -29.0 + } + calibration { + speed: 9.6 + acceleration: -2.27 + command: -28.0 + } + calibration { + speed: 9.6 + acceleration: -1.88 + command: -27.0 + } + calibration { + speed: 9.6 + acceleration: -1.41 + command: -26.0 + } + calibration { + speed: 9.6 + acceleration: -0.93 + command: -25.0 + } + calibration { + speed: 9.6 + acceleration: -0.69 + command: -24.0 + } + calibration { + speed: 9.6 + acceleration: -0.45 + command: -23.0 + } + calibration { + speed: 9.6 + acceleration: -0.37 + command: -22.0 + } + calibration { + speed: 9.6 + acceleration: -0.27 + command: -18.5 + } + calibration { + speed: 9.6 + acceleration: -0.25 + command: -13.0 + } + calibration { + speed: 9.6 + acceleration: -0.23 + command: -15.0 + } + calibration { + speed: 9.6 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 9.6 + acceleration: 0.29 + command: 25.0 + } + calibration { + speed: 9.6 + acceleration: 0.46 + command: 27.0 + } + calibration { + speed: 9.6 + acceleration: 0.66 + command: 30.0 + } + calibration { + speed: 9.6 + acceleration: 1.23 + command: 35.0 + } + calibration { + speed: 9.6 + acceleration: 1.79 + command: 40.0 + } + calibration { + speed: 9.6 + acceleration: 2.13 + command: 45.0 + } + calibration { + speed: 9.6 + acceleration: 2.42 + command: 50.0 + } + calibration { + speed: 9.6 + acceleration: 2.44 + command: 55.0 + } + calibration { + speed: 9.8 + acceleration: -7.98 + command: -35.0 + } + calibration { + speed: 9.8 + acceleration: -4.71 + command: -33.0 + } + calibration { + speed: 9.8 + acceleration: -4.32 + command: -32.0 + } + calibration { + speed: 9.8 + acceleration: -3.92 + command: -31.0 + } + calibration { + speed: 9.8 + acceleration: -2.91 + command: -30.0 + } + calibration { + speed: 9.8 + acceleration: -2.78 + command: -29.0 + } + calibration { + speed: 9.8 + acceleration: -2.28 + command: -28.0 + } + calibration { + speed: 9.8 + acceleration: -1.88 + command: -27.0 + } + calibration { + speed: 9.8 + acceleration: -1.41 + command: -26.0 + } + calibration { + speed: 9.8 + acceleration: -0.95 + command: -25.0 + } + calibration { + speed: 9.8 + acceleration: -0.68 + command: -24.0 + } + calibration { + speed: 9.8 + acceleration: -0.56 + command: 20.0 + } + calibration { + speed: 9.8 + acceleration: -0.45 + command: -23.0 + } + calibration { + speed: 9.8 + acceleration: -0.36 + command: -22.0 + } + calibration { + speed: 9.8 + acceleration: -0.31 + command: -17.0 + } + calibration { + speed: 9.8 + acceleration: -0.27 + command: -16.5 + } + calibration { + speed: 9.8 + acceleration: -0.26 + command: -15.0 + } + calibration { + speed: 9.8 + acceleration: 0.09 + command: 22.0 + } + calibration { + speed: 9.8 + acceleration: 0.27 + command: 25.0 + } + calibration { + speed: 9.8 + acceleration: 0.44 + command: 27.0 + } + calibration { + speed: 9.8 + acceleration: 0.68 + command: 30.0 + } + calibration { + speed: 9.8 + acceleration: 1.22 + command: 35.0 + } + calibration { + speed: 9.8 + acceleration: 1.75 + command: 40.0 + } + calibration { + speed: 9.8 + acceleration: 2.08 + command: 45.0 + } + calibration { + speed: 9.8 + acceleration: 2.37 + command: 50.0 + } + calibration { + speed: 9.8 + acceleration: 2.4 + command: 55.0 + } + calibration { + speed: 10.0 + acceleration: -7.91 + command: -35.0 + } + calibration { + speed: 10.0 + acceleration: -4.71 + command: -33.0 + } + calibration { + speed: 10.0 + acceleration: -4.25 + command: -32.0 + } + calibration { + speed: 10.0 + acceleration: -3.83 + command: -31.0 + } + calibration { + speed: 10.0 + acceleration: -3.31 + command: -30.0 + } + calibration { + speed: 10.0 + acceleration: -2.82 + command: -29.0 + } + calibration { + speed: 10.0 + acceleration: -2.28 + command: -28.0 + } + calibration { + speed: 10.0 + acceleration: -1.88 + command: -27.0 + } + calibration { + speed: 10.0 + acceleration: -1.39 + command: -26.0 + } + calibration { + speed: 10.0 + acceleration: -0.95 + command: -25.0 + } + calibration { + speed: 10.0 + acceleration: -0.69 + command: -24.0 + } + calibration { + speed: 10.0 + acceleration: -0.46 + command: -23.0 + } + calibration { + speed: 10.0 + acceleration: -0.36 + command: -22.0 + } + calibration { + speed: 10.0 + acceleration: -0.3 + command: -14.0 + } + calibration { + speed: 10.0 + acceleration: -0.29 + command: -20.0 + } + calibration { + speed: 10.0 + acceleration: -0.28 + command: -17.0 + } + calibration { + speed: 10.0 + acceleration: -0.04 + command: 20.0 + } + calibration { + speed: 10.0 + acceleration: 0.07 + command: 22.0 + } + calibration { + speed: 10.0 + acceleration: 0.26 + command: 25.0 + } + calibration { + speed: 10.0 + acceleration: 0.42 + command: 27.0 + } + calibration { + speed: 10.0 + acceleration: 0.64 + command: 30.0 + } + calibration { + speed: 10.0 + acceleration: 1.2 + command: 35.0 + } + calibration { + speed: 10.0 + acceleration: 1.71 + command: 40.0 + } + calibration { + speed: 10.0 + acceleration: 2.03 + command: 45.0 + } + calibration { + speed: 10.0 + acceleration: 2.33 + command: 50.0 + } + calibration { + speed: 10.0 + acceleration: 2.36 + command: 55.0 + } + } +} +trajectory_period: 0.1 +chassis_period: 0.01 +localization_period: 0.01 diff --git a/apollo_control/include/apollo_control/common/base_types.h b/apollo_control/include/apollo_control/common/base_types.h new file mode 100644 index 0000000..e08a180 --- /dev/null +++ b/apollo_control/include/apollo_control/common/base_types.h @@ -0,0 +1,77 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ +#ifndef MODULES_CONTROL_COMMON_BASE_TYPES_H_ +#define MODULES_CONTROL_COMMON_BASE_TYPES_H_ + +#include +#include + +/** + * @namespace apollo::control + * @brief apollo::control + */ +namespace apollo { +namespace control { + +struct PathPoint { + public: + double x = 0.0; + double y = 0.0; + double z = 0.0; + double theta = 0.0; + double kappa = 0.0; + double s = 0.0; + std::string DebugString() { + std::stringstream ss; + ss << "x:" << x << " y:" << y << " z:" << z << " theta:" << theta + << " kappa:" << kappa << " s:" << s; + return ss.str(); + } +}; + +struct TrajectoryPoint : public PathPoint { + public: + double v = 0.0; // in [m/s] + double a = 0.0; + double relative_time = 0.0; + std::string DebugString() { + std::stringstream ss; + ss << PathPoint::DebugString() << " v:" << v << " a:" << a + << " relative_time:" << relative_time; + return ss.str(); + } +}; + +} // namespace control +} // namespace apollo + +#endif /* MODULES_CONTROL_COMMON_BASE_TYPES_H_ */ diff --git a/apollo_control/include/apollo_control/common/control_gflags.h b/apollo_control/include/apollo_control/common/control_gflags.h new file mode 100644 index 0000000..72efe32 --- /dev/null +++ b/apollo_control/include/apollo_control/common/control_gflags.h @@ -0,0 +1,66 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_CONTROL_COMMON_CONTROL_GFLAGS_H_ +#define MODULES_CONTROL_COMMON_CONTROL_GFLAGS_H_ + +#include + +// data file +DECLARE_string(control_conf_file); + +DECLARE_double(min_alert_interval); +DECLARE_bool(enable_csv_debug); + +// gflags for test purpose +DECLARE_bool(use_state_exact_match); + +// temporary gflag for test purpose +DECLARE_bool(enable_speed_station_preview); + +DECLARE_bool(enable_control_watchdog); +DECLARE_string(node_name); +DECLARE_bool(is_control_test_mode); +DECLARE_bool(use_preview_speed_for_table); + +DECLARE_bool(enable_input_timestamp_check); + +DECLARE_int32(max_localization_miss_num); +DECLARE_int32(max_chassis_miss_num); +DECLARE_int32(max_planning_miss_num); + +DECLARE_double(max_acceleration_when_stopped); +DECLARE_double(max_abs_speed_when_stopped); + +DECLARE_double(steer_angle_rate); + +#endif // MODULES_CONTROL_COMMON_CONTROL_GFLAGS_H_ diff --git a/apollo_control/include/apollo_control/common/definitions.h b/apollo_control/include/apollo_control/common/definitions.h new file mode 100644 index 0000000..784116e --- /dev/null +++ b/apollo_control/include/apollo_control/common/definitions.h @@ -0,0 +1,52 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_CONTROL_COMMON_DEFINITIONS_H_ +#define MODULES_CONTROL_COMMON_DEFINITIONS_H_ + +#include "apollo_msgs/proto/common/error_code.pb.h" +#include "apollo_common/status/status.h" + +/** + * @namespace apollo::control + * @brief apollo::control + */ +namespace apollo { +namespace control { + +using apollo::common::Status; +using apollo::common::ErrorCode; + +} // namespace control +} // namespace apollo + +#endif // MODULES_CONTROL_COMMON_DEFINITIONS_H_ diff --git a/apollo_control/include/apollo_control/common/hysteresis_filter.h b/apollo_control/include/apollo_control/common/hysteresis_filter.h new file mode 100644 index 0000000..4d4db01 --- /dev/null +++ b/apollo_control/include/apollo_control/common/hysteresis_filter.h @@ -0,0 +1,60 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + */ + +#ifndef MODULES_CONTROL_COMMON_HYSTERESIS_FILTER_H_ +#define MODULES_CONTROL_COMMON_HYSTERESIS_FILTER_H_ + +/** + * @namespace apollo::control + * @brief apollo::control + */ +namespace apollo { +namespace control { + +class HysteresisFilter { + public: + HysteresisFilter() = default; + void filter(const double input_value, const double threshold, + const double hysteresis_upper, const double hysteresis_lower, + int *state, double *output_value); + + private: + int previous_state_ = 0; +}; + +} // namespace control +} // namespace apollo +#endif // MODULES_CONTROL_COMMON_HYSTERESIS_FILTER_H_ diff --git a/apollo_control/include/apollo_control/common/interpolation_2d.h b/apollo_control/include/apollo_control/common/interpolation_2d.h new file mode 100644 index 0000000..0205804 --- /dev/null +++ b/apollo_control/include/apollo_control/common/interpolation_2d.h @@ -0,0 +1,92 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + */ + +#ifndef MODULES_CONTROL_COMMON_INTERPOLATION_2D_H_ +#define MODULES_CONTROL_COMMON_INTERPOLATION_2D_H_ + +#include +#include +#include +#include +#include + +/** + * @namespace apollo::control + * @brief apollo::control + */ +namespace apollo { +namespace control { +/** + * @class Interpolation2D + * + * @brief linear interpolation from key (double, double) to one double value. + */ +class Interpolation2D { + public: + typedef std::vector> DataType; + typedef std::pair KeyType; + + Interpolation2D() = default; + + /** + * @brief initialize Interpolation2D internal table + * @param xyz passing interpolation initialization table data + * @return true if init is ok. + */ + bool Init(const DataType& xyz); + + /** + * @brief linear interpolate from 2D key (double, double) to one double value. + * @param xyz passing interpolation initialization table data + * @return true if init is ok. + */ + double Interpolate(const KeyType& xy) const; + + private: + double InterpolateYz(const std::map& yz_table, + double y) const; + + double InterpolateValue(const double value_before, const double dist_before, + const double value_after, + const double dist_after) const; + + std::map> xyz_; +}; + +} // namespace control +} // namespace apollo + +#endif // MODULES_CONTROL_COMMON_INTERPOLATION_1D_H_ diff --git a/apollo_control/include/apollo_control/common/pid_controller.h b/apollo_control/include/apollo_control/common/pid_controller.h new file mode 100644 index 0000000..44ae629 --- /dev/null +++ b/apollo_control/include/apollo_control/common/pid_controller.h @@ -0,0 +1,118 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file pid_controller.h + * @brief Defines the PIDController class. + */ + +#ifndef MODULES_CONTROL_COMMON_PID_CONTROLLER_H_ +#define MODULES_CONTROL_COMMON_PID_CONTROLLER_H_ + +#include "apollo_msgs/proto/control/lon_controller_conf.pb.h" + +/** + * @namespace apollo::control + * @brief apollo::control + */ +namespace apollo { +namespace control { + +/** + * @class PIDController + * @brief A proportional–integral–derivative controller for speed and steering + */ +class PIDController { + public: + /** + * @brief constructor + */ + PIDController() = default; + + /** + * @brief initialize pid controller + * @param pid_conf configuration for pid controller + */ + void Init(const PidConf &pid_conf); + + /** + * @brief set pid controller coefficients for the proportional, + * integral, and derivative + * @param pid_conf configuration for pid controller + */ + void SetPID(const PidConf &pid_conf); + + /** + * @brief reset variables for pid controller + */ + void Reset(); + + /** + * @brief compute control value based on the error + * @param error error value, the difference between + * a desired value and a measured value + * @param dt sampling time interval + * @return control value based on PID terms + */ + double Control(const double error, const double dt); + + /** + * @brief get saturation status + * @return saturation status + */ + int saturation_status() const; + + /** + * @brief get status that if integrator is hold + * @return if integrator is hold return true + */ + bool integrator_hold() const; + + private: + double kp_ = 0.0; + double ki_ = 0.0; + double kd_ = 0.0; + double previous_error_ = 0.0; + double previous_output_ = 0.0; + double integral_ = 0.0; + double saturation_high_ = 0.0; + double saturation_low_ = 0.0; + bool first_hit_ = false; + bool integrator_enabled_ = false; + bool integrator_hold_ = false; + int saturation_status_ = 0; +}; + +} // namespace control +} // namespace apollo + +#endif // MODULES_CONTROL_COMMON_PID_CONTROLLER_H_ diff --git a/apollo_control/include/apollo_control/common/trajectory_analyzer.h b/apollo_control/include/apollo_control/common/trajectory_analyzer.h new file mode 100644 index 0000000..091f839 --- /dev/null +++ b/apollo_control/include/apollo_control/common/trajectory_analyzer.h @@ -0,0 +1,158 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file trajectory_analyzer.h + * @brief Defines the TrajectoryAnalyzer class. + */ + +#ifndef MODULES_CONTROL_COMMON_TRAJECTORY_ANALYZER_H_ +#define MODULES_CONTROL_COMMON_TRAJECTORY_ANALYZER_H_ + +#include + +#include "apollo_common/vehicle_state/vehicle_state.h" +#include "apollo_msgs/proto/planning/planning.pb.h" + +#include "apollo_control/common/base_types.h" + +/** + * @namespace apollo::control + * @brief apollo::control + */ +namespace apollo { +namespace control { + +/** + * @class TrajectoryAnalyzer + * @brief process point query and conversion related to trajectory + */ +class TrajectoryAnalyzer { + public: + /** + * @brief constructor + */ + TrajectoryAnalyzer() = default; + + /** + * @brief constructor + * @param planning_published_trajectory trajectory data generated by + * planning module + */ + TrajectoryAnalyzer( + const planning::ADCTrajectory* planning_published_trajectory); + + /** + * @brief destructor + */ + ~TrajectoryAnalyzer() = default; + + /** + * @brief get sequence number of the trajecotry + * @return sequence number. + */ + unsigned int seq_num() { return seq_num_; } + + /** + * @brief query a point of trajectery that its absolute time is closest + * to the give time. + * @param t absolute time for query + * @return a point of trajectory + */ + TrajectoryPoint QueryNearestPointByAbsoluteTime(const double t) const; + + /** + * @brief query a point of trajectery that its relative time is closest + * to the give time. The time is relative to the first pointof trajectory + * @param t relative time for query + * @return a point of trajectory + */ + TrajectoryPoint QueryNearestPointByRelativeTime(const double t) const; + + /** + * @brief query a point of trajectery that its position is closest + * to the given position. + * @param x value of x-coordination in the given position + * @param y value of y-coordination in the given position + * @return a point of trajectory + */ + TrajectoryPoint QueryNearestPointByPosition(const double x, + const double y) const; + + /** + * @brief query a point on trajectery that its position is closest + * to the given position. + * @param x value of x-coordination in the given position + * @param y value of y-coordination in the given position + * @return a point on trajectory, the point may be a point of trajectory + * or interpolated by two adjacent points of trajectory + */ + PathPoint QueryMatchedPathPoint(const double x, const double y) const; + + /** + * @brief convert a position with theta and speed to trajectory frame, + * - longitudinal and lateral direction to the trajectory + * @param x x-value of the position + * @param y y-value of the position + * @param theta heading angle on the position + * @param v speed on the position + * @param matched_point matched point on trajectory for the given position + * @param ptr_s longitudinal distance + * @param ptr_s_dot longitudinal speed + * @param ptr_d lateral distance + * @param ptr_d_dot lateral speed + */ + void ToTrajectoryFrame(const double x, const double y, const double theta, + const double v, const PathPoint& matched_point, + double* ptr_s, double* ptr_s_dot, double* ptr_d, + double* ptr_d_dot) const; + + /** + * @brief get all points of the trajectory + * @return a vector of trajectory points + */ + const std::vector& trajectory_points() const; + + private: + PathPoint FindMinDistancePoint(const PathPoint& p0, const PathPoint& p1, + const double x, const double y) const; + + std::vector trajectory_points_; + + double header_time_ = 0.0; + unsigned int seq_num_ = 0; +}; + +} // namespace control +} // namespace apollo + +#endif /* MODULES_CONTROL_COMMON_TRAJECTORY_ANALYZER_H_ */ diff --git a/apollo_control/include/apollo_control/control.h b/apollo_control/include/apollo_control/control.h new file mode 100644 index 0000000..dba58aa --- /dev/null +++ b/apollo_control/include/apollo_control/control.h @@ -0,0 +1,148 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef CONTROL_CONTROL_H_ +#define CONTROL_CONTROL_H_ + +#include +#include +#include +#include + +#include +#include + +#include "apollo_msgs/proto/canbus/chassis.pb.h" +#include "apollo_msgs/proto/common/monitor.pb.h" +#include "apollo_msgs/proto/planning/planning.pb.h" +#include "apollo_msgs/proto/control/control_cmd.pb.h" +#include "apollo_msgs/proto/control/control_conf.pb.h" +#include "apollo_msgs/proto/control/pad_msg.pb.h" + +#include "apollo_common/apollo_app.h" +#include "apollo_common/monitor/monitor.h" +#include "apollo_common/util/util.h" +#include "apollo_control/controller/controller_agent.h" + +/** + * @namespace apollo::control + * @brief apollo::control + */ +namespace apollo { +namespace control { + +/** + * @class Control + * + * @brief control module main class, it processes localization, chasiss, and + * pad data to compute throttle, brake and steer values. + */ +class Control : public apollo::common::ApolloApp { + friend class ControlTestBase; + + public: + Control() : monitor_(apollo::common::monitor::MonitorMessageItem::CONTROL) {} + + /** + * @brief module name + */ + std::string Name() const override; + + /** + * @brief module initialization function + * @return initialization status + */ + apollo::common::Status Init() override; + + /** + * @brief module start function + * @return start status + */ + apollo::common::Status Start() override; + + /** + * @brief module stop function + */ + void Stop() override; + + /** + * @brief destructor + */ + virtual ~Control() = default; + + private: + // Upon receiving pad message + void OnPad(const apollo::control::PadMessage& pad); + + // Upon receiving monitor message + void OnMonitor( + const apollo::common::monitor::MonitorMessage& monitor_message); + + // Watch dog timer + void OnTimer(const ros::TimerEvent&); + + Status ProduceControlCommand(ControlCommand* control_command); + Status CheckInput(); + Status CheckTimestamp(); + Status CheckPad(); + + void Alert(); + void SendCmd(ControlCommand* control_command); + + private: + ::apollo::localization::LocalizationEstimate localization_; + ::apollo::canbus::Chassis chassis_; + ::apollo::planning::ADCTrajectory trajectory_; + ::apollo::control::PadMessage pad_msg_; + + ControllerAgent controller_agent_; + + bool estop_ = false; + bool pad_received_ = false; + + unsigned int status_lost_ = 0; + unsigned int status_sanity_check_failed_ = 0; + unsigned int total_status_lost_ = 0; + unsigned int total_status_sanity_check_failed_ = 0; + + double last_alert_timestamp_ = 0.0; + + ControlConf control_conf_; + + apollo::common::monitor::Monitor monitor_; + ros::Timer timer_; +}; + +} // namespace control +} // namespace apollo + +#endif // CONTROL_CONTROL_H_ diff --git a/apollo_control/include/apollo_control/controller/controller.h b/apollo_control/include/apollo_control/controller/controller.h new file mode 100644 index 0000000..90ff08a --- /dev/null +++ b/apollo_control/include/apollo_control/controller/controller.h @@ -0,0 +1,119 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the Controller base class. + */ + +#ifndef MODULES_CONTROL_CONTROLLER_CONTROLLER_H_ +#define MODULES_CONTROL_CONTROLLER_CONTROLLER_H_ + +#include +#include + +#include "apollo_msgs/proto/canbus/chassis.pb.h" +#include "apollo_msgs/proto/localization/localization.pb.h" +#include "apollo_msgs/proto/planning/planning.pb.h" +#include "apollo_msgs/proto/control/control_cmd.pb.h" +#include "apollo_msgs/proto/control/control_conf.pb.h" + +#include "apollo_control/common/definitions.h" + +/** + * @namespace apollo::control + * @brief apollo::control + */ +namespace apollo { +namespace control { + +/** + * @class Controller + * + * @brief base class for all controllers. + */ +class Controller { + public: + /** + * @brief constructor + */ + Controller() = default; + + /** + * @brief destructor + */ + virtual ~Controller() = default; + + /** + * @brief initialize Controller + * @param control_conf control configurations + * @return Status initialization status + */ + virtual Status Init(const ControlConf *control_conf) = 0; + + /** + * @brief compute control command based on current vehicle status + * and target trajectory + * @param localization vehicle location + * @param chassis vehicle status e.g., speed, acceleration + * @param trajectory trajectory generated by planning + * @param cmd control command + * @return Status computation status + */ + virtual Status ComputeControlCommand( + const ::apollo::localization::LocalizationEstimate *localization, + const ::apollo::canbus::Chassis *chassis, + const ::apollo::planning::ADCTrajectory *trajectory, + ::apollo::control::ControlCommand *cmd) = 0; + + /** + * @brief reset Controller + * @return Status reset status + */ + virtual Status Reset() = 0; + + /** + * @brief controller name + * @return string controller name in string + */ + virtual std::string Name() const = 0; + + /** + * @brief stop controller + */ + virtual void Stop() = 0; +}; + +} // namespace control +} // namespace apollo + +#endif // MODULES_CONTROL_CONTROLLER_CONTROLLER_H_ diff --git a/apollo_control/include/apollo_control/controller/controller_agent.h b/apollo_control/include/apollo_control/controller/controller_agent.h new file mode 100644 index 0000000..5d19cc9 --- /dev/null +++ b/apollo_control/include/apollo_control/controller/controller_agent.h @@ -0,0 +1,115 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the ControllerAgent class. + */ + +#ifndef MODULES_CONTROL_CONTROLLER_CONTROLLER_AGENT_H_ +#define MODULES_CONTROL_CONTROLLER_CONTROLLER_AGENT_H_ + +#include +#include +#include + +#include + +#include "apollo_common/util/factory.h" +#include "apollo_msgs/proto/planning/planning.pb.h" +#include "apollo_msgs/proto/control/control_cmd.pb.h" +#include "apollo_msgs/proto/control/control_conf.pb.h" + +#include "apollo_control/controller/controller.h" + +/** + * @namespace apollo::control + * @brief apollo::control + */ +namespace apollo { +namespace control { + +/** + * @class ControllerAgent + * + * @brief manage all controllers declared in control config file. + */ +class ControllerAgent { + public: + /** + * @brief initialize ControllerAgent + * @param control_conf control configurations + * @return Status initialization status + */ + Status Init(const ControlConf *control_conf); + + /** + * @brief compute control command based on current vehicle status + * and target trajectory + * @param localization vehicle location + * @param chassis vehicle status e.g., speed, acceleration + * @param trajectory trajectory generated by planning + * @param cmd control command + * @return Status computation status + */ + Status ComputeControlCommand( + const ::apollo::localization::LocalizationEstimate *localization, + const ::apollo::canbus::Chassis *chassis, + const ::apollo::planning::ADCTrajectory *trajectory, + ::apollo::control::ControlCommand *cmd); + + /** + * @brief reset ControllerAgent + * @return Status reset status + */ + Status Reset(); + + private: + /** + * @brief + * Register new controllers. If you need to add a new type of controller, + * You should first register your controller in this function. + */ + void RegisterControllers(); + + Status InitializeConf(const ControlConf *control_conf); + + const ControlConf *control_conf_ = nullptr; + apollo::common::util::Factory + controller_factory_; + std::vector> controller_list_; +}; + +} // namespace control +} // namespace apollo + +#endif // MODULES_CONTROL_CONTROLLER_CONTROLLER_AGENT_H_ diff --git a/apollo_control/include/apollo_control/controller/lat_controller.h b/apollo_control/include/apollo_control/controller/lat_controller.h new file mode 100644 index 0000000..48c31ce --- /dev/null +++ b/apollo_control/include/apollo_control/controller/lat_controller.h @@ -0,0 +1,234 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the LatController class. + */ + +#ifndef MODULES_CONTROL_CONTROLLER_LAT_CONTROLLER_H_ +#define MODULES_CONTROL_CONTROLLER_LAT_CONTROLLER_H_ + +#include +#include + +#include "apollo_control/common/definitions.h" +#include "apollo_control/common/trajectory_analyzer.h" +#include "apollo_control/controller/controller.h" +#include "apollo_control/filters/digital_filter.h" +#include "apollo_control/filters/digital_filter_coefficients.h" +#include "apollo_control/filters/mean_filter.h" + +/** + * @namespace apollo::control + * @brief apollo::control + */ +namespace apollo { +namespace control { + +/** + * @class LatController + * + * @brief Lateral controller, to compute steering target. + */ +class LatController : public Controller { + public: + /** + * @brief constructor + */ + LatController(); + + /** + * @brief destructor + */ + virtual ~LatController(); + + /** + * @brief initialize Lateral Controller + * @param control_conf control configurations + * @return Status initialization status + */ + Status Init(const ControlConf* control_conf) override; + + /** + * @brief compute steering target based on current vehicle status + * and target trajectory + * @param localization vehicle location + * @param chassis vehicle status e.g., speed, acceleration + * @param trajectory trajectory generated by planning + * @param cmd control command + * @return Status computation status + */ + Status ComputeControlCommand( + const localization::LocalizationEstimate* localization, + const canbus::Chassis* chassis, const planning::ADCTrajectory* trajectory, + ControlCommand* cmd) override; + + /** + * @brief reset Lateral Controller + * @return Status reset status + */ + Status Reset() override; + + /** + * @brief stop Lateral controller + */ + void Stop() override; + + /** + * @brief Lateral controller name + * @return string controller name in string + */ + std::string Name() const override; + + protected: + void UpdateState(SimpleLateralDebug* debug); + + void UpdateStateAnalyticalMatching(SimpleLateralDebug* debug); + + void UpdateMatrix(); + + void UpdateMatrixCompound(); + + double ComputeFeedForward(double ref_curvature) const; + + double GetLateralError(const Eigen::Vector2d& point, + TrajectoryPoint* trajectory_point) const; + + void ComputeLateralErrors(const double x, const double y, const double theta, + const double linear_v, const double angular_v, + const TrajectoryAnalyzer& trajectory_analyzer, + SimpleLateralDebug* debug) const; + bool LoadControlConf(const ControlConf* control_conf); + void InitializeFilters(const ControlConf* control_conf); + void LogInitParameters(); + void ProcessLogs(const SimpleLateralDebug* debug, + const canbus::Chassis* chassis); + + void CloseLogFile(); + + // a proxy to access vehicle movement state + ::apollo::common::vehicle_state::VehicleState vehicle_state_; + + // a proxy to analyze the planning trajectory + TrajectoryAnalyzer trajectory_analyzer_; + + // the following parameters are vehicle physics related. + // control time interval + double ts_ = 0.0; + // corner stiffness; front + double cf_ = 0.0; + // corner stiffness; rear + double cr_ = 0.0; + // distance between front and rear wheel center + double wheelbase_ = 0.0; + // mass of the vehicle + double mass_ = 0.0; + // distance from front wheel center to COM + double lf_ = 0.0; + // distance from rear wheel center to COM + double lr_ = 0.0; + // rotational inertia + double iz_ = 0.0; + // the ratio between the turn of the steering wheel and the turn of the wheels + double steer_transmission_ratio_ = 0.0; + // the maximum turn of steer + double steer_single_direction_max_degree_ = 0.0; + + // number of control cycles look ahead (preview controller) + int preview_window_ = 0; + // number of states without previews, includes + // lateral error, lateral error rate, heading error, heading error rate + const int basic_state_size_ = 4; + // vehicle state matrix + Eigen::MatrixXd matrix_a_; + // vehicle state matrix (discrete-time) + Eigen::MatrixXd matrix_ad_; + // vehicle state matrix compound; related to preview + Eigen::MatrixXd matrix_adc_; + // control matrix + Eigen::MatrixXd matrix_b_; + // control matrix (discrete-time) + Eigen::MatrixXd matrix_bd_; + // control matrix compound + Eigen::MatrixXd matrix_bdc_; + // gain matrix + Eigen::MatrixXd matrix_k_; + // control authority weighting matrix + Eigen::MatrixXd matrix_r_; + // state weighting matrix + Eigen::MatrixXd matrix_q_; + // vehicle state matrix coefficients + Eigen::MatrixXd matrix_a_coeff_; + // 4 by 1 matrix; state matrix + Eigen::MatrixXd matrix_state_; + + // heading error + // double heading_error_ = 0.0; + // lateral distance to reference trajectory + // double lateral_error_ = 0.0; + + // reference heading + // double ref_heading_ = 0.0; + // reference trajectory curvature + // double ref_curvature_ = 0.0; + + // heading error of last control cycle + double previous_heading_error_ = 0.0; + // lateral distance to reference trajectory of last control cycle + double previous_lateral_error_ = 0.0; + + // heading error change rate over time, i.e. d(heading_error) / dt + // double heading_error_rate_ = 0.0; + // lateral error change rate over time, i.e. d(lateral_error) / dt + // double lateral_error_rate_ = 0.0; + + // parameters for lqr solver; number of iterations + int lqr_max_iteration_ = 0; + // parameters for lqr solver; threshold for computation + double lqr_eps_ = 0.0; + + DigitalFilter digital_filter_; + + // MeanFilter heading_rate_filter_; + MeanFilter lateral_error_filter_; + + // for logging purpose + std::ofstream steer_log_file_; + + const std::string name_; +}; + +} // namespace control +} // namespace apollo + +#endif // MODULES_CONTROL_CONTROLLER_LATERAL_CONTROLLER_H_ diff --git a/apollo_control/include/apollo_control/controller/lon_controller.h b/apollo_control/include/apollo_control/controller/lon_controller.h new file mode 100644 index 0000000..4ff9af9 --- /dev/null +++ b/apollo_control/include/apollo_control/controller/lon_controller.h @@ -0,0 +1,164 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the LonController class. + */ + +#ifndef MODULES_CONTROL_CONTROLLER_LON_CONTROLLER_H_ +#define MODULES_CONTROL_CONTROLLER_LON_CONTROLLER_H_ + +#include +#include +#include +#include + +#include "apollo_common/vehicle_state/vehicle_state.h" +#include "apollo_control/common/definitions.h" +#include "apollo_control/common/interpolation_2d.h" +#include "apollo_control/common/pid_controller.h" +#include "apollo_control/common/trajectory_analyzer.h" +#include "apollo_control/controller/controller.h" +#include "apollo_control/filters/digital_filter.h" +#include "apollo_control/filters/digital_filter_coefficients.h" + +/** + * @namespace apollo::control + * @brief apollo::control + */ +namespace apollo { +namespace control { + +/** + * @class LonController + * + * @brief Longitudinal controller, to compute brake / throttle values. + */ +class LonController : public Controller { + public: + /** + * @brief constructor + */ + LonController(); + + /** + * @brief destructor + */ + virtual ~LonController(); + + /** + * @brief initialize Longitudinal Controller + * @param control_conf control configurations + * @return Status initialization status + */ + Status Init(const ControlConf *control_conf) override; + + /** + * @brief compute brake / throttle values based on current vehicle status + * and target trajectory + * @param localization vehicle location + * @param chassis vehicle status e.g., speed, acceleration + * @param trajectory trajectory generated by planning + * @param cmd control command + * @return Status computation status + */ + Status ComputeControlCommand( + const ::apollo::localization::LocalizationEstimate *localization, + const ::apollo::canbus::Chassis *chassis, + const ::apollo::planning::ADCTrajectory *trajectory, + ::apollo::control::ControlCommand *cmd) override; + + /** + * @brief reset longitudinal controller + * @return Status reset status + */ + Status Reset() override; + + /** + * @brief stop longitudinal controller + */ + void Stop() override; + + /** + * @brief longitudinal controller name + * @return string controller name in string + */ + std::string Name() const override; + + protected: + void ComputeLongitudinalErrors( + const ::apollo::common::vehicle_state::VehicleState &vehicle_state, + const TrajectoryAnalyzer *trajectory, const double preview_time, + SimpleLongitudinalDebug *debug); + + private: + void SetDigitalFilterAcceleration( + const LonControllerConf &lon_controller_conf); + + void SetDigitalFilterThrottle(const LonControllerConf &lon_controller_conf); + + void SetDigitalFilterBrake(const LonControllerConf &lon_controller_conf); + + void LoadControlCalibrationTable( + const LonControllerConf &lon_controller_conf); + + void SetDigitalFilter(double ts, double cutoff_freq, + DigitalFilter *digital_filter); + + void CloseLogFile(); + + const ::apollo::localization::LocalizationEstimate *localization_ = nullptr; + const ::apollo::canbus::Chassis *chassis_ = nullptr; + ::apollo::common::vehicle_state::VehicleState vehicle_state_; + + std::unique_ptr control_interpolation_; + const ::apollo::planning::ADCTrajectory *trajectory_message_ = nullptr; + std::unique_ptr trajectory_analyzer_; + + std::string name_; + bool controller_initialized_ = false; + + PIDController speed_pid_controller_; + PIDController station_pid_controller_; + + FILE *speed_log_file_ = nullptr; + + DigitalFilter digital_filter_throttle_; + DigitalFilter digital_filter_brake_; + DigitalFilter digital_filter_acceleration_; + + const ControlConf *control_conf_ = nullptr; +}; +} // namespace control +} // namespace apollo +#endif // MODULES_CONTROL_CONTROLLER_LONGITUDINAL_CONTROLLER_H_ diff --git a/apollo_control/include/apollo_control/filters/digital_filter.h b/apollo_control/include/apollo_control/filters/digital_filter.h new file mode 100644 index 0000000..fca6656 --- /dev/null +++ b/apollo_control/include/apollo_control/filters/digital_filter.h @@ -0,0 +1,171 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the DigitalFilter class. + */ + +#ifndef MODULES_CONTROL_FILTERS_DIGITAL_FILTER_H_ +#define MODULES_CONTROL_FILTERS_DIGITAL_FILTER_H_ + +#include +#include + +/** + * @namespace apollo::control + * @brief apollo::control + */ +namespace apollo { +namespace control { + +/** + * @class DigitalFilter + * @brief The DigitalFilter class is used to pass signals with a frequency + * lower than a certain cutoff frequency and attenuates signals with + * frequencies higher than the cutoff frequency. + */ +class DigitalFilter { + public: + DigitalFilter() = default; + + /** + * @brief Initializes a DigitalFilter with given denominators and numerators. + * @param denominators The denominators of the DigitalFilter. + * @param numerators The numerators of the DigitalFilter. + */ + DigitalFilter(const std::vector& denominators, + const std::vector& numerators); + + /** + * @brief Default destructor. + */ + ~DigitalFilter() = default; + + /** + * @brief Processes a new measurement with the filter. + * @param x_insert The new input to be processed by the filter. + */ + double Filter(const double x_insert); + /** + * @desc: Filter by the input x_insert + * Input: new value of x_insert + * Remove x[n - 1], insert x_insert into x[0] + * Remove y[n - 1], + * Solve den[0] * y + den[1] * y[0] + ... + den[n - 1]*y[n - 2] = + * num[0] * x[0] + num[1] * x[1] + ... + num[n - 1] * x[n - 1] for y + * Insert y into y[0] + * Output: y[0] + */ + + /** + * @brief set denominators by an input vector + * @param denominators The denominators of filter + */ + void set_denominators(const std::vector& denominators); + + /** + * @brief set numerators by an input vector + * @param numerators The numerators of filter + */ + void set_numerators(const std::vector& numerators); + + /** + * @brief set denominators and numerators + * @param denominators The denominators of filter + * @param numerators The numerators of filter + */ + void set_coefficients(const std::vector& denominators, + const std::vector& numerators); + + /** + * @brief set filter deadzone + * @param deadzone The value of deadzone + */ + void set_dead_zone(const double deadzone); + + /** + * @brief get denominators + * @return vector The denominators of filter + */ + const std::vector& denominators() const; + + /** + * @brief get numerators + * @return vector The numerators of filter + */ + const std::vector& numerators() const; + + /** + * @brief get dead_zone + * @return double The dead_zone + */ + double dead_zone() const; + + private: + /** + * @desc: Update the last-filtered value, + * if the difference is less than dead_zone_ + */ + double UpdateLast(const double input); + + /** + * @desc: Compute the inner product of values[coeff_start : coeff_end] and + * coefficients[coeff_start : coeff_end] + */ + double Compute(const std::deque& values, + const std::vector& coefficients, + const std::size_t coeff_start, const std::size_t coeff_end); + + // Front is latest, back is oldest. + std::deque x_values_; + + // Front is latest, back is oldest. + std::deque y_values_; + + // Coefficients with y values + std::vector denominators_; + + // Coefficients with x values + std::vector numerators_; + + // threshold of updating last-filtered value + double dead_zone_ = 0.0; + + // last-filtered value + double last_ = 0.0; +}; + +} // namespace control +} // namespace apollo + +#endif /* MODULES_CONTROL_FILTERS_DIGITAL_FILTER_H_ */ diff --git a/apollo_control/include/apollo_control/filters/digital_filter_coefficients.h b/apollo_control/include/apollo_control/filters/digital_filter_coefficients.h new file mode 100644 index 0000000..d8df2f1 --- /dev/null +++ b/apollo_control/include/apollo_control/filters/digital_filter_coefficients.h @@ -0,0 +1,64 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file digital_filter_coefficients.h + * @brief Functions to generate coefficients for digital filter. + */ + +#ifndef MODULES_CONTROL_FILTERS_DIGITAL_FILTER_COEFFICIENTS_H_ +#define MODULES_CONTROL_FILTERS_DIGITAL_FILTER_COEFFICIENTS_H_ + +#include + +/** + * @namespace apollo::control + * @brief apollo::control + */ +namespace apollo { +namespace control { + +/** + * @brief Get low-pass coefficients for digital filter. + * @param ts Time interval between signals. + * @param cutoff_freq Cutoff of frequency to filter high-frequency signals out. + * @param denominators Denominator coefficients for digital filter. + * @param numerators Numerator coefficients for digital filter. + */ +void LpfCoefficients(const double ts, const double cutoff_freq, + std::vector *denominators, + std::vector *numerators); + +} // namespace control +} // namespace apollo + +#endif // MODULES_CONTROL_FILTERS_DIGITAL_FILTER_COEFFICIENTS_H_ diff --git a/apollo_control/include/apollo_control/filters/mean_filter.h b/apollo_control/include/apollo_control/filters/mean_filter.h new file mode 100644 index 0000000..ccf7d86 --- /dev/null +++ b/apollo_control/include/apollo_control/filters/mean_filter.h @@ -0,0 +1,105 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file + * @brief Defines the MeanFilter class. + */ + +#ifndef MODULES_CONTROL_FILTERS_MEAN_FILTER_H_ +#define MODULES_CONTROL_FILTERS_MEAN_FILTER_H_ + +#include +#include +#include +#include + +/** + * @namespace apollo::control + * @brief The apollo::control namespace contains the code of the control module. + */ +namespace apollo { +namespace control { + +/** + * @class MeanFilter + * @brief The MeanFilter class is used to smoothen a series of noisy numbers, + * such as sensor data or the output of a function that we wish to be smoother. + * + * This is achieved by keeping track of the last k measurements + * (where k is the window size), and returning the average of all but the + * minimum and maximum measurements, which are likely to be outliers. + */ +class MeanFilter { + public: + /** + * @brief Initializes a MeanFilter with a given window size. + * @param window_size The window size of the MeanFilter. + * Older measurements are discarded. + */ + explicit MeanFilter(const std::uint_fast8_t window_size); + /** + * @brief Default constructor; defers initialization. + */ + MeanFilter() = default; + /** + * @brief Default destructor. + */ + ~MeanFilter() = default; + /** + * @brief Processes a new measurement in amortized constant time. + * @param measurement The measurement to be processed by the filter. + */ + double Update(const double measurement); + + private: + void RemoveEarliest(); + void Insert(const double value); + double GetMin() const; + double GetMax() const; + bool ShouldPopOldestCandidate(const std::uint_fast8_t old_time) const; + std::uint_fast8_t window_size_ = 0; + double sum_ = 0.0; + std::uint_fast8_t time_ = 0; + // front = earliest + std::deque values_; + // front = min + std::deque> min_candidates_; + // front = max + std::deque> max_candidates_; + bool initialized_ = false; +}; + +} // namespace control +} // namespace apollo + +#endif // MODULES_CONTROL_FILTERS_MEAN_FILTER_H_ diff --git a/apollo_control/launch/control.launch b/apollo_control/launch/control.launch new file mode 100644 index 0000000..46a97a2 --- /dev/null +++ b/apollo_control/launch/control.launch @@ -0,0 +1,8 @@ + + + + \ No newline at end of file diff --git a/apollo_control/package.xml b/apollo_control/package.xml new file mode 100644 index 0000000..3335437 --- /dev/null +++ b/apollo_control/package.xml @@ -0,0 +1,29 @@ + + + apollo_control + 0.0.0 + The apollo_control package + + forrest + TODO + + catkin + + roscpp + roscpp + roscpp + + apollo_msgs + apollo_msgs + apollo_msgs + + apollo_common + apollo_common + apollo_common + + + + + + + diff --git a/apollo_control/src/common/control_gflags.cc b/apollo_control/src/common/control_gflags.cc new file mode 100644 index 0000000..d4a7334 --- /dev/null +++ b/apollo_control/src/common/control_gflags.cc @@ -0,0 +1,64 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_control/common/control_gflags.h" + +DEFINE_double(min_alert_interval, 1., + "minimum alert interval to prevent alerting too frequently."); +DEFINE_string(control_conf_file, "modules/control/conf/lincoln.pb.txt", + "default control conf data file"); +DEFINE_bool(enable_csv_debug, false, "True to write out csv debug file."); +DEFINE_bool(use_state_exact_match, false, + "whether use state exact match in lateral controller"); +DEFINE_bool(enable_speed_station_preview, true, "enable speed/station preview"); +DEFINE_bool(enable_control_watchdog, true, "True to enable control watchdog"); +DEFINE_string(node_name, "control", "The control node name in proto"); +DEFINE_bool(is_control_test_mode, false, "True to run control in test mode"); +DEFINE_bool(use_preview_speed_for_table, false, + "True to use preview speed for table lookup"); + +DEFINE_bool(enable_input_timestamp_check, true, + "True to enable input timestamp delay check"); + +DEFINE_int32(max_localization_miss_num, 20, + "Max missing number of localization before entering estop mode"); +DEFINE_int32(max_chassis_miss_num, 20, + "Max missing number of chassis before entering estop mode"); +DEFINE_int32(max_planning_miss_num, 20, + "Max missing number of planning before entering estop mode"); + +DEFINE_double(max_acceleration_when_stopped, 0.01, + "max acceleration can be observed when vehicle is stopped"); +DEFINE_double(max_abs_speed_when_stopped, 0.01, + "max absolute speed can be observed when vehicle is stopped"); +DEFINE_double(steer_angle_rate, 100.0, + "Steer angle change rate in percentage."); diff --git a/apollo_control/src/common/hysteresis_filter.cc b/apollo_control/src/common/hysteresis_filter.cc new file mode 100644 index 0000000..eb20132 --- /dev/null +++ b/apollo_control/src/common/hysteresis_filter.cc @@ -0,0 +1,59 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_control/common/hysteresis_filter.h" + +namespace apollo { +namespace control { + +void HysteresisFilter::filter(const double input_value, const double threshold, + const double hysteresis_upper, + const double hysteresis_lower, int *state, + double *output_value) { + // Use integer to represent mode as of now, for instance, + // 1 is throttle, 0 is brake, then threshold is speed error + if (input_value > threshold + hysteresis_upper) { + *state = 1; + previous_state_ = *state; + *output_value = threshold + hysteresis_upper; + } else if (input_value < threshold - hysteresis_lower) { + *state = 0; + previous_state_ = *state; + *output_value = threshold - hysteresis_lower; + } else { + *state = previous_state_; + *output_value = input_value; + } +} + +} // namespace control +} // namespace apollo diff --git a/apollo_control/src/common/interpolation_2d.cc b/apollo_control/src/common/interpolation_2d.cc new file mode 100644 index 0000000..cb97a30 --- /dev/null +++ b/apollo_control/src/common/interpolation_2d.cc @@ -0,0 +1,126 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_control/common/interpolation_2d.h" + +#include + +#include "apollo_common/log.h" + +namespace { + +const double kDoubleEpsilon = 1.0e-6; + +} // namespace + +namespace apollo { +namespace control { + +bool Interpolation2D::Init(const DataType& xyz) { + if (xyz.empty()) { + AERROR << "empty input."; + return false; + } + for (const auto& t : xyz) { + xyz_[std::get<0>(t)][std::get<1>(t)] = std::get<2>(t); + } + return true; +} + +double Interpolation2D::Interpolate(const KeyType& xy) const { + double max_x = xyz_.rbegin()->first; + double min_x = xyz_.begin()->first; + if (xy.first >= max_x - kDoubleEpsilon) { + return InterpolateYz(xyz_.rbegin()->second, xy.second); + } + if (xy.first <= min_x + kDoubleEpsilon) { + return InterpolateYz(xyz_.begin()->second, xy.second); + } + + auto itr_after = xyz_.lower_bound(xy.first); + auto itr_before = itr_after; + --itr_before; + + double x_before = itr_before->first; + double z_before = InterpolateYz(itr_before->second, xy.second); + double x_after = itr_after->first; + double z_after = InterpolateYz(itr_after->second, xy.second); + + double x_diff_before = std::fabs(xy.first - x_before); + double x_diff_after = std::fabs(xy.first - x_after); + + return InterpolateValue(z_before, x_diff_before, z_after, x_diff_after); +} + +double Interpolation2D::InterpolateYz(const std::map& yz_table, + double y) const { + double max_y = yz_table.rbegin()->first; + double min_y = yz_table.begin()->first; + if (y >= max_y - kDoubleEpsilon) { + return yz_table.rbegin()->second; + } + if (y <= min_y + kDoubleEpsilon) { + return yz_table.begin()->second; + } + + auto itr_after = yz_table.lower_bound(y); + auto itr_before = itr_after; + --itr_before; + + double y_before = itr_before->first; + double z_before = itr_before->second; + double y_after = itr_after->first; + double z_after = itr_after->second; + + double y_diff_before = std::fabs(y - y_before); + double y_diff_after = std::fabs(y - y_after); + + return InterpolateValue(z_before, y_diff_before, z_after, y_diff_after); +} + +double Interpolation2D::InterpolateValue(const double value_before, + const double dist_before, + const double value_after, + const double dist_after) const { + if (dist_before < kDoubleEpsilon) { + return value_before; + } + if (dist_after < kDoubleEpsilon) { + return value_after; + } + double value_gap = value_after - value_before; + double value_buff = value_gap * dist_before / (dist_before + dist_after); + return value_before + value_buff; +} + +} // namespace control +} // namespace apollo diff --git a/apollo_control/src/common/pid_controller.cc b/apollo_control/src/common/pid_controller.cc new file mode 100644 index 0000000..3526388 --- /dev/null +++ b/apollo_control/src/common/pid_controller.cc @@ -0,0 +1,109 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_control/common/pid_controller.h" + +#include + +#include "apollo_common/log.h" + +namespace apollo { +namespace control { + +double PIDController::Control(const double error, const double dt) { + if (dt <= 0) { + AWARN << "dt <= 0, will use the last output"; + return previous_output_; + } + double diff = 0; + double output = 0; + + if (first_hit_) { + first_hit_ = false; + } else { + diff = (error - previous_error_) / dt; + } + // integral handling + if (!integrator_enabled_) { + integral_ = 0; + } else if (integrator_enabled_ && !integrator_hold_) { + integral_ += error * dt * ki_; + // apply Ki before integrating to avoid steps when change Ki at steady state + if (integral_ > saturation_high_) { + integral_ = saturation_high_; + saturation_status_ = 1; + } else if (integral_ < saturation_low_) { + integral_ = saturation_low_; + saturation_status_ = -1; + } else { + saturation_status_ = 0; + } + } + previous_error_ = error; + output = error * kp_ + integral_ + diff * kd_; // Ki already applied + previous_output_ = output; + return output; +} + +void PIDController::Reset() { + previous_error_ = 0.0; + previous_output_ = 0.0; + integral_ = 0.0; + first_hit_ = true; +} + +void PIDController::Init(const PidConf &pid_conf) { + previous_error_ = 0.0; + previous_output_ = 0.0; + integral_ = 0.0; + first_hit_ = true; + integrator_enabled_ = pid_conf.integrator_enable(); + saturation_high_ = std::fabs(pid_conf.integrator_saturation_level()); + saturation_low_ = -std::fabs(pid_conf.integrator_saturation_level()); + saturation_status_ = 0; + integrator_hold_ = false; + + SetPID(pid_conf); +} + +void PIDController::SetPID(const PidConf &pid_conf) { + kp_ = pid_conf.kp(); + ki_ = pid_conf.ki(); + kd_ = pid_conf.kd(); +} + +int PIDController::saturation_status() const { return saturation_status_; } + +bool PIDController::integrator_hold() const { return integrator_hold_; } + +} // namespace control +} // namespace apollo diff --git a/apollo_control/src/common/trajectory_analyzer.cc b/apollo_control/src/common/trajectory_analyzer.cc new file mode 100644 index 0000000..2310210 --- /dev/null +++ b/apollo_control/src/common/trajectory_analyzer.cc @@ -0,0 +1,244 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_control/common/trajectory_analyzer.h" + +#include +#include + +#include "apollo_common/log.h" +#include "apollo_common/math/linear_interpolation.h" +#include "apollo_common/math/math_utils.h" +#include "apollo_common/math/search.h" + +namespace math = ::apollo::common::math; + +namespace apollo { +namespace control { + +TrajectoryAnalyzer::TrajectoryAnalyzer( + const planning::ADCTrajectory* planning_published_trajectory) { + header_time_ = planning_published_trajectory->header().timestamp_sec(); + seq_num_ = planning_published_trajectory->header().sequence_num(); + + int num_points = planning_published_trajectory->adc_trajectory_point_size(); + trajectory_points_.reserve(num_points); + + for (int i = 0; + i < planning_published_trajectory->adc_trajectory_point_size(); ++i) { + const auto& published_trajectory_point = + planning_published_trajectory->adc_trajectory_point(i); + + TrajectoryPoint point; + point.s = published_trajectory_point.accumulated_s(); + point.x = published_trajectory_point.x(); + point.y = published_trajectory_point.y(); + point.theta = published_trajectory_point.theta(); + point.kappa = published_trajectory_point.curvature(); + point.v = published_trajectory_point.speed(); + point.a = published_trajectory_point.acceleration_s(); + point.relative_time = published_trajectory_point.relative_time(); + + trajectory_points_.push_back(std::move(point)); + } +} + +PathPoint TrajectoryAnalyzer::QueryMatchedPathPoint(const double x, + const double y) const { + auto func_distance_square = [](const PathPoint& point, const double x, + const double y) { + double dx = point.x - x; + double dy = point.y - y; + return dx * dx + dy * dy; + }; + + double d_min = func_distance_square(trajectory_points_.front(), x, y); + size_t index_min = 0; + + for (size_t i = 1; i < trajectory_points_.size(); ++i) { + double d_temp = func_distance_square(trajectory_points_[i], x, y); + if (d_temp < d_min) { + d_min = d_temp; + index_min = i; + } + } + + size_t index_start = index_min == 0 ? index_min : index_min - 1; + size_t index_end = + index_min + 1 == trajectory_points_.size() ? index_min : index_min + 1; + + if (index_start == index_end || + common::math::double_compare(trajectory_points_[index_start].s, + trajectory_points_[index_end].s) == 0) { + return trajectory_points_[index_start]; + } + + return FindMinDistancePoint(trajectory_points_[index_start], + trajectory_points_[index_end], x, y); +} + +// reference: Optimal trajectory generation for dynamic street scenarios in a +// Frenét Frame, +// Moritz Werling, Julius Ziegler, Sören Kammel and Sebastian Thrun, ICRA 2010 +// similar to the method in this paper without the assumption the "normal" +// vector +// (from vehicle position to ref_point position) and reference heading are +// perpendicular. +void TrajectoryAnalyzer::ToTrajectoryFrame(const double x, const double y, + const double theta, const double v, + const PathPoint& ref_point, + double* ptr_s, double* ptr_s_dot, + double* ptr_d, + double* ptr_d_dot) const { + double dx = x - ref_point.x; + double dy = y - ref_point.y; + + double cos_ref_theta = std::cos(ref_point.theta); + double sin_ref_theta = std::sin(ref_point.theta); + + // the sin of diff angle between vector (cos_ref_theta, sin_ref_theta) and + // (dx, dy) + double cross_rd_nd = cos_ref_theta * dy - sin_ref_theta * dx; + *ptr_d = cross_rd_nd; + + // the cos of diff angle between vector (cos_ref_theta, sin_ref_theta) and + // (dx, dy) + double dot_rd_nd = dx * cos_ref_theta + dy * sin_ref_theta; + *ptr_s = ref_point.s + dot_rd_nd; + + double delta_theta = theta - ref_point.theta; + double cos_delta_theta = std::cos(delta_theta); + double sin_delta_theta = std::sin(delta_theta); + + *ptr_d_dot = v * sin_delta_theta; + + double one_minus_kappa_r_d = 1 - ref_point.kappa * (*ptr_d); + if (one_minus_kappa_r_d <= 0.0) { + AERROR << "TrajectoryAnalyzer::ToTrajectoryFrame " + "found fatal reference and actual difference. " + "Control output might be unstable:" + << " ref_point.kappa:" << ref_point.kappa + << " ref_point.x:" << ref_point.x << " ref_point.y:" << ref_point.y + << " car x:" << x << " car y:" << y << " *ptr_d:" << *ptr_d + << " one_minus_kappa_r_d:" << one_minus_kappa_r_d; + // currently set to a small value to avoid control crash. + one_minus_kappa_r_d = 0.01; + } + + *ptr_s_dot = v * cos_delta_theta / one_minus_kappa_r_d; +} + +TrajectoryPoint TrajectoryAnalyzer::QueryNearestPointByAbsoluteTime( + const double t) const { + return QueryNearestPointByRelativeTime(t - header_time_); +} + +TrajectoryPoint TrajectoryAnalyzer::QueryNearestPointByRelativeTime( + const double t) const { + auto func_comp = [](const TrajectoryPoint& point, + const double relative_time) { + return point.relative_time < relative_time; + }; + + auto it_low = std::lower_bound(trajectory_points_.begin(), + trajectory_points_.end(), t, func_comp); + + if (it_low == trajectory_points_.begin()) { + return trajectory_points_.front(); + } + + if (it_low == trajectory_points_.end()) { + return trajectory_points_.back(); + } + + auto it_lower = it_low - 1; + if (it_low->relative_time - t < t - it_lower->relative_time) { + return *it_low; + } else { + return *it_lower; + } +} + +TrajectoryPoint TrajectoryAnalyzer::QueryNearestPointByPosition( + const double x, const double y) const { + auto func_distance_square = [](const PathPoint& point, const double x, + const double y) { + double dx = point.x - x; + double dy = point.y - y; + return dx * dx + dy * dy; + }; + + double d_min = func_distance_square(trajectory_points_.front(), x, y); + size_t index_min = 0; + + for (size_t i = 1; i < trajectory_points_.size(); ++i) { + double d_temp = func_distance_square(trajectory_points_[i], x, y); + if (d_temp < d_min) { + d_min = d_temp; + index_min = i; + } + } + return trajectory_points_[index_min]; +} + +const std::vector& TrajectoryAnalyzer::trajectory_points() + const { + return trajectory_points_; +} + +PathPoint TrajectoryAnalyzer::FindMinDistancePoint(const PathPoint& p0, + const PathPoint& p1, + const double x, + const double y) const { + // given the fact that the discretized trajectory is dense enough, + // we assume linear trajectory between consecutive trajectory points. + auto dist_square = [&p0, &p1, &x, &y](const double s) { + double px = math::lerp(p0.x, p0.s, p1.x, p1.s, s); + double py = math::lerp(p0.y, p0.s, p1.y, p1.s, s); + double dx = px - x; + double dy = py - y; + return dx * dx + dy * dy; + }; + + PathPoint p = p0; + double s = math::GoldenSectionSearch(dist_square, p0.s, p1.s); + p.s = s; + p.x = math::lerp(p0.x, p0.s, p1.x, p1.s, s); + p.y = math::lerp(p0.y, p0.s, p1.y, p1.s, s); + p.theta = math::slerp(p0.theta, p0.s, p1.theta, p1.s, s); + // approximate the curvature at the intermediate point + p.kappa = math::lerp(p0.kappa, p0.s, p1.kappa, p1.s, s); + return p; +} + +} // namespace control +} // namespace apollo diff --git a/apollo_control/src/control.cc b/apollo_control/src/control.cc new file mode 100644 index 0000000..c2fc6e2 --- /dev/null +++ b/apollo_control/src/control.cc @@ -0,0 +1,331 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ +#include "apollo_control/control.h" + +#include + +#include "apollo_common/adapters/adapter_gflags.h" +#include "apollo_common/adapters/adapter_manager.h" +#include "apollo_common/log.h" +#include "apollo_common/time/time.h" +#include "apollo_msgs/proto/localization/localization.pb.h" + +#include "apollo_control/common/control_gflags.h" + +namespace apollo { +namespace control { + +using ::apollo::canbus::Chassis; +using ::apollo::common::ErrorCode; +using ::apollo::common::Status; +using ::apollo::common::adapter::AdapterManager; +using ::apollo::common::monitor::MonitorMessageItem; +using ::apollo::common::time::Clock; +using ::apollo::localization::LocalizationEstimate; +using ::apollo::planning::ADCTrajectory; + +#define CHECK_PROTO(a, b) \ + if (!a.has_##b()) { \ + AERROR << "PB invalid! [" << #a << "] has NO [" << #b << "]!"; \ + return Status(ErrorCode::CONTROL_COMPUTE_ERROR, \ + #a " missing pb field:" #b); \ + } + +std::string Control::Name() const { return FLAGS_node_name; } + +Status Control::Init() { + AINFO << "Control init, starting ..."; + if (!::apollo::common::util::GetProtoFromFile(FLAGS_control_conf_file, + &control_conf_)) { + return Status( + ErrorCode::CONTROL_INIT_ERROR, + "Unable to load control conf file: " + FLAGS_control_conf_file); + } + + AINFO << "Conf file: " << FLAGS_control_conf_file << " is loaded."; + + AdapterManager::Init(FLAGS_adapter_config_path); + + apollo::common::monitor::MonitorBuffer buffer(&monitor_); + + // set controller + if (!controller_agent_.Init(&control_conf_).ok()) { + std::string error_msg = "Control init controller failed! Stopping..."; + buffer.ERROR(error_msg); + return Status(ErrorCode::CONTROL_INIT_ERROR, error_msg); + } + + // lock it in case for after sub, init_vehicle not ready, but msg trigger + // come + CHECK(AdapterManager::GetLocalization()) + << "Localization is not initialized."; + + CHECK(AdapterManager::GetChassis()) << "Chassis is not initialized."; + + CHECK(AdapterManager::GetPlanningTrajectory()) + << "PlanningTrajectory is not initialized."; + + CHECK(AdapterManager::GetPad()) << "Pad is not initialized."; + + CHECK(AdapterManager::GetControlCommand()) + << "ControlCommand publisher is not initialized."; + + AdapterManager::SetPadCallback(&Control::OnPad, this); + AdapterManager::SetMonitorCallback(&Control::OnMonitor, this); + + return Status::OK(); +} + +Status Control::Start() { + // set initial vehicle state by cmd + // need to sleep, because advertised channel is not ready immediately + // simple test shows a short delay of 80 ms or so + AINFO << "Control resetting vehicle state, sleeping for 1000 ms ..."; + usleep(1000 * 1000); + + // should init_vehicle first, let car enter work status, then use status msg + // trigger control + + AINFO << "Control default driving action is " + << DrivingAction_Name(control_conf_.action()); + pad_msg_.set_action(control_conf_.action()); + + timer_ = AdapterManager::CreateTimer( + ros::Duration(control_conf_.control_period()), &Control::OnTimer, this); + + AINFO << "Control init done!"; + + apollo::common::monitor::MonitorBuffer buffer(&monitor_); + buffer.INFO("control started"); + + return Status::OK(); +} + +void Control::OnPad(const apollo::control::PadMessage& pad) { + pad_msg_ = pad; + AINFO << "Received Pad Msg:" << pad.DebugString(); + + if (!CheckPad().ok()) { + AERROR << "pad message check failed!"; + } + // do something according to pad message + if (pad_msg_.action() == ::apollo::control::DrivingAction::RESET) { + AINFO << "Control received RESET action!"; + estop_ = false; + } + pad_received_ = true; +} + +void Control::OnMonitor( + const apollo::common::monitor::MonitorMessage& monitor_message) { + for (const auto& item : monitor_message.item()) { + if (item.log_level() == MonitorMessageItem::FATAL) { + estop_ = true; + return; + } + } +} + +Status Control::ProduceControlCommand(ControlCommand* control_command) { + Status status = CheckInput(); + // check data + if (!status.ok()) { + AERROR << "Control input data failed: " << status.error_message(); + estop_ = true; + Alert(); + } else { + Status status_ts = CheckTimestamp(); + if (!status_ts.ok()) { + AERROR << "Input messages timeout"; + estop_ = true; + Alert(); + status = status_ts; + } + // estop_的重置是通过pad发送过来的,我们这里进行自动更新 + else { + estop_ = false; + } + } + + // check estop + estop_ = estop_ || trajectory_.estop().is_estop(); + + // if planning set estop, then no control process triggered + if (!estop_) { + if (chassis_.driving_mode() == ::apollo::canbus::Chassis::COMPLETE_MANUAL) { + controller_agent_.Reset(); + AINFO << "Reset Controllers in Manual Mode"; + } + + auto debug = control_command->mutable_debug()->mutable_input_debug(); + debug->mutable_localization_header()->CopyFrom(localization_.header()); + debug->mutable_canbus_header()->CopyFrom(chassis_.header()); + debug->mutable_trajectory_header()->CopyFrom(trajectory_.header()); + + Status status_compute = controller_agent_.ComputeControlCommand( + &localization_, &chassis_, &trajectory_, control_command); + + if (!status_compute.ok()) { + AERROR << "Control main function failed" + << " with localization: " << localization_.ShortDebugString() + << " with chassis: " << chassis_.ShortDebugString() + << " with trajectory: " << trajectory_.ShortDebugString() + << " with cmd: " << control_command->ShortDebugString() + << " status:" << status_compute.error_message(); + estop_ = true; + status = status_compute; + } + } + + if (estop_) { + AWARN << "Estop triggered! No control core method executed!"; + // set Estop command + control_command->set_speed(0); + control_command->set_throttle(0); + control_command->set_brake(control_conf_.soft_estop_brake()); + } + // check signal + if (trajectory_.has_signal()) { + control_command->mutable_signal()->CopyFrom(trajectory_.signal()); + } + return status; +} + +void Control::OnTimer(const ros::TimerEvent&) { + double start_timestamp = apollo::common::time::ToSecond(Clock::Now()); + + ControlCommand control_command; + + control_command.set_gear_location(::apollo::canbus::Chassis::GEAR_DRIVE); + + Status status = ProduceControlCommand(&control_command); + if (!status.ok()) { + AERROR << "Failed to produce control command:" << status.error_message(); + } + + double end_timestamp = apollo::common::time::ToSecond(Clock::Now()); + + if (pad_received_) { + control_command.mutable_pad_msg()->CopyFrom(pad_msg_); + pad_received_ = false; + } + + control_command.mutable_latency_stats()->set_total_time_ms( + (end_timestamp - start_timestamp) * 1000); + AINFO << "control cycle time is: " << (end_timestamp - start_timestamp) * 1000 + << " ms."; + status.Save(control_command.mutable_header()->mutable_status()); + + SendCmd(&control_command); +} + +Status Control::CheckInput() { + AdapterManager::Observe(); + auto localization_adapter = AdapterManager::GetLocalization(); + if (localization_adapter->Empty()) { + AINFO << "No Localization msg yet. "; + return Status(ErrorCode::CONTROL_COMPUTE_ERROR, "No localization msg"); + } + localization_ = localization_adapter->GetLatestObserved(); + ADEBUG << "Received localization:" << localization_.ShortDebugString(); + + auto chassis_adapter = AdapterManager::GetChassis(); + if (chassis_adapter->Empty()) { + AINFO << "No Chassis msg yet. "; + return Status(ErrorCode::CONTROL_COMPUTE_ERROR, "No chassis msg"); + } + chassis_ = chassis_adapter->GetLatestObserved(); + ADEBUG << "Received chassis:" << chassis_.ShortDebugString(); + + auto trajectory_adapter = AdapterManager::GetPlanningTrajectory(); + if (trajectory_adapter->Empty()) { + AINFO << "No planning msg yet. "; + return Status(ErrorCode::CONTROL_COMPUTE_ERROR, "No planning msg"); + } + trajectory_ = trajectory_adapter->GetLatestObserved(); + + return Status::OK(); +} + +Status Control::CheckTimestamp() { + if (!FLAGS_enable_input_timestamp_check || FLAGS_is_control_test_mode) { + ADEBUG << "Skip input timestamp check by gflags."; + return Status::OK(); + } + double current_timestamp = apollo::common::time::ToSecond(Clock::Now()); + double localization_diff = + current_timestamp - localization_.header().timestamp_sec(); + if (localization_diff > + (FLAGS_max_localization_miss_num * control_conf_.localization_period())) { + AERROR << "Localization msg lost for " << std::setprecision(6) + << localization_diff << "s"; + return Status(ErrorCode::CONTROL_COMPUTE_ERROR, "Localization msg timeout"); + } + + double chassis_diff = current_timestamp - chassis_.header().timestamp_sec(); + if (chassis_diff > + (FLAGS_max_chassis_miss_num * control_conf_.chassis_period())) { + AERROR << "Chassis msg lost for " << std::setprecision(6) << chassis_diff + << "s"; + return Status(ErrorCode::CONTROL_COMPUTE_ERROR, "Chassis msg timeout"); + } + + double trajectory_diff = + current_timestamp - trajectory_.header().timestamp_sec(); + if (trajectory_diff > + (FLAGS_max_planning_miss_num * control_conf_.trajectory_period())) { + AERROR << "Trajectory msg lost for " << std::setprecision(6) + << trajectory_diff << "s"; + return Status(ErrorCode::CONTROL_COMPUTE_ERROR, "Trajectory msg timeout"); + } + return Status::OK(); +} + +void Control::SendCmd(ControlCommand* control_command) { + // set header + AdapterManager::FillControlCommandHeader(Name(), + control_command->mutable_header()); + + ADEBUG << control_command->ShortDebugString(); + if (FLAGS_is_control_test_mode) { + ADEBUG << "Skip publish control command in test mode"; + return; + } + AdapterManager::PublishControlCommand(*control_command); +} + +Status Control::CheckPad() { + // CHECK_PROTO(pad_msg_, action) + return Status::OK(); +} + +void Control::Alert() { + // do not alert too frequently + // though "0" means first hit + if (last_alert_timestamp_ > 0. && + (apollo::common::time::ToSecond(Clock::Now()) - last_alert_timestamp_) < + FLAGS_min_alert_interval) { + return; + } + + // update timestamp + last_alert_timestamp_ = apollo::common::time::ToSecond(Clock::Now()); +} + +void Control::Stop() {} + +} // namespace control +} // namespace apollo diff --git a/apollo_control/src/controller/controller_agent.cc b/apollo_control/src/controller/controller_agent.cc new file mode 100644 index 0000000..bf49dc5 --- /dev/null +++ b/apollo_control/src/controller/controller_agent.cc @@ -0,0 +1,124 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_control/controller/controller_agent.h" + +#include + +#include "apollo_common/log.h" +#include "apollo_common/time/time.h" + +#include "apollo_control/controller/lat_controller.h" +#include "apollo_control/controller/lon_controller.h" + +namespace apollo { +namespace control { + +using apollo::common::time::Clock; + +void ControllerAgent::RegisterControllers() { + controller_factory_.Register( + ControlConf::LAT_CONTROLLER, + []() -> Controller * { return new LatController(); }); + controller_factory_.Register( + ControlConf::LON_CONTROLLER, + []() -> Controller * { return new LonController(); }); +} + +Status ControllerAgent::InitializeConf(const ControlConf *control_conf) { + if (!control_conf) { + AERROR << "control_conf is null"; + return Status(ErrorCode::CONTROL_INIT_ERROR, "Failed to load config"); + } + control_conf_ = control_conf; + AINFO << control_conf_->DebugString(); + for (auto controller_type : control_conf_->active_controllers()) { + auto controller = controller_factory_.CreateObject( + static_cast(controller_type)); + if (controller) { + controller_list_.emplace_back(std::move(controller)); + } else { + AERROR << "Controller: " << controller_type << "is not supported"; + return Status(ErrorCode::CONTROL_INIT_ERROR, + "Invalid controller type:" + controller_type); + } + } + return Status::OK(); +} + +Status ControllerAgent::Init(const ControlConf *control_conf) { + RegisterControllers(); + CHECK(InitializeConf(control_conf).ok()) << "Fail to initialize config."; + for (auto &controller : controller_list_) { + if (controller == NULL || !controller->Init(control_conf_).ok()) { + if (controller != NULL) { + AERROR << "Controller <" << controller->Name() << "> init failed!"; + return Status(ErrorCode::CONTROL_INIT_ERROR, + "Failed to init Controller:" + controller->Name()); + } else { + return Status(ErrorCode::CONTROL_INIT_ERROR, + "Failed to init Controller"); + } + } + AINFO << "Controller <" << controller->Name() << "> init done!"; + } + return Status::OK(); +} + +Status ControllerAgent::ComputeControlCommand( + const ::apollo::localization::LocalizationEstimate *localization, + const ::apollo::canbus::Chassis *chassis, + const ::apollo::planning::ADCTrajectory *trajectory, + ::apollo::control::ControlCommand *cmd) { + for (auto &controller : controller_list_) { + ADEBUG << "controller:" << controller->Name() << " processing ..."; + double start_timestamp = apollo::common::time::ToSecond(Clock::Now()); + controller->ComputeControlCommand(localization, chassis, trajectory, cmd); + double end_timestamp = apollo::common::time::ToSecond(Clock::Now()); + AINFO << "controller: " << controller->Name() << " calculation time is: " + << (end_timestamp - start_timestamp) * 1000 << " ms."; + cmd->mutable_latency_stats()->add_controller_time_ms( + (end_timestamp - start_timestamp) * 1000); + } + return Status::OK(); +} + +Status ControllerAgent::Reset() { + for (auto &controller : controller_list_) { + ADEBUG << "controller:" << controller->Name() << " reset..."; + controller->Reset(); + } + return Status::OK(); +} + +} // namespace control +} // namespace apollo diff --git a/apollo_control/src/controller/lat_controller.cc b/apollo_control/src/controller/lat_controller.cc new file mode 100644 index 0000000..e6a762c --- /dev/null +++ b/apollo_control/src/controller/lat_controller.cc @@ -0,0 +1,507 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_control/controller/lat_controller.h" + +#include +#include +#include +#include +#include +#include +#include + +#include + +#include "apollo_common/log.h" +#include "apollo_common/math/linear_quadratic_regulator.h" +#include "apollo_common/math/math_utils.h" +#include "apollo_common/time/time.h" + +#include "apollo_control/common/control_gflags.h" + +namespace apollo { +namespace control { + +using common::Point3D; +using Matrix = Eigen::MatrixXd; +using ::apollo::common::vehicle_state::VehicleState; + +namespace { + +std::string GetLogFileName() { + time_t raw_time; + char name_buffer[80]; + std::time(&raw_time); + strftime(name_buffer, 80, "/tmp/steer_log_simple_optimal_%F_%H%M%S.csv", + localtime(&raw_time)); + return std::string(name_buffer); +} + +void WriteHeaders(std::ofstream& file_stream) { + file_stream << "current_lateral_error," + << "current_ref_heading," + << "current_heading," + << "current_heading_error," + << "heading_error_rate," + << "lateral_error_rate," + << "current_curvature," + << "steer_angle," + << "steer_angle_feedforward," + << "steer_angle_lateral_contribution," + << "steer_angle_lateral_rate_contribution," + << "steer_angle_heading_contribution," + << "steer_angle_heading_rate_contribution," + << "steer_angle_feedback," + << "steering_position," + << "v" << std::endl; +} +} // namespace + +LatController::LatController() : name_("LQR-based Lateral Controller") { + if (FLAGS_enable_csv_debug) { + steer_log_file_.open(GetLogFileName()); + steer_log_file_ << std::fixed; + steer_log_file_ << std::setprecision(6); + WriteHeaders(steer_log_file_); + } + AINFO << "Using " << name_; +} + +LatController::~LatController() { CloseLogFile(); } + +bool LatController::LoadControlConf(const ControlConf* control_conf) { + if (!control_conf) { + AERROR << "[LatController] control_conf == nullptr"; + return false; + } + ts_ = control_conf->lat_controller_conf().ts(); + CHECK_GT(ts_, 0.0) << "[LatController] Invalid control update interval."; + cf_ = control_conf->lat_controller_conf().cf(); + cr_ = control_conf->lat_controller_conf().cr(); + preview_window_ = control_conf->lat_controller_conf().preview_window(); + wheelbase_ = control_conf->lat_controller_conf().wheelbase(); + steer_transmission_ratio_ = + control_conf->lat_controller_conf().steer_transmission_ratio(); + steer_single_direction_max_degree_ = + control_conf->lat_controller_conf().steer_single_direction_max_degree(); + double mass_fl = control_conf->lat_controller_conf().mass_fl(); + double mass_fr = control_conf->lat_controller_conf().mass_fr(); + double mass_rl = control_conf->lat_controller_conf().mass_rl(); + double mass_rr = control_conf->lat_controller_conf().mass_rr(); + double mass_front = mass_fl + mass_fr; + double mass_rear = mass_rl + mass_rr; + mass_ = mass_front + mass_rear; + + lf_ = wheelbase_ * (1.0 - mass_front / mass_); + lr_ = wheelbase_ * (1.0 - mass_rear / mass_); + iz_ = lf_ * lf_ * mass_front + lr_ * lr_ * mass_rear; + + lqr_eps_ = control_conf->lat_controller_conf().eps(); + lqr_max_iteration_ = control_conf->lat_controller_conf().max_iteration(); + return true; +} + +void LatController::ProcessLogs(const SimpleLateralDebug* debug, + const canbus::Chassis* chassis) { + std::stringstream log_stream; + log_stream << debug->lateral_error() << "," << debug->ref_heading() << "," + << vehicle_state_.heading() << "," << debug->heading_error() << "," + << debug->heading_error_rate() << "," + << debug->lateral_error_rate() << "," << debug->curvature() << "," + << debug->steer_angle() << "," << debug->steer_angle_feedforward() + << "," << debug->steer_angle_lateral_contribution() << "," + << debug->steer_angle_lateral_rate_contribution() << "," + << debug->steer_angle_heading_contribution() << "," + << debug->steer_angle_heading_rate_contribution() << "," + << debug->steer_angle_feedback() << "," + << chassis->steering_percentage() << "," + << vehicle_state_.linear_velocity(); + if (FLAGS_enable_csv_debug) { + steer_log_file_ << log_stream.str() << std::endl; + } + // AINFO << "Steer_Control_Detail: " << log_stream.str(); +} + +void LatController::LogInitParameters() { + AINFO << name_ << " begin."; + AINFO << "[LatController parameters]" + << " mass_: " << mass_ << "," + << " iz_: " << iz_ << "," + << " lf_: " << lf_ << "," + << " lr_: " << lr_; +} + +void LatController::InitializeFilters(const ControlConf* control_conf) { + // Low pass filter + std::vector den(3, 0.0); + std::vector num(3, 0.0); + LpfCoefficients(ts_, control_conf->lat_controller_conf().cutoff_freq(), &den, + &num); + digital_filter_.set_coefficients(den, num); + // Mean filters + /** + heading_rate_filter_ = MeanFilter( + control_conf->lat_controller_conf().mean_filter_window_size()); + **/ + lateral_error_filter_ = + MeanFilter(control_conf->lat_controller_conf().mean_filter_window_size()); +} + +Status LatController::Init(const ControlConf* control_conf) { + if (!LoadControlConf(control_conf)) { + AERROR << "failed to load control conf"; + return Status(ErrorCode::CONTROL_COMPUTE_ERROR, + "failed to load control_conf"); + } + // Matrix init operations. + int matrix_size = basic_state_size_ + preview_window_; + matrix_a_ = Matrix::Zero(basic_state_size_, basic_state_size_); + matrix_ad_ = Matrix::Zero(basic_state_size_, basic_state_size_); + matrix_adc_ = Matrix::Zero(matrix_size, matrix_size); + matrix_a_(0, 1) = 1.0; + matrix_a_(1, 2) = (cf_ + cr_) / mass_; + matrix_a_(2, 3) = 1.0; + matrix_a_(3, 2) = (lf_ * cf_ - lr_ * cr_) / iz_; + + matrix_a_coeff_ = Matrix::Zero(matrix_size, matrix_size); + matrix_a_coeff_(1, 1) = -(cf_ + cr_) / mass_; + matrix_a_coeff_(1, 3) = (lr_ * cr_ - lf_ * cf_) / mass_; + matrix_a_coeff_(2, 3) = 1.0; + matrix_a_coeff_(3, 1) = (lr_ * cr_ - lf_ * cf_) / iz_; + matrix_a_coeff_(3, 3) = -1.0 * (lf_ * lf_ * cf_ + lr_ * lr_ * cr_) / iz_; + + matrix_b_ = Matrix::Zero(basic_state_size_, 1); + matrix_bd_ = Matrix::Zero(basic_state_size_, 1); + matrix_bdc_ = Matrix::Zero(matrix_size, 1); + matrix_b_(1, 0) = cf_ / mass_; + matrix_b_(3, 0) = lf_ * cf_ / iz_; + matrix_bd_ = matrix_b_ * ts_; + + matrix_state_ = Matrix::Zero(matrix_size, 1); + matrix_k_ = Matrix::Zero(1, matrix_size); + matrix_r_ = Matrix::Identity(1, 1); + matrix_q_ = Matrix::Zero(matrix_size, matrix_size); + + int q_param_size = control_conf->lat_controller_conf().matrix_q_size(); + if (matrix_size != q_param_size) { + AERROR << "matrix_q size: " << q_param_size + << " in parameter file not equal to matrix_size: " << matrix_size; + return Status(ErrorCode::CONTROL_COMPUTE_ERROR, + "lateral controller error: matrix_q size: " + + std::to_string(q_param_size) + + " in parameter file not equal to matrix_size: " + + std::to_string(matrix_size)); + } + for (int i = 0; i < q_param_size; ++i) { + matrix_q_(i, i) = control_conf->lat_controller_conf().matrix_q(i); + } + + InitializeFilters(control_conf); + LogInitParameters(); + return Status::OK(); +} + +void LatController::CloseLogFile() { + if (FLAGS_enable_csv_debug && steer_log_file_.is_open()) { + steer_log_file_.close(); + } +} + +void LatController::Stop() { CloseLogFile(); } + +std::string LatController::Name() const { return name_; } + +Status LatController::ComputeControlCommand( + const localization::LocalizationEstimate* localization, + const canbus::Chassis* chassis, + const planning::ADCTrajectory* planning_published_trajectory, + ControlCommand* cmd) { + vehicle_state_ = std::move(VehicleState(localization, chassis)); + vehicle_state_.set_linear_velocity(std::max(vehicle_state_.linear_velocity(), 1.0)); + + trajectory_analyzer_ = std::move(TrajectoryAnalyzer(planning_published_trajectory)); + + SimpleLateralDebug* debug = cmd->mutable_debug()->mutable_simple_lat_debug(); + debug->Clear(); + + // Update state = [Lateral Error, Lateral Error Rate, Heading Error, Heading + // Error Rate, preview lateral error1 , preview lateral error2, ...] + if (FLAGS_use_state_exact_match) { + UpdateStateAnalyticalMatching(debug); + } else { + UpdateState(debug); + } + + UpdateMatrix(); + + // Compound discrete matrix with road preview model + UpdateMatrixCompound(); + + common::math::SolveLQRProblem(matrix_adc_, matrix_bdc_, matrix_q_, matrix_r_, + lqr_eps_, lqr_max_iteration_, &matrix_k_); + + // feedback = - K * state + // Convert vehicle steer angle from rad to degree and then to steer degree + // then to 100% ratio + double steer_angle_feedback = -(matrix_k_ * matrix_state_)(0, 0) * 180 / + M_PI * steer_transmission_ratio_ / + steer_single_direction_max_degree_ * 100; + + double steer_angle_feedforward = ComputeFeedForward(debug->curvature()); + double steer_angle = steer_angle_feedback + steer_angle_feedforward; + // Clamp the steer angle to -100.0 to 100.0 + steer_angle = apollo::common::math::Clamp(steer_angle, -100.0, 100.0); + + steer_angle = digital_filter_.Filter(steer_angle); + cmd->set_steering_target(steer_angle); + cmd->set_steering_rate(FLAGS_steer_angle_rate); + + // compute extra information for logging and debugging + double steer_angle_lateral_contribution = + -matrix_k_(0, 0) * matrix_state_(0, 0) * 180 / M_PI * + steer_transmission_ratio_ / steer_single_direction_max_degree_ * 100; + + double steer_angle_lateral_rate_contribution = + -matrix_k_(0, 1) * matrix_state_(1, 0) * 180 / M_PI * + steer_transmission_ratio_ / steer_single_direction_max_degree_ * 100; + + double steer_angle_heading_contribution = + -matrix_k_(0, 2) * matrix_state_(2, 0) * 180 / M_PI * + steer_transmission_ratio_ / steer_single_direction_max_degree_ * 100; + + double steer_angle_heading_rate_contribution = + -matrix_k_(0, 3) * matrix_state_(3, 0) * 180 / M_PI * + steer_transmission_ratio_ / steer_single_direction_max_degree_ * 100; + + // TODO(yifei): move up temporary values to use debug fields. + + debug->set_heading(vehicle_state_.heading()); + debug->set_steer_angle(steer_angle); + debug->set_steer_angle_feedforward(steer_angle_feedforward); + debug->set_steer_angle_lateral_contribution(steer_angle_lateral_contribution); + debug->set_steer_angle_lateral_rate_contribution( + steer_angle_lateral_rate_contribution); + debug->set_steer_angle_heading_contribution(steer_angle_heading_contribution); + debug->set_steer_angle_heading_rate_contribution( + steer_angle_heading_rate_contribution); + debug->set_steer_angle_feedback(steer_angle_feedback); + debug->set_steering_position(chassis->steering_percentage()); + debug->set_ref_speed(vehicle_state_.linear_velocity()); + ProcessLogs(debug, chassis); + return Status::OK(); +} + +Status LatController::Reset() { + previous_heading_error_ = 0.0; + previous_lateral_error_ = 0.0; + return Status::OK(); +} + +// state = [Lateral Error, Lateral Error Rate, Heading Error, Heading Error +// Rate, Preview Lateral1, Preview Lateral2, ...] +void LatController::UpdateState(SimpleLateralDebug* debug) { + TrajectoryPoint traj_point; + Eigen::Vector2d com = vehicle_state_.ComputeCOMPosition(lr_); + double raw_lateral_error = GetLateralError(com, &traj_point); + + // lateral_error_ = lateral_rate_filter_.Filter(raw_lateral_error); + debug->set_lateral_error(lateral_error_filter_.Update(raw_lateral_error)); + + // ref_curvature_ = traj_point.kappa; + debug->set_curvature(traj_point.kappa); + + // ref_heading_ = traj_point.theta; + debug->set_ref_heading(traj_point.theta); + + // heading_error_ = + // common::math::NormalizeAngle(vehicle_state_.heading() - ref_heading_); + debug->set_heading_error(common::math::NormalizeAngle(vehicle_state_.heading() - traj_point.theta)); + + // heading_error_rate_ = (heading_error_ - previous_heading_error_) / ts_; + debug->set_heading_error_rate( + (debug->heading_error() - previous_heading_error_) / ts_); + // lateral_error_rate_ = (lateral_error_ - previous_lateral_error_) / ts_; + debug->set_lateral_error_rate( + (debug->lateral_error() - previous_lateral_error_) / ts_); + + // Prepare for next iteration. + previous_heading_error_ = debug->heading_error(); + previous_lateral_error_ = debug->lateral_error(); + + // State matrix update; + // First four elements are fixed; + matrix_state_(0, 0) = debug->lateral_error(); + matrix_state_(1, 0) = debug->lateral_error_rate(); + matrix_state_(2, 0) = debug->heading_error(); + matrix_state_(3, 0) = debug->heading_error_rate(); + + // Next elements are depending on preview window size; + for (int i = 0; i < preview_window_; ++i) { + double preview_time = ts_ * (i + 1); + Eigen::Vector2d future_position_estimate = + vehicle_state_.EstimateFuturePosition(preview_time); + double preview_lateral = GetLateralError(future_position_estimate, nullptr); + matrix_state_(basic_state_size_ + i, 0) = preview_lateral; + } + // preview matrix update; +} + +void LatController::UpdateStateAnalyticalMatching(SimpleLateralDebug* debug) { + Eigen::Vector2d com = vehicle_state_.ComputeCOMPosition(lr_); + ComputeLateralErrors(com.x(), com.y(), vehicle_state_.heading(), + vehicle_state_.linear_velocity(), + vehicle_state_.angular_velocity(), trajectory_analyzer_, + debug); + + // State matrix update; + // First four elements are fixed; + matrix_state_(0, 0) = debug->lateral_error(); + matrix_state_(1, 0) = debug->lateral_error_rate(); + matrix_state_(2, 0) = debug->heading_error(); + matrix_state_(3, 0) = debug->heading_error_rate(); + + // Next elements are depending on preview window size; + for (int i = 0; i < preview_window_; ++i) { + double preview_time = ts_ * (i + 1); + auto preview_point = + trajectory_analyzer_.QueryNearestPointByRelativeTime(preview_time); + + auto matched_point = trajectory_analyzer_.QueryNearestPointByPosition( + preview_point.x, preview_point.y); + + double dx = preview_point.x - matched_point.x; + double dy = preview_point.y - matched_point.y; + + double cos_matched_theta = std::cos(matched_point.theta); + double sin_matched_theta = std::sin(matched_point.theta); + double preview_d_error = cos_matched_theta * dy - sin_matched_theta * dx; + + matrix_state_(basic_state_size_ + i, 0) = preview_d_error; + } +} + +void LatController::UpdateMatrix() { + double v = vehicle_state_.linear_velocity(); + matrix_a_(1, 1) = matrix_a_coeff_(1, 1) / v; + matrix_a_(1, 3) = matrix_a_coeff_(1, 3) / v; + matrix_a_(3, 1) = matrix_a_coeff_(3, 1) / v; + matrix_a_(3, 3) = matrix_a_coeff_(3, 3) / v; + Matrix matrix_i = Matrix::Identity(matrix_a_.cols(), matrix_a_.cols()); + matrix_ad_ = (matrix_i + ts_ * 0.5 * matrix_a_) * + (matrix_i - ts_ * 0.5 * matrix_a_).inverse(); +} + +void LatController::UpdateMatrixCompound() { + // Initialize preview matrix + matrix_adc_.block(0, 0, basic_state_size_, basic_state_size_) = matrix_ad_; + matrix_bdc_.block(0, 0, basic_state_size_, 1) = matrix_bd_; + if (preview_window_ > 0) { + matrix_bdc_(matrix_bdc_.rows() - 1, 0) = 1; + // Update augument A matrix; + for (int i = 0; i < preview_window_ - 1; ++i) { + matrix_adc_(basic_state_size_ + i, basic_state_size_ + 1 + i) = 1; + } + } +} + +double LatController::ComputeFeedForward(double ref_curvature) const { + double kv = + lr_ * mass_ / 2 / cf_ / wheelbase_ - lf_ * mass_ / 2 / cr_ / wheelbase_; + + // then change it from rad to % + double v = vehicle_state_.linear_velocity(); + double steer_angle_feedforwardterm = + (wheelbase_ * ref_curvature + kv * v * v * ref_curvature - + matrix_k_(0, 2) * + (lr_ * ref_curvature - + lf_ * mass_ * v * v * ref_curvature / 2 / cr_ / wheelbase_)) * + 180 / M_PI * steer_transmission_ratio_ / + steer_single_direction_max_degree_ * 100; + return steer_angle_feedforwardterm; +} + +/* + * SL coordinate system: + * left to the ref_line, L is + + * right to the ref_line, L is - + */ +double LatController::GetLateralError(const Eigen::Vector2d& point, + TrajectoryPoint* traj_point) const { + auto closest = + trajectory_analyzer_.QueryNearestPointByPosition(point.x(), point.y()); + + double point_angle = std::atan2(point.y() - closest.y, point.x() - closest.x); + double point2path_angle = point_angle - closest.theta; + if (traj_point != nullptr) { + *traj_point = closest; + } + + double dx = closest.x - point.x(); + double dy = closest.y - point.y(); + return std::sin(point2path_angle) * std::sqrt(dx * dx + dy * dy); +} + +void LatController::ComputeLateralErrors( + const double x, const double y, const double theta, const double linear_v, + const double angular_v, const TrajectoryAnalyzer& trajectory_analyzer, + SimpleLateralDebug* debug) const { + auto matched_point = trajectory_analyzer.QueryNearestPointByPosition(x, y); + + double dx = x - matched_point.x; + double dy = y - matched_point.y; + + double cos_matched_theta = std::cos(matched_point.theta); + double sin_matched_theta = std::sin(matched_point.theta); + // d_error = cos_matched_theta * dy - sin_matched_theta * dx; + debug->set_lateral_error(cos_matched_theta * dy - sin_matched_theta * dx); + + double delta_theta = + common::math::NormalizeAngle(theta - matched_point.theta); + double sin_delta_theta = std::sin(delta_theta); + // d_error_dot = linear_v * sin_delta_theta; + debug->set_lateral_error_rate(linear_v * sin_delta_theta); + + // theta_error = delta_theta; + debug->set_heading_error(delta_theta); + // theta_error_dot = angular_v - matched_point.kappa * matched_point.v; + debug->set_heading_error_rate(angular_v - + matched_point.kappa * matched_point.v); + + // matched_theta = matched_point.theta; + debug->set_ref_heading(matched_point.theta); + // matched_kappa = matched_point.kappa; + debug->set_curvature(matched_point.kappa); +} + +} // namespace control +} // namespace apollo diff --git a/apollo_control/src/controller/lon_controller.cc b/apollo_control/src/controller/lon_controller.cc new file mode 100644 index 0000000..f913d2a --- /dev/null +++ b/apollo_control/src/controller/lon_controller.cc @@ -0,0 +1,369 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ +#include "apollo_control/controller/lon_controller.h" + +#include +#include + +#include "apollo_common/log.h" +#include "apollo_common/math/math_utils.h" +#include "apollo_common/time/time.h" + +#include "apollo_control/common/control_gflags.h" +// #include "modules/localization/common/localization_gflags.h" + +namespace apollo { +namespace control { + +using ::apollo::common::time::Clock; +using ::apollo::common::vehicle_state::VehicleState; + +LonController::LonController() + : name_(ControlConf_ControllerType_Name(ControlConf::LON_CONTROLLER)) { + if (FLAGS_enable_csv_debug) { + time_t rawtime; + char name_buffer[80]; + std::time(&rawtime); + strftime(name_buffer, 80, "/tmp/speed_log__%F_%H%M%S.csv", + localtime(&rawtime)); + speed_log_file_ = fopen(name_buffer, "w"); + if (speed_log_file_ == nullptr) { + AERROR << "Fail to open file:" << name_buffer; + FLAGS_enable_csv_debug = false; + } + if (speed_log_file_ != nullptr) { + fprintf(speed_log_file_, + "station_reference," + "station_error," + "station_error_limited," + "preview_station_error," + "speed_reference," + "speed_error," + "speed_error_limited," + "preview_speed_reference," + "preview_speed_error," + "preview_acceleration_reference," + "acceleration_cmd_closeloop," + "acceleration_cmd," + "acceleration_lookup," + "speed_lookup," + "calibration_value," + "throttle_cmd," + "brake_cmd," + "is_full_stop," + "\r\n"); + + fflush(speed_log_file_); + } + AINFO << name_ << " used."; + } +} + +void LonController::CloseLogFile() { + if (FLAGS_enable_csv_debug) { + if (speed_log_file_ != nullptr) { + fclose(speed_log_file_); + speed_log_file_ = nullptr; + } + } +} +void LonController::Stop() { CloseLogFile(); } + +LonController::~LonController() { CloseLogFile(); } + +Status LonController::Init(const ControlConf *control_conf) { + control_conf_ = control_conf; + if (control_conf_ == nullptr) { + controller_initialized_ = false; + AERROR << "get_longitudinal_param() nullptr"; + return Status(ErrorCode::CONTROL_INIT_ERROR, + "Failed to load LonController conf"); + } + const LonControllerConf &lon_controller_conf = + control_conf_->lon_controller_conf(); + + station_pid_controller_.Init(lon_controller_conf.station_pid_conf()); + speed_pid_controller_.Init(lon_controller_conf.low_speed_pid_conf()); + + SetDigitalFilterAcceleration(lon_controller_conf); + SetDigitalFilterThrottle(lon_controller_conf); + SetDigitalFilterBrake(lon_controller_conf); + + LoadControlCalibrationTable(lon_controller_conf); + controller_initialized_ = true; + return Status::OK(); +} + +void LonController::SetDigitalFilterAcceleration( + const LonControllerConf &lon_controller_conf) { + double cutoff_freq = + lon_controller_conf.acceleration_filter_conf().cutoff_freq(); + double ts = lon_controller_conf.ts(); + SetDigitalFilter(ts, cutoff_freq, &digital_filter_acceleration_); +} + +void LonController::SetDigitalFilterThrottle( + const LonControllerConf &lon_controller_conf) { + double cutoff_freq = lon_controller_conf.throttle_filter_conf().cutoff_freq(); + double ts = lon_controller_conf.ts(); + SetDigitalFilter(ts, cutoff_freq, &digital_filter_throttle_); +} + +void LonController::SetDigitalFilterBrake( + const LonControllerConf &lon_controller_conf) { + double cutoff_freq = lon_controller_conf.brake_filter_conf().cutoff_freq(); + double ts = lon_controller_conf.ts(); + SetDigitalFilter(ts, cutoff_freq, &digital_filter_brake_); +} + +void LonController::LoadControlCalibrationTable( + const LonControllerConf &lon_controller_conf) { + const auto &control_table = lon_controller_conf.calibration_table(); + AINFO << "Control calibration table loaded"; + int control_table_size = control_table.calibration_size(); + AINFO << "Control calibration table size is " << control_table_size; + Interpolation2D::DataType xyz; + for (int i = 0; i < control_table_size; ++i) { + const auto &calibration = control_table.calibration(i); + xyz.push_back(std::make_tuple(calibration.speed(), + calibration.acceleration(), + calibration.command())); + } + control_interpolation_.reset(new Interpolation2D); + CHECK(control_interpolation_->Init(xyz)) + << "Fail to load control calibration table"; +} + +Status LonController::ComputeControlCommand( + const ::apollo::localization::LocalizationEstimate *localization, + const ::apollo::canbus::Chassis *chassis, + const ::apollo::planning::ADCTrajectory *planning_published_trajectory, + ::apollo::control::ControlCommand *cmd) { + localization_ = localization; + chassis_ = chassis; + vehicle_state_ = std::move(VehicleState(localization, chassis)); + + trajectory_message_ = planning_published_trajectory; + if (!control_interpolation_) { + AERROR << "Fail to initialize calibration table."; + return Status(ErrorCode::CONTROL_COMPUTE_ERROR, + "Fail to initialize calibration table."); + } + + if (trajectory_analyzer_ == nullptr || + trajectory_analyzer_->seq_num() != + trajectory_message_->header().sequence_num()) { + trajectory_analyzer_.reset(new TrajectoryAnalyzer(trajectory_message_)); + } + const LonControllerConf &lon_controller_conf = + control_conf_->lon_controller_conf(); + + auto debug = cmd->mutable_debug()->mutable_simple_lon_debug(); + debug->Clear(); + + double brake_cmd = 0.0; + double throttle_cmd = 0.0; + double ts = lon_controller_conf.ts(); + double preview_time = lon_controller_conf.preview_window() * ts; + + if (preview_time < 0.0) { + AERROR << "Preview time set as: " << preview_time << " less than 0"; + return Status(ErrorCode::CONTROL_COMPUTE_ERROR, + "Invalid preview time:" + std::to_string(preview_time)); + } + ComputeLongitudinalErrors(vehicle_state_, trajectory_analyzer_.get(), + preview_time, debug); + + double station_error_limit = lon_controller_conf.station_error_limit(); + double station_error_limited = 0.0; + if (FLAGS_enable_speed_station_preview) { + station_error_limited = + apollo::common::math::Clamp(debug->preview_station_error(), + -station_error_limit, station_error_limit); + } else { + station_error_limited = apollo::common::math::Clamp( + debug->station_error(), -station_error_limit, station_error_limit); + } + double speed_offset = + station_pid_controller_.Control(station_error_limited, ts); + + double speed_controller_input = 0.0; + double speed_controller_input_limit = + lon_controller_conf.speed_controller_input_limit(); + double speed_controller_input_limited = 0.0; + if (FLAGS_enable_speed_station_preview) { + speed_controller_input = speed_offset + debug->preview_speed_error(); + } else { + speed_controller_input = speed_offset + debug->speed_error(); + } + speed_controller_input_limited = apollo::common::math::Clamp( + speed_controller_input, -speed_controller_input_limit, + speed_controller_input_limit); + + double acceleration_cmd_closeloop = 0.0; + if (vehicle_state_.linear_velocity() <= lon_controller_conf.switch_speed()) { + speed_pid_controller_.SetPID(lon_controller_conf.low_speed_pid_conf()); + acceleration_cmd_closeloop = + speed_pid_controller_.Control(speed_controller_input_limited, ts); + } else { + speed_pid_controller_.SetPID(lon_controller_conf.high_speed_pid_conf()); + acceleration_cmd_closeloop = + speed_pid_controller_.Control(speed_controller_input_limited, ts); + } + + double acceleration_cmd = + acceleration_cmd_closeloop + debug->preview_acceleration_reference(); + debug->set_is_full_stop(false); + if (std::abs(debug->preview_acceleration_reference()) <= + FLAGS_max_acceleration_when_stopped && + std::abs(debug->preview_speed_reference()) <= + FLAGS_max_abs_speed_when_stopped) { + acceleration_cmd = lon_controller_conf.standstill_acceleration(); + AINFO << "Stop location reached"; + debug->set_is_full_stop(true); + } + + double throttle_deadzone = lon_controller_conf.throttle_deadzone(); + double brake_deadzone = lon_controller_conf.brake_deadzone(); + double calibration_value = 0.0; + if (FLAGS_use_preview_speed_for_table) { + calibration_value = control_interpolation_->Interpolate( + std::make_pair(debug->preview_speed_reference(), acceleration_cmd)); + } else { + calibration_value = control_interpolation_->Interpolate( + std::make_pair(chassis_->speed_mps(), acceleration_cmd)); + } + + if (calibration_value >= 0) { + throttle_cmd = calibration_value > throttle_deadzone ? calibration_value + : throttle_deadzone; + brake_cmd = 0.0; + } else { + throttle_cmd = 0.0; + brake_cmd = -calibration_value > brake_deadzone ? -calibration_value + : brake_deadzone; + } + + debug->set_station_error_limited(station_error_limited); + debug->set_speed_controller_input_limited(speed_controller_input_limited); + debug->set_acceleration_cmd(acceleration_cmd); + debug->set_throttle_cmd(throttle_cmd); + debug->set_brake_cmd(brake_cmd); + debug->set_acceleration_lookup(acceleration_cmd); + debug->set_speed_lookup(chassis_->speed_mps()); + debug->set_calibration_value(calibration_value); + debug->set_acceleration_cmd_closeloop(acceleration_cmd_closeloop); + + if (FLAGS_enable_csv_debug && speed_log_file_ != nullptr) { + fprintf(speed_log_file_, + "%.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f," + "%.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %d,\r\n", + debug->station_reference(), debug->station_error(), + station_error_limited, debug->preview_station_error(), + debug->speed_reference(), debug->speed_error(), + speed_controller_input_limited, debug->preview_speed_reference(), + debug->preview_speed_error(), + debug->preview_acceleration_reference(), acceleration_cmd_closeloop, + acceleration_cmd, debug->acceleration_lookup(), + debug->speed_lookup(), calibration_value, throttle_cmd, brake_cmd, + debug->is_full_stop()); + } + + cmd->set_throttle(throttle_cmd); + cmd->set_brake(brake_cmd); + return Status::OK(); +} + +Status LonController::Reset() { + speed_pid_controller_.Reset(); + station_pid_controller_.Reset(); + return Status::OK(); +} + +std::string LonController::Name() const { return name_; } + +void LonController::ComputeLongitudinalErrors( + const VehicleState &vehicle_state, + const TrajectoryAnalyzer *trajectory_analyzer, const double preview_time, + SimpleLongitudinalDebug *debug) { + // the decomposed vehicle motion onto Frenet frame + // s: longitudinal accumulated distance along reference trajectory + // s_dot: longitudinal velocity along reference trajectory + // d: lateral distance w.r.t. reference trajectory + // d_dot: lateral distance change rate, i.e. dd/dt + double s_matched = 0.0; + double s_dot_matched = 0.0; + double d_matched = 0.0; + double d_dot_matched = 0.0; + + auto matched_point = trajectory_analyzer->QueryMatchedPathPoint( + vehicle_state.x(), vehicle_state.y()); + + trajectory_analyzer->ToTrajectoryFrame( + vehicle_state.x(), vehicle_state.y(), vehicle_state.heading(), + vehicle_state.linear_velocity(), matched_point, &s_matched, + &s_dot_matched, &d_matched, &d_dot_matched); + + double current_control_time = apollo::common::time::ToSecond(Clock::Now()); + double preview_control_time = current_control_time + preview_time; + + TrajectoryPoint reference_point = + trajectory_analyzer->QueryNearestPointByAbsoluteTime( + current_control_time); + TrajectoryPoint preview_point = + trajectory_analyzer->QueryNearestPointByAbsoluteTime( + preview_control_time); + + ADEBUG << "matched point:" << matched_point.DebugString(); + ADEBUG << "reference point:" << reference_point.DebugString(); + ADEBUG << "preview point:" << preview_point.DebugString(); + debug->set_station_error(reference_point.s - s_matched); + debug->set_speed_error(reference_point.v - s_dot_matched); + + debug->set_station_reference(reference_point.s); + debug->set_speed_reference(reference_point.v); + debug->set_preview_station_error(preview_point.s - s_matched); + debug->set_preview_speed_error(preview_point.v - s_dot_matched); + debug->set_preview_speed_reference(preview_point.v); + debug->set_preview_acceleration_reference(preview_point.a); +} + +void LonController::SetDigitalFilter(double ts, double cutoff_freq, + DigitalFilter *digital_filter) { + std::vector denominators; + std::vector numerators; + LpfCoefficients(ts, cutoff_freq, &denominators, &numerators); + digital_filter->set_coefficients(denominators, numerators); +} + +} // namespace control +} // namespace apollo diff --git a/apollo_control/src/filters/digital_filter.cc b/apollo_control/src/filters/digital_filter.cc new file mode 100644 index 0000000..149ddcc --- /dev/null +++ b/apollo_control/src/filters/digital_filter.cc @@ -0,0 +1,140 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_control/filters/digital_filter.h" + +#include + +#include "apollo_common/log.h" + +namespace { + +const double kDoubleEpsilon = 1.0e-6; + +} // namespace + +namespace apollo { +namespace control { + +DigitalFilter::DigitalFilter(const std::vector& denominators, + const std::vector& numerators) { + dead_zone_ = 0.0; + last_ = 0.0; + set_coefficients(denominators, numerators); +} + +void DigitalFilter::set_denominators(const std::vector& denominators) { + denominators_ = denominators; + y_values_.resize(denominators_.size(), 0.0); +} + +void DigitalFilter::set_numerators(const std::vector& numerators) { + numerators_ = numerators; + x_values_.resize(numerators_.size(), 0.0); +} + +void DigitalFilter::set_coefficients(const std::vector& denominators, + const std::vector& numerators) { + set_denominators(denominators); + set_numerators(numerators); +} + +void DigitalFilter::set_dead_zone(const double deadzone) { + dead_zone_ = std::abs(deadzone); + AINFO << "Setting digital filter dead zone = " << dead_zone_; +} + +double DigitalFilter::Filter(const double x_insert) { + if (denominators_.empty() || numerators_.empty()) { + AERROR << "Empty denominators or numerators"; + return 0.0; + } + + x_values_.pop_back(); + x_values_.push_front(x_insert); + double xside = Compute(x_values_, numerators_, 0, numerators_.size() - 1); + + y_values_.pop_back(); + double yside = Compute(y_values_, denominators_, 1, denominators_.size() - 1); + + double y_insert = 0.0; + if (std::abs(denominators_.front()) > kDoubleEpsilon) { + y_insert = (xside - yside) / denominators_.front(); + } + y_values_.push_front(y_insert); + + return UpdateLast(y_insert); +} + +double DigitalFilter::UpdateLast(const double input) { + double diff = std::abs(input - last_); + if (diff < dead_zone_) { + return last_; + } else { + last_ = input; + return input; + } +} + +double DigitalFilter::Compute(const std::deque& values, + const std::vector& coefficients, + const std::size_t coeff_start, + const std::size_t coeff_end) { + if (coeff_start > coeff_end || coeff_end >= coefficients.size()) { + AERROR << "Invalid inputs."; + return 0.0; + } + if (coeff_end - coeff_start + 1 != values.size()) { + AERROR << "Sizes not match."; + return 0.0; + } + double sum = 0.0; + int i = coeff_start; + for (auto& value : values) { + sum += value * coefficients[i]; + ++i; + } + return sum; +} + +const std::vector& DigitalFilter::denominators() const { + return denominators_; +} + +const std::vector& DigitalFilter::numerators() const { + return numerators_; +} + +double DigitalFilter::dead_zone() const { return dead_zone_; } + +} // namespace control +} // namespace apollo diff --git a/apollo_control/src/filters/digital_filter_coefficients.cc b/apollo_control/src/filters/digital_filter_coefficients.cc new file mode 100644 index 0000000..6a88d55 --- /dev/null +++ b/apollo_control/src/filters/digital_filter_coefficients.cc @@ -0,0 +1,68 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_control/filters/digital_filter_coefficients.h" + +#include +#include + +namespace apollo { +namespace control { + +void LpfCoefficients(const double ts, const double cutoff_freq, + std::vector *denominators, + std::vector *numerators) { + denominators->clear(); + numerators->clear(); + denominators->reserve(3); + numerators->reserve(3); + + double wa = 2.0 * M_PI * cutoff_freq; // Analog frequency in rad/s + double alpha = wa * ts / 2.0; // tan(Wd/2), Wd is discrete frequency + double alpha_sqr = alpha * alpha; + double tmp_term = std::sqrt(2.0) * alpha + alpha_sqr; + double gain = alpha_sqr / (1.0 + tmp_term); + + denominators->push_back(1.0); + denominators->push_back(2.0 * (alpha_sqr - 1.0) / (1.0 + tmp_term)); + denominators->push_back((1.0 - std::sqrt(2.0) * alpha + alpha_sqr) / + (1.0 + tmp_term)); + + numerators->push_back(gain); + numerators->push_back(2.0 * gain); + numerators->push_back(gain); + + return; +} + +} // namespace control +} // namespace apollo diff --git a/apollo_control/src/filters/mean_filter.cc b/apollo_control/src/filters/mean_filter.cc new file mode 100644 index 0000000..cc01e1f --- /dev/null +++ b/apollo_control/src/filters/mean_filter.cc @@ -0,0 +1,127 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_control/filters/mean_filter.h" + +#include + +#include "apollo_common/log.h" + +namespace apollo { +namespace control { + +using MF = MeanFilter; +using uint8 = std::uint_fast8_t; +using TimedValue = std::pair; + +const uint8 kMaxWindowSize = std::numeric_limits::max() / 2; + +MF::MeanFilter(const uint8 window_size) : window_size_(window_size) { + CHECK_GT(window_size_, 0); + CHECK_LE(window_size_, kMaxWindowSize); + initialized_ = true; +} + +double MF::GetMin() const { + if (min_candidates_.size() == 0) { + return std::numeric_limits::infinity(); + } else { + return min_candidates_.front().second; + } +} + +double MF::GetMax() const { + if (max_candidates_.size() == 0) { + return -std::numeric_limits::infinity(); + } else { + return max_candidates_.front().second; + } +} + +double MF::Update(const double measurement) { + CHECK(initialized_); + CHECK_LE(values_.size(), window_size_); + CHECK_LE(min_candidates_.size(), window_size_); + CHECK_LE(max_candidates_.size(), window_size_); + ++time_; + time_ %= 2 * window_size_; + if (values_.size() == window_size_) { + RemoveEarliest(); + } + Insert(measurement); + if (values_.size() > 2) { + return (sum_ - GetMin() - GetMax()) / (values_.size() - 2); + } else { + return sum_ / values_.size(); + } +} + +bool MF::ShouldPopOldestCandidate(const uint8 old_time) const { + if (old_time < window_size_) { + CHECK_LE(time_, old_time + window_size_); + return old_time + window_size_ == time_; + } else if (time_ < window_size_) { + CHECK_GE(old_time, time_ + window_size_); + return old_time == time_ + window_size_; + } else { + return false; + } +} + +void MF::RemoveEarliest() { + CHECK_EQ(values_.size(), window_size_); + double removed = values_.front(); + values_.pop_front(); + sum_ -= removed; + if (ShouldPopOldestCandidate(min_candidates_.front().first)) { + min_candidates_.pop_front(); + } + if (ShouldPopOldestCandidate(max_candidates_.front().first)) { + max_candidates_.pop_front(); + } +} + +void MF::Insert(const double value) { + values_.push_back(value); + sum_ += value; + while (min_candidates_.size() > 0 && min_candidates_.back().second > value) { + min_candidates_.pop_back(); + } + min_candidates_.push_back(std::make_pair(time_, value)); + while (max_candidates_.size() > 0 && max_candidates_.back().second < value) { + max_candidates_.pop_back(); + } + max_candidates_.push_back(std::make_pair(time_, value)); +} + +} // namespace control +} // namespace apollo diff --git a/apollo_control/src/main.cc b/apollo_control/src/main.cc new file mode 100644 index 0000000..471628e --- /dev/null +++ b/apollo_control/src/main.cc @@ -0,0 +1,37 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/apollo_app.h" +#include "apollo_control/common/control_gflags.h" +#include "apollo_control/control.h" + +APOLLO_MAIN(apollo::control::Control); diff --git a/apollo_decision/CMakeLists.txt b/apollo_decision/CMakeLists.txt new file mode 100644 index 0000000..5f619aa --- /dev/null +++ b/apollo_decision/CMakeLists.txt @@ -0,0 +1,50 @@ +cmake_minimum_required(VERSION 3.0.2) +project(apollo_decision) + +add_compile_options(-std=c++17) +# set(CMAKE_BUILD_TYPE "Debug") +set(CMAKE_BUILD_TYPE "Release") + +find_package(Eigen3 REQUIRED) + +find_package(catkin REQUIRED COMPONENTS + roscpp + apollo_msgs + apollo_common +) + +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES apollo_decision +# CATKIN_DEPENDS roscpp +# DEPENDS system_lib +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIR} +) + +add_executable(${PROJECT_NAME} + src/main.cc + src/decision.cc + # common + src/common/decision_gflags.cc +) +add_dependencies(${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} + protobuf + glog + gflags +) + +# install +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) \ No newline at end of file diff --git a/apollo_decision/README.md b/apollo_decision/README.md new file mode 100644 index 0000000..eca98e6 --- /dev/null +++ b/apollo_decision/README.md @@ -0,0 +1,21 @@ +# Decision + +## Introduction + Decision module receives obstacles information (e.g., position, speed, + acceleration, prediction trajectory, and etc.), master vehicle status + (e.g, position, speed, acceleration, and etc.), traffic light status, + and map and routing information. Based on the aforementioned + information, decision module generates decision command for master vehicle + and each obstacle. It also generates virtual obstacles if necessary and + position them based on map information. + +## Input + * Obstacles information from perception and prediction modules + * Traffic lights status from perception module + * Map and routing information + * Master vehicle status + +## Output + * Decision command for master vehicle + * Generated virtual obstacles + * Decision command for each obstacle \ No newline at end of file diff --git a/apollo_decision/conf/adapter.conf b/apollo_decision/conf/adapter.conf new file mode 100644 index 0000000..940ce0d --- /dev/null +++ b/apollo_decision/conf/adapter.conf @@ -0,0 +1,6 @@ +config { + type: DECISION + mode: PUBLISH_ONLY + message_history_limit: 10 +} +is_ros: true diff --git a/apollo_decision/conf/decision.conf b/apollo_decision/conf/decision.conf new file mode 100644 index 0000000..5c5d4b5 --- /dev/null +++ b/apollo_decision/conf/decision.conf @@ -0,0 +1 @@ +--decision_publish_freq=5.0 \ No newline at end of file diff --git a/apollo_decision/include/apollo_decision/common/decision_gflags.h b/apollo_decision/include/apollo_decision/common/decision_gflags.h new file mode 100644 index 0000000..eee3d39 --- /dev/null +++ b/apollo_decision/include/apollo_decision/common/decision_gflags.h @@ -0,0 +1,42 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODEULES_DECISION_COMMON_DECISION_GFLAGS_H_ +#define MODEULES_DECISION_COMMON_DECISION_GFLAGS_H_ + +#include + +DECLARE_string(decision_module_name); + +DECLARE_double(decision_publish_freq); + +#endif // MODEULES_DECISION_COMMON_DECISION_GFLAGS_H_ diff --git a/apollo_decision/include/apollo_decision/decision.h b/apollo_decision/include/apollo_decision/decision.h new file mode 100644 index 0000000..70fda48 --- /dev/null +++ b/apollo_decision/include/apollo_decision/decision.h @@ -0,0 +1,69 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_DECISION_DECISION_H_ +#define MODULES_DECISION_DECISION_H_ + +#include + +#include + +#include "apollo_common/apollo_app.h" +#include "apollo_common/macro.h" + +/** + * @namespace apollo::decision + * @brief apollo::decision + */ +namespace apollo { +namespace decision { + +class Decision : public apollo::common::ApolloApp { + public: + std::string Name() const override; + apollo::common::Status Init() override; + apollo::common::Status Start() override; + void Stop() override; + virtual ~Decision() = default; + + private: + void OnTimer(const ros::TimerEvent& event); + void PublishDecision(); + + private: + ros::Timer timer_; +}; + +} // namespace decision +} // namespace apollo + +#endif // MODULES_DECISION_DECISION_H_ diff --git a/apollo_decision/launch/decision.launch b/apollo_decision/launch/decision.launch new file mode 100644 index 0000000..c08fe35 --- /dev/null +++ b/apollo_decision/launch/decision.launch @@ -0,0 +1,7 @@ + + + + \ No newline at end of file diff --git a/apollo_decision/package.xml b/apollo_decision/package.xml new file mode 100644 index 0000000..f88ee1e --- /dev/null +++ b/apollo_decision/package.xml @@ -0,0 +1,29 @@ + + + apollo_decision + 0.0.0 + The apollo_decision package + + forrest + TODO + + catkin + + roscpp + roscpp + roscpp + + apollo_msgs + apollo_msgs + apollo_msgs + + apollo_common + apollo_common + apollo_common + + + + + + + diff --git a/apollo_decision/src/common/decision_gflags.cc b/apollo_decision/src/common/decision_gflags.cc new file mode 100644 index 0000000..8a03d6f --- /dev/null +++ b/apollo_decision/src/common/decision_gflags.cc @@ -0,0 +1,37 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_decision/common/decision_gflags.h" + +DEFINE_string(decision_module_name, "decision", "decision module name"); + +DEFINE_double(decision_publish_freq, 10, "decision publishing frequency."); diff --git a/apollo_decision/src/decision.cc b/apollo_decision/src/decision.cc new file mode 100644 index 0000000..bc57235 --- /dev/null +++ b/apollo_decision/src/decision.cc @@ -0,0 +1,80 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_decision/decision.h" + +#include "apollo_msgs/proto/common/adapter_config.pb.h" +#include "apollo_common/adapters/adapter_manager.h" +#include "apollo_common/time/time.h" + +#include "apollo_decision/common/decision_gflags.h" + +namespace apollo { +namespace decision { + +using apollo::common::adapter::AdapterManager; +using apollo::common::time::Clock; + +std::string Decision::Name() const { + return FLAGS_decision_module_name; +} + +apollo::common::Status Decision::Init() { + return apollo::common::Status::OK(); +} + +apollo::common::Status Decision::Start() { + AdapterManager::Init(); + + // start ROS timer, one-shot = false, auto-start = true + const double duration = 1.0 / FLAGS_decision_publish_freq; + timer_ = AdapterManager::CreateTimer(ros::Duration(duration), + &Decision::OnTimer, this); + return apollo::common::Status::OK(); +} + +void Decision::Stop() { // spinner_.stop(); +} + +void Decision::OnTimer(const ros::TimerEvent&) { + PublishDecision(); +} + +void Decision::PublishDecision() { + DecisionResult decision_result; + AdapterManager::FillDecisionHeader(Name(), decision_result.mutable_header()); + + AdapterManager::PublishDecision(decision_result); +} + +} // namespace decision +} // namespace apollo diff --git a/apollo_decision/src/main.cc b/apollo_decision/src/main.cc new file mode 100644 index 0000000..15651b8 --- /dev/null +++ b/apollo_decision/src/main.cc @@ -0,0 +1,42 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include + +#include + +#include "apollo_common/log.h" + +#include "apollo_decision/common/decision_gflags.h" +#include "apollo_decision/decision.h" + +APOLLO_MAIN(apollo::decision::Decision); diff --git a/apollo_localization/CMakeLists.txt b/apollo_localization/CMakeLists.txt new file mode 100644 index 0000000..05c20c0 --- /dev/null +++ b/apollo_localization/CMakeLists.txt @@ -0,0 +1,54 @@ +cmake_minimum_required(VERSION 3.0.2) +project(apollo_localization) + +add_compile_options(-std=c++17) +# set(CMAKE_BUILD_TYPE "Debug") +set(CMAKE_BUILD_TYPE "Release") + +find_package(Eigen3 REQUIRED) + +find_package(catkin REQUIRED COMPONENTS + roscpp + apollo_msgs + apollo_common +) + +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES apollo_localization +# CATKIN_DEPENDS roscpp +# DEPENDS system_lib +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIR} +) + +add_executable(${PROJECT_NAME} + src/main.cc + src/localization.cc + # common + src/common/localization_gflags.cc + # camera + src/camera/camera_localization.cc + # rtk + src/rtk/rtk_localization.cc +) +add_dependencies(${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} + protobuf + glog + gflags +) + +# install +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) \ No newline at end of file diff --git a/apollo_localization/README.md b/apollo_localization/README.md new file mode 100644 index 0000000..ea1db46 --- /dev/null +++ b/apollo_localization/README.md @@ -0,0 +1,29 @@ +# Localization + +## Introduction + This module provides localization service. It has implemented a RTK based localization which incorporates GPS and IMU information. + +## Input + In the provided RTK localization method, there are two inputs: + * GPS The Global Position System. + * IMU Inertial Measurement Unit. + +## Output + * An object instance defined by Protobuf message `LocalizationEstimate`, which can be found in file `localization/proto/localization.proto`. + +## Add localization implementation + Currently the RTK based localization is implemented in class `RTKLocalization`. If a new localization method need to be implemented with a name such as `FooLocalization`, you can follow the following steps: + + 1. In `proto/localization_config.proto`, add `FOO` in the `LocalizationType` enum type. + + 1. Go to the `modules/localization` directory, and create a `foo` directory. In the `foo` directory, implement class `FooLocalization` following the `RTKLocalization` class in the `rtk` directory. `FooLocalization` has to be a subclass of `LocalizationBase`. Also create file foo/BUILD following file `rtk/BUILD`. + + 1. You need to register `FooLocalizatoin` class in function `Localization::RegisterLocalizationMethods()`, which is located in cpp file `localization.cc`. You can register by inserting the following code at the end of the function: + + ``` + localization_factory_.Register(LocalizationConfing::FOO, []()->LocalizationBase* { return new FooLocalization(); }); + ``` + + Make sure your code can be compiled by including the header files that defines class `FooLocalization`. + + 1. Now you can go back to the `apollo` root directory and build your code with command `bash apollo.sh build`. diff --git a/apollo_localization/conf/camera_adapter.conf b/apollo_localization/conf/camera_adapter.conf new file mode 100644 index 0000000..8181617 --- /dev/null +++ b/apollo_localization/conf/camera_adapter.conf @@ -0,0 +1,26 @@ +config { + type: GPS + mode: RECEIVE_ONLY + message_history_limit: 50 +} +config { + type: IMU + mode: RECEIVE_ONLY + message_history_limit: 50 +} +config { + type: CAMERA + mode: RECEIVE_ONLY + message_history_limit: 3 +} +config { + type: LOCALIZATION + mode: PUBLISH_ONLY + message_history_limit: 10 +} +config { + type: MONITOR + mode: PUBLISH_ONLY + message_history_limit: 10 +} +is_ros: true diff --git a/apollo_localization/conf/localization.conf b/apollo_localization/conf/localization.conf new file mode 100644 index 0000000..ccba030 --- /dev/null +++ b/apollo_localization/conf/localization.conf @@ -0,0 +1 @@ +--noenable_gps_imu_interprolate diff --git a/apollo_localization/conf/localization_config.pb.txt b/apollo_localization/conf/localization_config.pb.txt new file mode 100644 index 0000000..534b58d --- /dev/null +++ b/apollo_localization/conf/localization_config.pb.txt @@ -0,0 +1 @@ +localization_type: RTK diff --git a/apollo_localization/conf/rtk_adapter.conf b/apollo_localization/conf/rtk_adapter.conf new file mode 100644 index 0000000..e3c11fe --- /dev/null +++ b/apollo_localization/conf/rtk_adapter.conf @@ -0,0 +1,21 @@ +config { + type: GPS + mode: RECEIVE_ONLY + message_history_limit: 50 +} +config { + type: IMU + mode: RECEIVE_ONLY + message_history_limit: 50 +} +config { + type: LOCALIZATION + mode: PUBLISH_ONLY + message_history_limit: 10 +} +config { + type: MONITOR + mode: PUBLISH_ONLY + message_history_limit: 10 +} +is_ros: true diff --git a/apollo_localization/include/apollo_localization/camera/camera_localization.h b/apollo_localization/include/apollo_localization/camera/camera_localization.h new file mode 100644 index 0000000..9b6d9c6 --- /dev/null +++ b/apollo_localization/include/apollo_localization/camera/camera_localization.h @@ -0,0 +1,113 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file localization_rtk.h + * @brief The class of CameraLocalization + */ + +#ifndef MODULES_LOCALIZATION_CAMERA_LOCALIZATION_CAMERA_H_ +#define MODULES_LOCALIZATION_CAMERA_LOCALIZATION_CAMERA_H_ + +#include +#include +#include +#include + +#include +#include + +#include "apollo_common/monitor/monitor.h" +#include "apollo_common/status/status.h" +#include "apollo_msgs/proto/localization/camera.pb.h" +#include "apollo_msgs/proto/localization/camera_parameter.pb.h" +#include "apollo_msgs/proto/localization/gps.pb.h" +#include "apollo_msgs/proto/localization/imu.pb.h" +#include "apollo_msgs/proto/localization/localization.pb.h" + +#include "apollo_localization/localization_base.h" + +/** + * @namespace apollo::localization + * @brief apollo::localization + */ +namespace apollo { +namespace localization { + +/** + * @class CameraLocalization + * + * @brief generate localization info based on Camera + */ +class CameraLocalization : public LocalizationBase { + public: + CameraLocalization(); + virtual ~CameraLocalization() = default; + + /** + * @brief module start function + * @return start status + */ + apollo::common::Status Start() override; + + /** + * @brief module stop function + * @return stop status + */ + apollo::common::Status Stop() override; + + private: + void OnTimer(const ros::TimerEvent &event); + bool PublishLocalization(); + void RunWatchDog(); + + bool PrepareLocalizationMsg(LocalizationEstimate *localization); + bool CreateLocalizationMsg(const ::apollo::localization::Gps &gps_msg, + const ::apollo::localization::Camera &camera_msg, + LocalizationEstimate *localization); + template + T InterpolateXYZ(const T &p1, const T &p2, const double &frac1); + + private: + ros::Timer timer_; + apollo::common::monitor::Monitor monitor_; + CameraParameter camera_parameter_; + double last_received_timestamp_sec_ = 0.0; + double last_reported_timestamp_sec_ = 0.0; + bool use_imu_ = false; + bool service_started_ = false; +}; + +} // namespace localization +} // namespace apollo + +#endif // MODULES_LOCALIZATION_Camera_LOCALIZATION_Camera_H_ diff --git a/apollo_localization/include/apollo_localization/common/localization_gflags.h b/apollo_localization/include/apollo_localization/common/localization_gflags.h new file mode 100644 index 0000000..3562b0b --- /dev/null +++ b/apollo_localization/include/apollo_localization/common/localization_gflags.h @@ -0,0 +1,74 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file localization_gflags.h + * @brief The gflags used by localization module + */ + +#ifndef MODEULES_LOCALIZATION_COMMON_LOCALIZATION_GFLAGS_H_ +#define MODEULES_LOCALIZATION_COMMON_LOCALIZATION_GFLAGS_H_ + +#include + +DECLARE_string(localization_module_name); + +DECLARE_double(localization_publish_freq); + +DECLARE_string(localization_config_file); +DECLARE_string(rtk_adapter_config_file); +DECLARE_string(camera_adapter_config_file); +DECLARE_string(camera_parameter_config_file); + +DECLARE_bool(enable_gps_imu_interprolate); +DECLARE_bool(enable_map_reference_unify); +DECLARE_bool(enable_watchdog); + +DECLARE_double(gps_time_delay_tolerance); +DECLARE_double(imu_time_delay_tolerance); +DECLARE_double(camera_time_delay_tolerance); +DECLARE_double(gps_imu_timestamp_sec_diff_tolerance); +DECLARE_double(timestamp_sec_tolerance); + +DECLARE_double(map_offset_x); +DECLARE_double(map_offset_y); +DECLARE_double(map_offset_z); + +DECLARE_int32(monitor_level); + +DECLARE_int32(report_threshold_err_num); +DECLARE_double(report_gps_imu_time_diff_threshold); + +DECLARE_bool(enable_gps_timestamp); +DECLARE_bool(enable_camera_timestamp); + +#endif // MODEULES_LOCALIZATION_COMMON_LOCALIZATION_GFLAGS_H_ diff --git a/apollo_localization/include/apollo_localization/decision.h b/apollo_localization/include/apollo_localization/decision.h new file mode 100644 index 0000000..70fda48 --- /dev/null +++ b/apollo_localization/include/apollo_localization/decision.h @@ -0,0 +1,69 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_DECISION_DECISION_H_ +#define MODULES_DECISION_DECISION_H_ + +#include + +#include + +#include "apollo_common/apollo_app.h" +#include "apollo_common/macro.h" + +/** + * @namespace apollo::decision + * @brief apollo::decision + */ +namespace apollo { +namespace decision { + +class Decision : public apollo::common::ApolloApp { + public: + std::string Name() const override; + apollo::common::Status Init() override; + apollo::common::Status Start() override; + void Stop() override; + virtual ~Decision() = default; + + private: + void OnTimer(const ros::TimerEvent& event); + void PublishDecision(); + + private: + ros::Timer timer_; +}; + +} // namespace decision +} // namespace apollo + +#endif // MODULES_DECISION_DECISION_H_ diff --git a/apollo_localization/include/apollo_localization/localization.h b/apollo_localization/include/apollo_localization/localization.h new file mode 100644 index 0000000..faab40c --- /dev/null +++ b/apollo_localization/include/apollo_localization/localization.h @@ -0,0 +1,103 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file localization.h + * @brief The class of Localization + */ + +#ifndef MODULES_LOCALIZATION_LOCALIZATION_H_ +#define MODULES_LOCALIZATION_LOCALIZATION_H_ + +#include +#include + +#include "apollo_common/apollo_app.h" +#include "apollo_common/status/status.h" +#include "apollo_common/util/factory.h" +#include "apollo_msgs/proto/localization/localization_config.pb.h" + +#include "apollo_localization/localization_base.h" + +/** + * @namespace apollo::localization + * @brief apollo::localization + */ +namespace apollo { +namespace localization { + +/** + * @class Localization + * + * @brief Localization module main class. It processes GPS and IMU as input, + * to generate localization info. + */ +class Localization : public apollo::common::ApolloApp { + public: + /** + * @brief module name + * @return module name + */ + std::string Name() const override; + + /** + * @brief module initialization function + * @return initialization status + */ + apollo::common::Status Init() override; + + /** + * @brief module start function + * @return start status + */ + apollo::common::Status Start() override; + + /** + * @brief module stop function + * @return stop status + */ + void Stop() override; + + private: + void RegisterLocalizationMethods(); + + std::unique_ptr localization_; + apollo::common::util::Factory + localization_factory_; + LocalizationConfig config_; +}; + +} // namespace localization +} // namespace apollo + +#endif // MODULES_LOCALIZATION_LOCALIZATION_H_ diff --git a/apollo_localization/include/apollo_localization/localization_base.h b/apollo_localization/include/apollo_localization/localization_base.h new file mode 100644 index 0000000..3869d42 --- /dev/null +++ b/apollo_localization/include/apollo_localization/localization_base.h @@ -0,0 +1,75 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file localization_base.h + * @brief The class of LocalizationBase + */ + +#ifndef MODULES_LOCALIZATION_LOCALIZATION_BASE_H_ +#define MODULES_LOCALIZATION_LOCALIZATION_BASE_H_ + +#include "apollo_common/status/status.h" + +/** + * @namespace apollo::localization + * @brief apollo::localization + */ +namespace apollo { +namespace localization { + +/** + * @class LocalizationBase + * + * @brief base class for Localization factory + */ +class LocalizationBase { + public: + virtual ~LocalizationBase() = default; + + /** + * @brief module start function + * @return start status + */ + virtual apollo::common::Status Start() = 0; + + /** + * @brief module stop function + * @return stop status + */ + virtual apollo::common::Status Stop() = 0; +}; + +} // namespace localization +} // namespace apollo + +#endif // MODULES_LOCALIZATION_LOCALIZATION_BASE_H_ diff --git a/apollo_localization/include/apollo_localization/rtk/rtk_localization.h b/apollo_localization/include/apollo_localization/rtk/rtk_localization.h new file mode 100644 index 0000000..adcf076 --- /dev/null +++ b/apollo_localization/include/apollo_localization/rtk/rtk_localization.h @@ -0,0 +1,116 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/** + * @file localization_rtk.h + * @brief The class of RTKLocalization + */ + +#ifndef MODULES_LOCALIZATION_RTK_RTK_LOCALIZATION_H_ +#define MODULES_LOCALIZATION_RTK_RTK_LOCALIZATION_H_ + +#include +#include +#include +#include + +#include +#include + +#include "apollo_common/monitor/monitor.h" +#include "apollo_common/status/status.h" +#include "apollo_msgs/proto/localization/gps.pb.h" +#include "apollo_msgs/proto/localization/imu.pb.h" +#include "apollo_msgs/proto/localization/localization.pb.h" + +#include "apollo_localization/localization_base.h" + +/** + * @namespace apollo::localization + * @brief apollo::localization + */ +namespace apollo { +namespace localization { + +/** + * @class RTKLocalization + * + * @brief generate localization info based on RTK + */ +class RTKLocalization : public LocalizationBase { + public: + RTKLocalization(); + virtual ~RTKLocalization() = default; + + /** + * @brief module start function + * @return start status + */ + apollo::common::Status Start() override; + + /** + * @brief module stop function + * @return stop status + */ + apollo::common::Status Stop() override; + + private: + void OnTimer(const ros::TimerEvent &event); + void PublishLocalization(); + void RunWatchDog(); + + void PrepareLocalizationMsg(LocalizationEstimate *localization); + void ComposeLocalizationMsg(const ::apollo::localization::Gps &gps, + const ::apollo::localization::Imu &imu, + LocalizationEstimate *localization); + bool FindMatchingIMU(const double gps_timestamp_sec, Imu *imu_msg); + void InterpolateIMU(const Imu &imu1, const Imu &imu2, + const double timestamp_sec, Imu *msgbuf); + template + T InterpolateXYZ(const T &p1, const T &p2, const double &frac1); + + private: + ros::Timer timer_; + apollo::common::monitor::Monitor monitor_; + const std::vector map_offset_; + double last_received_timestamp_sec_ = 0.0; + double last_reported_timestamp_sec_ = 0.0; + bool service_started_ = false; + + FRIEND_TEST(RTKLocalizationTest, InterpolateIMU); + FRIEND_TEST(RTKLocalizationTest, ComposeLocalizationMsg); +}; + +} // namespace localization +} // namespace apollo + +#endif // MODULES_LOCALIZATION_RTK_RTK_LOCALIZATION_H_ diff --git a/apollo_localization/launch/localization.launch b/apollo_localization/launch/localization.launch new file mode 100644 index 0000000..6b36c4e --- /dev/null +++ b/apollo_localization/launch/localization.launch @@ -0,0 +1,9 @@ + + + + \ No newline at end of file diff --git a/apollo_localization/package.xml b/apollo_localization/package.xml new file mode 100644 index 0000000..a132936 --- /dev/null +++ b/apollo_localization/package.xml @@ -0,0 +1,29 @@ + + + apollo_localization + 0.0.0 + The apollo_localization package + + forrest + TODO + + catkin + + roscpp + roscpp + roscpp + + apollo_msgs + apollo_msgs + apollo_msgs + + apollo_common + apollo_common + apollo_common + + + + + + + diff --git a/apollo_localization/src/camera/camera_localization.cc b/apollo_localization/src/camera/camera_localization.cc new file mode 100644 index 0000000..67a5701 --- /dev/null +++ b/apollo_localization/src/camera/camera_localization.cc @@ -0,0 +1,264 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_localization/camera/camera_localization.h" + +#include "apollo_common/adapters/adapter_manager.h" +#include "apollo_common/math/quaternion.h" +#include "apollo_common/time/time.h" +#include "apollo_common/util/file.h" + +#include "apollo_localization/common/localization_gflags.h" + +namespace apollo { +namespace localization { + +using ::Eigen::Vector3d; +using ::apollo::common::adapter::AdapterManager; +using ::apollo::common::adapter::ImuAdapter; +using ::apollo::common::monitor::MonitorMessageItem; +using ::apollo::common::monitor::MonitorBuffer; +using ::apollo::common::Status; +using ::apollo::common::time::Clock; + +CameraLocalization::CameraLocalization() + : monitor_(MonitorMessageItem::LOCALIZATION) {} + +Status CameraLocalization::Start() { + MonitorBuffer buffer(&monitor_); + if (!apollo::common::util::GetProtoFromFile( + FLAGS_camera_parameter_config_file, &camera_parameter_)) { + buffer.ERROR() << "Camera parameter is not initialized. Check " + << FLAGS_camera_parameter_config_file; + buffer.PrintLog(); + return Status(apollo::common::LOCALIZATION_ERROR, + "failed to load camera parameter"); + } + + AdapterManager::Init(FLAGS_camera_adapter_config_file); + // start ROS timer, one-shot = false, auto-start = true + const double duration = 1.0 / FLAGS_localization_publish_freq; + timer_ = AdapterManager::CreateTimer(ros::Duration(duration), + &CameraLocalization::OnTimer, this); + if (!AdapterManager::GetGps()) { + buffer.ERROR() << "GPS input not initialized. Check " + << FLAGS_camera_adapter_config_file; + buffer.PrintLog(); + return Status(apollo::common::LOCALIZATION_ERROR, "no GPS adapter"); + } + if (!AdapterManager::GetCamera()) { + buffer.ERROR() << "Camera input not initialized. Check " + << FLAGS_camera_adapter_config_file; + buffer.PrintLog(); + return Status(apollo::common::LOCALIZATION_ERROR, "no Camera adapter"); + } + // IMU is optional + if (!AdapterManager::GetImu()) { + buffer.INFO("IMU input not initialized. Check your adapter.conf file!"); + buffer.PrintLog(); + use_imu_ = false; + } else { + use_imu_ = true; + } + return Status::OK(); +} + +Status CameraLocalization::Stop() { + timer_.stop(); + return Status::OK(); +} + +void CameraLocalization::OnTimer(const ros::TimerEvent &event) { + double time_delay = apollo::common::time::ToSecond(Clock::Now()) - + last_received_timestamp_sec_; + MonitorBuffer buffer(&monitor_); + if (FLAGS_enable_gps_timestamp && + time_delay > FLAGS_gps_time_delay_tolerance) { + buffer.ERROR() << "GPS message time delay: " << time_delay; + buffer.PrintLog(); + } + if (FLAGS_enable_camera_timestamp && + time_delay > FLAGS_camera_time_delay_tolerance) { + AERROR << "Camera message time delay: " << time_delay; + buffer.ERROR() << "Camera message time delay: " << time_delay; + buffer.PrintLog(); + } + + // Take a snapshot of the current received messages. + AdapterManager::Observe(); + + if (AdapterManager::GetGps()->Empty()) { + AERROR << "GPS message buffer is empty."; + if (service_started_) { + buffer.ERROR("GPS message buffer is empty."); + } + return; + } + if (AdapterManager::GetCamera()->Empty()) { + AERROR << "Camera message buffer is empty."; + if (service_started_) { + buffer.ERROR("Camera message buffer is empty."); + } + return; + } + if (use_imu_ && AdapterManager::GetImu()->Empty()) { + AERROR << "Imu message buffer is empty."; + if (service_started_) { + buffer.ERROR("Imu message buffer is empty."); + } + return; + } + + // publish localization messages + if (!PublishLocalization()) { + buffer.ERROR("Publish localization failed"); + buffer.PrintLog(); + return; + } + service_started_ = true; + + // watch dog + RunWatchDog(); + + last_received_timestamp_sec_ = apollo::common::time::ToSecond(Clock::Now()); +} + +// TODO(Dong): Implement this function for camera based high accuracy +// localization. +bool CameraLocalization::CreateLocalizationMsg( + const ::apollo::localization::Gps &gps_msg, + const ::apollo::localization::Camera &camera_msg, + LocalizationEstimate *localization) { + localization->Clear(); + + // header + AdapterManager::FillLocalizationHeader(FLAGS_localization_module_name, + localization->mutable_header()); + if (FLAGS_enable_gps_timestamp) { + // copy time stamp, do NOT use Clock::Now() + localization->mutable_header()->set_timestamp_sec( + gps_msg.header().timestamp_sec()); + } + + if (!gps_msg.has_localization()) { + AERROR << "GPS has no localization field"; + return false; + } + + if (camera_msg.image().empty() || !camera_msg.width() == 0 || + !camera_msg.height()== 0) { + AERROR << "camera data is invalid"; + return false; + } + + // TODO(Dong): Get high accuracy position information from gps and camera + // image. + // const auto &gps_location = gps_msg.localization(); + // const auto &image = camera_msg.image(); + // const auto image_width = camera_msg.width(); + // const auto image_height = camera_msg.height(); + return true; +} + +bool CameraLocalization::PublishLocalization() { + LocalizationEstimate localization; + const auto &gps_msg = AdapterManager::GetGps()->GetLatestObserved(); + const auto &camera_msg = AdapterManager::GetCamera()->GetLatestObserved(); + // TODO(Dong): Implement how to apply camera parameter to camera data. + // + // TODO(Dong): Find the timestamp difference in GPS message and Camera + // message, do time alignment if necessary. + // + // TODO(Dong): Produce localization message based on GPS and Camera Data. + if (!CreateLocalizationMsg(gps_msg, camera_msg, &localization)) { + AERROR << "Failed to compose localization message"; + return false; + } + + // publish localization messages + AdapterManager::PublishLocalization(localization); + AINFO << "[OnTimer]: Localization message publish success!"; + return true; +} + +void CameraLocalization::RunWatchDog() { + if (!FLAGS_enable_watchdog) { + return; + } + + bool msg_lost = false; + + MonitorBuffer buffer(&monitor_); + + // check GPS time stamp against ROS timer + double gps_delay_sec = + apollo::common::time::ToSecond(Clock::Now()) - + AdapterManager::GetGps()->GetLatestObserved().header().timestamp_sec(); + int64_t gps_delay_cycle_cnt = + static_cast(gps_delay_sec * FLAGS_localization_publish_freq); + if (FLAGS_enable_gps_timestamp && + (gps_delay_cycle_cnt > FLAGS_report_threshold_err_num)) { + msg_lost = true; + + buffer.ERROR() << "Raw GPS Message Lost. GPS message is " + << gps_delay_cycle_cnt << " cycle " << gps_delay_sec + << " sec behind current time."; + buffer.PrintLog(); + } + + // check Camera time stamp against ROS timer + double camera_delay_sec = + apollo::common::time::ToSecond(Clock::Now()) - + AdapterManager::GetCamera()->GetLatestObserved().header().timestamp_sec(); + int64_t camera_delay_cycle_cnt = + static_cast(camera_delay_sec * FLAGS_localization_publish_freq); + if (FLAGS_enable_gps_timestamp && + camera_delay_cycle_cnt > FLAGS_report_threshold_err_num) { + msg_lost = true; + + buffer.ERROR() << "Raw Camera Message Lost. IMU message is " + << camera_delay_cycle_cnt << " cycle " << camera_delay_sec + << " sec behind current time."; + buffer.PrintLog(); + } + + // to prevent it from beeping continuously + if (msg_lost && (last_reported_timestamp_sec_ < 1. || + apollo::common::time::ToSecond(Clock::Now()) > + last_reported_timestamp_sec_ + 1.)) { + AERROR << "gps/camera frame lost!"; + last_reported_timestamp_sec_ = apollo::common::time::ToSecond(Clock::Now()); + } +} + +} // namespace localization +} // namespace apollo diff --git a/apollo_localization/src/common/localization_gflags.cc b/apollo_localization/src/common/localization_gflags.cc new file mode 100644 index 0000000..79cab8b --- /dev/null +++ b/apollo_localization/src/common/localization_gflags.cc @@ -0,0 +1,93 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_localization/common/localization_gflags.h" + +DEFINE_string(localization_module_name, "localization", + "localization module name"); + +DEFINE_double(localization_publish_freq, 100, + "localization publishing frequency."); + +DEFINE_string(rtk_adapter_config_file, + "modules/localization/conf/rtk_adapter.conf", + "rtk adapter configuration"); + +DEFINE_string(camera_adapter_config_file, + "modules/localization/conf/camera_adapter.conf", + "camera based localization adapter configuration"); + +DEFINE_string(camera_parameter_config_file, + "modules/localization/conf/camera_parameter.conf", + "camera parameter config in camera based localiztion"); + +DEFINE_string(localization_config_file, + "modules/localization/conf/localization_config.pb.txt", + "localization config file"); + +// features +DEFINE_bool(enable_gps_imu_interprolate, true, "enable GPU/IMU interprolate"); +DEFINE_bool(enable_map_reference_unify, true, + "enable IMU data convert to map reference"); +DEFINE_bool(enable_watchdog, true, "enable watchdog"); + +DEFINE_double(gps_time_delay_tolerance, 1.0, + "gps message time delay tolerance (sec)"); + +DEFINE_double(imu_time_delay_tolerance, 1.0, + "imu message time delay tolerance (sec)"); + +DEFINE_double(camera_time_delay_tolerance, 1.0, + "camera imu message time delay tolerance (sec)"); + +DEFINE_double(gps_imu_timestamp_sec_diff_tolerance, 20e-3, + "gps/imu timestamp diff tolerance (sec)"); + +DEFINE_double(timestamp_sec_tolerance, 10e-7, "timestamp second tolerance"); +// map offset +DEFINE_double(map_offset_x, 0.0, "map_offsite: x"); +DEFINE_double(map_offset_y, 0.0, "map_offsite: y"); +DEFINE_double(map_offset_z, 0.0, "map_offsite: z"); + +DEFINE_int32(monitor_level, 2, + "minimum log level(INFO=0; WARN=1;" + "ERROR=2;FATAL=3) for monitor msg"); + +DEFINE_int32(report_threshold_err_num, 10, "report threshold error num"); +DEFINE_double(report_gps_imu_time_diff_threshold, 0.02, + "report threshold of timestamp diff between gps and imu(sec)"); + +DEFINE_bool(enable_gps_timestamp, false, + "True to set gps timestamp as localization header timestamp"); + +DEFINE_bool(enable_camera_timestamp, false, + "True to set camera timestamp as localization header timestamp"); diff --git a/apollo_localization/src/localization.cc b/apollo_localization/src/localization.cc new file mode 100644 index 0000000..a63b9e8 --- /dev/null +++ b/apollo_localization/src/localization.cc @@ -0,0 +1,93 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_localization/localization.h" + +#include "apollo_common/log.h" +#include "apollo_common/util/file.h" + +#include "apollo_localization/camera/camera_localization.h" +#include "apollo_localization/common/localization_gflags.h" +#include "apollo_localization/rtk/rtk_localization.h" + +namespace apollo { +namespace localization { + +using apollo::common::Status; +using apollo::common::ErrorCode; + +std::string Localization::Name() const { + return FLAGS_localization_module_name; +} + +void Localization::RegisterLocalizationMethods() { + localization_factory_.Register( + LocalizationConfig::RTK, + []() -> LocalizationBase* { return new RTKLocalization(); }); + + // TODO(Dong): Implement camera based localization method. + localization_factory_.Register( + LocalizationConfig::CAMERA, + []() -> LocalizationBase* { return new CameraLocalization(); }); +} + +Status Localization::Init() { + RegisterLocalizationMethods(); + if (!apollo::common::util::GetProtoFromFile(FLAGS_localization_config_file, + &config_)) { + AERROR << "failed to load localization config file " + << FLAGS_localization_config_file; + return Status(ErrorCode::LOCALIZATION_ERROR, + "failed to load localization config file: " + + FLAGS_localization_config_file); + } + + return Status::OK(); +} + +Status Localization::Start() { + localization_ = + localization_factory_.CreateObject(config_.localization_type()); + if (!localization_) { + return Status(ErrorCode::LOCALIZATION_ERROR, + "localization is not initialized with config : " + + config_.DebugString()); + } + localization_->Start(); + + return Status::OK(); +} + +void Localization::Stop() {} + +} // namespace localization +} // namespace apollo diff --git a/apollo_localization/src/main.cc b/apollo_localization/src/main.cc new file mode 100644 index 0000000..7b22c8d --- /dev/null +++ b/apollo_localization/src/main.cc @@ -0,0 +1,36 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_common/apollo_app.h" +#include "apollo_localization/localization.h" + +APOLLO_MAIN(::apollo::localization::Localization) diff --git a/apollo_localization/src/rtk/rtk_localization.cc b/apollo_localization/src/rtk/rtk_localization.cc new file mode 100644 index 0000000..d717b8a --- /dev/null +++ b/apollo_localization/src/rtk/rtk_localization.cc @@ -0,0 +1,429 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_localization/rtk/rtk_localization.h" + +#include "apollo_common/adapters/adapter_manager.h" +#include "apollo_common/math/quaternion.h" +#include "apollo_common/time/time.h" + +#include "apollo_localization/common/localization_gflags.h" + +namespace apollo { +namespace localization { + +using ::Eigen::Vector3d; +using ::apollo::common::adapter::AdapterManager; +using ::apollo::common::adapter::ImuAdapter; +using ::apollo::common::monitor::MonitorMessageItem; +using ::apollo::common::Status; +using ::apollo::common::time::Clock; + +RTKLocalization::RTKLocalization() + : monitor_(MonitorMessageItem::LOCALIZATION), + map_offset_{FLAGS_map_offset_x, FLAGS_map_offset_y, FLAGS_map_offset_z} {} + +Status RTKLocalization::Start() { + AdapterManager::Init(FLAGS_rtk_adapter_config_file); + + // start ROS timer, one-shot = false, auto-start = true + const double duration = 1.0 / FLAGS_localization_publish_freq; + timer_ = AdapterManager::CreateTimer(ros::Duration(duration), + &RTKLocalization::OnTimer, this); + apollo::common::monitor::MonitorBuffer buffer(&monitor_); + if (!AdapterManager::GetGps()) { + buffer.ERROR() << "GPS input not initialized. Check file " + << FLAGS_rtk_adapter_config_file; + buffer.PrintLog(); + return Status(apollo::common::LOCALIZATION_ERROR, "no GPS adapter"); + } + if (!AdapterManager::GetImu()) { + buffer.ERROR("IMU input not initialized. Check your adapter.conf file!"); + buffer.PrintLog(); + return Status(apollo::common::LOCALIZATION_ERROR, "no IMU adapter"); + } + return Status::OK(); +} + +Status RTKLocalization::Stop() { + timer_.stop(); + return Status::OK(); +} + +void RTKLocalization::OnTimer(const ros::TimerEvent &event) { + double time_delay = apollo::common::time::ToSecond(Clock::Now()) - + last_received_timestamp_sec_; + apollo::common::monitor::MonitorBuffer buffer(&monitor_); + if (FLAGS_enable_gps_timestamp && + time_delay > FLAGS_gps_time_delay_tolerance) { + buffer.ERROR() << "GPS message time delay: " << time_delay; + buffer.PrintLog(); + } + + // Take a snapshot of the current received messages. + AdapterManager::Observe(); + + if (AdapterManager::GetGps()->Empty()) { + AERROR << "GPS message buffer is empty."; + if (service_started_) { + buffer.ERROR("GPS message buffer is empty."); + } + return; + } + if (AdapterManager::GetImu()->Empty()) { + AERROR << "IMU message buffer is empty."; + if (service_started_) { + buffer.ERROR("IMU message buffer is empty."); + } + return; + } + + // publish localization messages + PublishLocalization(); + service_started_ = true; + + // watch dog + RunWatchDog(); + + last_received_timestamp_sec_ = apollo::common::time::ToSecond(Clock::Now()); +} + +template +T RTKLocalization::InterpolateXYZ(const T &p1, const T &p2, + const double &frac1) { + T p; + double frac2 = 1.0 - frac1; + if (!std::isnan(p1.x()) && !std::isnan(p2.x())) { + p.set_x(p1.x() * frac2 + p2.x() * frac1); + } + if (!std::isnan(p1.y()) && !std::isnan(p2.y())) { + p.set_y(p1.y() * frac2 + p2.y() * frac1); + } + if (!std::isnan(p1.z()) && !std::isnan(p2.z())) { + p.set_z(p1.z() * frac2 + p2.z() * frac1); + } + return p; +} + +bool RTKLocalization::FindMatchingIMU(const double gps_timestamp_sec, + Imu *imu_msg) { + bool success = false; + + auto *imu_adapter = AdapterManager::GetImu(); + if (imu_adapter->Empty()) { + AERROR << "[FindMatchingIMU]: Cannot find Matching IMU. " + << "IMU message Queue is empty! GPS timestamp[" << gps_timestamp_sec + << "]"; + return success; + } + + // scan imu buffer, find first imu message that is newer than the given + // timestamp + ImuAdapter::Iterator imu_it = imu_adapter->begin(); + for (; imu_it != imu_adapter->end(); ++imu_it) { + if ((*imu_it)->header().timestamp_sec() - gps_timestamp_sec > + FLAGS_timestamp_sec_tolerance) { + break; + } + } + + success = true; + + if (imu_it != imu_adapter->end()) { // found one + if (imu_it == imu_adapter->begin()) { + AERROR << "[FindMatchingIMU]: IMU queue too short or request too old. " + << "Oldest timestamp[" + << imu_adapter->GetOldestObserved().header().timestamp_sec() + << "], Newest timestamp[" + << imu_adapter->GetLatestObserved().header().timestamp_sec() + << "], GPS timestamp[" << gps_timestamp_sec << "]"; + *imu_msg = imu_adapter->GetOldestObserved(); // the oldest imu + } else { + // here is the normal case + auto imu_it_1 = imu_it; + imu_it_1--; + InterpolateIMU(**imu_it_1, **imu_it, gps_timestamp_sec, imu_msg); + } + } else { + // give the newest imu, without extrapolation + *imu_msg = imu_adapter->GetLatestObserved(); + + if (fabs(imu_msg->header().timestamp_sec() - gps_timestamp_sec) > + FLAGS_report_gps_imu_time_diff_threshold) { + // 20ms threshold to report error + AERROR << "[FindMatchingIMU]: Cannot find Matching IMU. " + << "IMU messages too old" + << "Newest timestamp[" + << imu_adapter->GetLatestObserved().header().timestamp_sec() + << "], GPS timestamp[" << gps_timestamp_sec << "]"; + } + } + + return success; +} + +void RTKLocalization::InterpolateIMU(const Imu &imu1, const Imu &imu2, + const double timestamp_sec, Imu *imu_msg) { + if (timestamp_sec - imu1.header().timestamp_sec() < + FLAGS_timestamp_sec_tolerance) { + AERROR << "[InterpolateIMU]: the given time stamp[" << timestamp_sec + << "] is older than the 1st message[" + << imu1.header().timestamp_sec() << "]"; + *imu_msg = imu1; + } else if (timestamp_sec - imu2.header().timestamp_sec() > + FLAGS_timestamp_sec_tolerance) { + AERROR << "[InterpolateIMU]: the given time stamp[" << timestamp_sec + << "] is newer than the 2nd message[" + << imu2.header().timestamp_sec() << "]"; + *imu_msg = imu1; + } else { + *imu_msg = imu1; + imu_msg->mutable_header()->set_timestamp_sec(timestamp_sec); + + double time_diff = + imu2.header().timestamp_sec() - imu1.header().timestamp_sec(); + if (fabs(time_diff) >= 0.001) { + double frac1 = + (timestamp_sec - imu1.header().timestamp_sec()) / time_diff; + + if (imu1.has_imu() && imu1.imu().has_angular_velocity() && + imu2.has_imu() && imu2.imu().has_angular_velocity()) { + auto val = InterpolateXYZ(imu1.imu().angular_velocity(), + imu2.imu().angular_velocity(), frac1); + imu_msg->mutable_imu()->mutable_angular_velocity()->CopyFrom(val); + } + + if (imu1.has_imu() && imu1.imu().has_linear_acceleration() && + imu2.has_imu() && imu2.imu().has_linear_acceleration()) { + auto val = InterpolateXYZ(imu1.imu().linear_acceleration(), + imu2.imu().linear_acceleration(), frac1); + imu_msg->mutable_imu()->mutable_linear_acceleration()->CopyFrom(val); + } + } + } +} + +void RTKLocalization::PrepareLocalizationMsg( + LocalizationEstimate *localization) { + const auto &gps_msg = AdapterManager::GetGps()->GetLatestObserved(); + + bool imu_valid = true; + Imu imu_msg; + if (FLAGS_enable_gps_imu_interprolate) { + // find the matching gps and imu message + double gps_time_stamp = gps_msg.header().timestamp_sec(); + if (!FindMatchingIMU(gps_time_stamp, &imu_msg)) { + imu_valid = false; + } + } else { + imu_msg = AdapterManager::GetImu()->GetLatestObserved(); + } + + if (imu_valid && + fabs(gps_msg.header().timestamp_sec() - imu_msg.header().timestamp_sec() > + FLAGS_gps_imu_timestamp_sec_diff_tolerance)) { + // not the same time stamp, 20ms threshold + AERROR << "[PrepareLocalizationMsg]: time stamp of GPS[" + << gps_msg.header().timestamp_sec() + << "] is different from timestamp of IMU[" + << imu_msg.header().timestamp_sec() << "]"; + } + + ComposeLocalizationMsg(gps_msg, imu_msg, localization); +} + +void RTKLocalization::ComposeLocalizationMsg( + const ::apollo::localization::Gps &gps_msg, + const ::apollo::localization::Imu &imu_msg, + LocalizationEstimate *localization) { + localization->Clear(); + + // header + AdapterManager::FillLocalizationHeader(FLAGS_localization_module_name, + localization->mutable_header()); + if (FLAGS_enable_gps_timestamp) { + // copy time stamp, do NOT use Clock::Now() + localization->mutable_header()->set_timestamp_sec( + gps_msg.header().timestamp_sec()); + } + + // combine gps and imu + auto mutable_pose = localization->mutable_pose(); + if (gps_msg.has_localization()) { + const auto &pose = gps_msg.localization(); + + if (pose.has_position()) { + // position + // world frame -> map frame + mutable_pose->mutable_position()->set_x(pose.position().x() - + map_offset_[0]); + mutable_pose->mutable_position()->set_y(pose.position().y() - + map_offset_[1]); + mutable_pose->mutable_position()->set_z(pose.position().z() - + map_offset_[2]); + } + + // orientation + if (pose.has_orientation()) { + mutable_pose->mutable_orientation()->CopyFrom(pose.orientation()); + double heading = ::apollo::common::math::QuaternionToHeading( + pose.orientation().qw(), pose.orientation().qx(), + pose.orientation().qy(), pose.orientation().qz()); + mutable_pose->set_heading(heading); + } + // linear velocity + if (pose.has_linear_velocity()) { + mutable_pose->mutable_linear_velocity()->CopyFrom(pose.linear_velocity()); + } + } + + if (imu_msg.has_imu()) { + const auto &imu = imu_msg.imu(); + // linear acceleration + if (imu.has_linear_acceleration()) { + if (FLAGS_enable_map_reference_unify) { + if (localization->pose().has_orientation()) { + // linear_acceleration: + // convert from vehicle reference to map reference + Vector3d orig(imu.linear_acceleration().x(), + imu.linear_acceleration().y(), + imu.linear_acceleration().z()); + Vector3d vec = ::apollo::common::math::QuaternionRotate( + localization->pose().orientation(), orig); + mutable_pose->mutable_linear_acceleration()->set_x(vec[0]); + mutable_pose->mutable_linear_acceleration()->set_y(vec[1]); + mutable_pose->mutable_linear_acceleration()->set_z(vec[2]); + + // linear_acceleration_vfr + mutable_pose->mutable_linear_acceleration_vrf()->CopyFrom( + imu.linear_acceleration()); + + } else { + AERROR << "[PrepareLocalizationMsg]: " + << "fail to convert linear_acceleration"; + } + } else { + mutable_pose->mutable_linear_acceleration()->CopyFrom( + imu.linear_acceleration()); + } + } + + // angular velocity + if (imu.has_angular_velocity()) { + if (FLAGS_enable_map_reference_unify) { + if (localization->pose().has_orientation()) { + // angular_velocity: + // convert from vehicle reference to map reference + Vector3d orig(imu.angular_velocity().x(), imu.angular_velocity().y(), + imu.angular_velocity().z()); + Vector3d vec = ::apollo::common::math::QuaternionRotate( + localization->pose().orientation(), orig); + mutable_pose->mutable_angular_velocity()->set_x(vec[0]); + mutable_pose->mutable_angular_velocity()->set_y(vec[1]); + mutable_pose->mutable_angular_velocity()->set_z(vec[2]); + + // angular_velocity_vf + mutable_pose->mutable_angular_velocity_vrf()->CopyFrom( + imu.angular_velocity()); + } else { + AERROR << "[PrepareLocalizationMsg]: " + << "fail to convert angular_velocity"; + } + } else { + mutable_pose->mutable_angular_velocity()->CopyFrom( + imu.angular_velocity()); + } + } + } +} + +void RTKLocalization::PublishLocalization() { + LocalizationEstimate localization; + PrepareLocalizationMsg(&localization); + + // publish localization messages + AdapterManager::PublishLocalization(localization); + AINFO << "[OnTimer]: Localization message publish success!"; +} + +void RTKLocalization::RunWatchDog() { + if (!FLAGS_enable_watchdog) { + return; + } + + bool msg_lost = false; + + apollo::common::monitor::MonitorBuffer buffer(&monitor_); + + // check GPS time stamp against ROS timer + double gps_delay_sec = + apollo::common::time::ToSecond(Clock::Now()) - + AdapterManager::GetGps()->GetLatestObserved().header().timestamp_sec(); + int64_t gps_delay_cycle_cnt = + static_cast(gps_delay_sec * FLAGS_localization_publish_freq); + if (FLAGS_enable_gps_timestamp && + (gps_delay_cycle_cnt > FLAGS_report_threshold_err_num)) { + msg_lost = true; + + buffer.ERROR() << "Raw GPS Message Lost. GPS message is " + << gps_delay_cycle_cnt << " cycle " << gps_delay_sec + << " sec behind current time."; + buffer.PrintLog(); + } + + // check IMU time stamp against ROS timer + double imu_delay_sec = + apollo::common::time::ToSecond(Clock::Now()) - + AdapterManager::GetImu()->GetLatestObserved().header().timestamp_sec(); + int64_t imu_delay_cycle_cnt = + static_cast(imu_delay_sec * FLAGS_localization_publish_freq); + if (FLAGS_enable_gps_timestamp && + imu_delay_cycle_cnt > FLAGS_report_threshold_err_num) { + msg_lost = true; + + buffer.ERROR() << "Raw GPS Message Lost. IMU message is " + << imu_delay_cycle_cnt << " cycle " << imu_delay_sec + << " sec behind current time."; + buffer.PrintLog(); + } + + // to prevent it from beeping continuously + if (msg_lost && (last_reported_timestamp_sec_ < 1. || + apollo::common::time::ToSecond(Clock::Now()) > + last_reported_timestamp_sec_ + 1.)) { + AERROR << "gps/imu frame lost!"; + last_reported_timestamp_sec_ = apollo::common::time::ToSecond(Clock::Now()); + } +} + +} // namespace localization +} // namespace apollo diff --git a/apollo_msgs/CMakeLists.txt b/apollo_msgs/CMakeLists.txt new file mode 100644 index 0000000..9e3e8d7 --- /dev/null +++ b/apollo_msgs/CMakeLists.txt @@ -0,0 +1,81 @@ +cmake_minimum_required(VERSION 3.0.2) +project(apollo_msgs) + +add_compile_options(-std=c++17) +# set(CMAKE_BUILD_TYPE "Debug") +set(CMAKE_BUILD_TYPE "Release") + +# for proto message. +set(PROTO_LIB_NAME apollo_proto) +macro(SUBDIRLIST result curdir) + file(GLOB children RELATIVE ${curdir} ${curdir}/*) + set(dirlist "") + foreach(child ${children}) + if(IS_DIRECTORY ${curdir}/${child}) + LIST(APPEND dirlist ${child}) + endif() + endforeach() + set(${result} ${dirlist}) +endmacro() +set(PROTOBUF_PROTOC_EXECUTABLE protoc) +set(PROTO_HRDS) +set(PROTO_SRCS) +SUBDIRLIST(SUBDIRS ${PROJECT_SOURCE_DIR}/proto/${PROJECT_NAME}/proto) +foreach(subdir ${SUBDIRS}) + file(GLOB PROTO_FILES "${PROJECT_SOURCE_DIR}/proto/${PROJECT_NAME}/proto/${subdir}/*.proto") + message(STATUS "proto files: ${PROTO_FILES}") + set(proto_out_path ${PROJECT_SOURCE_DIR}/include) + file(REMOVE ${proto_out_path}) + file(MAKE_DIRECTORY ${proto_out_path}) + foreach(proto_file ${PROTO_FILES}) + get_filename_component(msg_path ${proto_file} ABSOLUTE) + get_filename_component(msg_name ${proto_file} NAME_WE) + list(APPEND PROTO_HRDS ${proto_out_path}/${PROJECT_NAME}/proto/${subdir}/${msg_name}.pb.h) + list(APPEND PROTO_SRCS ${proto_out_path}/${PROJECT_NAME}/proto/${subdir}/${msg_name}.pb.cc) + execute_process( + COMMAND ${PROTOBUF_PROTOC_EXECUTABLE} + # -I=${PROJECT_SOURCE_DIR}/proto/${subdir} + -I=${PROJECT_SOURCE_DIR}/proto + --cpp_out=${proto_out_path} ${msg_path} + # WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} + ) + endforeach() + message(STATUS "proto srcs: ${PROTO_SRCS}") +endforeach() + +find_package(catkin REQUIRED COMPONENTS + roscpp +) + +catkin_package( + INCLUDE_DIRS include + LIBRARIES ${PROTO_LIB_NAME} + CATKIN_DEPENDS roscpp +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} + /usr/include +) + +# proto message lib. +add_library(${PROTO_LIB_NAME} + ${PROTO_HRDS} + ${PROTO_SRCS} +) +target_link_libraries(${PROTO_LIB_NAME} + protobuf +) + +# install +install(DIRECTORY include/${PROJECT_NAME}/ + DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} + FILES_MATCHING PATTERN "*.h" + PATTERN ".svn" EXCLUDE +) + +install(TARGETS ${PROTO_LIB_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) diff --git a/apollo_msgs/README.md b/apollo_msgs/README.md new file mode 100644 index 0000000..6e5d336 --- /dev/null +++ b/apollo_msgs/README.md @@ -0,0 +1,3 @@ +# Msgs + +This module contains proto msgs file for Apollo. diff --git a/apollo_msgs/include/apollo_msgs/proto/canbus/chassis.pb.cc b/apollo_msgs/include/apollo_msgs/proto/canbus/chassis.pb.cc new file mode 100644 index 0000000..ae94267 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/canbus/chassis.pb.cc @@ -0,0 +1,1763 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/canbus/chassis.proto + +#include "apollo_msgs/proto/canbus/chassis.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Signal; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace apollo { +namespace canbus { +class SignalDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Signal_default_instance_; +class ChassisDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Chassis_default_instance_; +} // namespace canbus +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto { +static void InitDefaultsSignal() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_Signal_default_instance_; + new (ptr) ::apollo::canbus::Signal(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::Signal::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Signal = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsSignal}, {}}; + +static void InitDefaultsChassis() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_Chassis_default_instance_; + new (ptr) ::apollo::canbus::Chassis(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::Chassis::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_Chassis = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsChassis}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::scc_info_Signal.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_Signal.base); + ::google::protobuf::internal::InitSCC(&scc_info_Chassis.base); +} + +::google::protobuf::Metadata file_level_metadata[2]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[4]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Signal, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Signal, turn_signal_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Signal, high_beam_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Signal, low_beam_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Signal, horn_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Signal, emergency_light_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, engine_started_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, engine_rpm_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, speed_mps_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, odometer_m_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, fuel_range_m_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, throttle_percentage_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, brake_percentage_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, steering_percentage_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, steering_torque_nm_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, parking_brake_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, wiper_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, disengage_status_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, driving_mode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, error_code_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, gear_location_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, steering_timestamp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, chassis_error_mask_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, signal_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, high_beam_signal_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, low_beam_signal_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, left_turn_signal_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, right_turn_signal_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Chassis, horn_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::canbus::Signal)}, + { 10, -1, sizeof(::apollo::canbus::Chassis)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::canbus::_Signal_default_instance_), + reinterpret_cast(&::apollo::canbus::_Chassis_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/canbus/chassis.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 2); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n&apollo_msgs/proto/canbus/chassis.proto" + "\022\rapollo.canbus\032%apollo_msgs/proto/commo" + "n/header.proto\"\307\001\n\006Signal\0225\n\013turn_signal" + "\030\001 \001(\0162 .apollo.canbus.Signal.TurnSignal" + "\022\021\n\thigh_beam\030\002 \001(\010\022\020\n\010low_beam\030\003 \001(\010\022\014\n" + "\004horn\030\004 \001(\010\022\027\n\017emergency_light\030\005 \001(\010\":\n\n" + "TurnSignal\022\r\n\tTURN_NONE\020\000\022\r\n\tTURN_LEFT\020\001" + "\022\016\n\nTURN_RIGHT\020\002\"\334\010\n\007Chassis\022\026\n\016engine_s" + "tarted\030\003 \001(\010\022\022\n\nengine_rpm\030\004 \001(\002\022\021\n\tspee" + "d_mps\030\005 \001(\002\022\022\n\nodometer_m\030\006 \001(\002\022\024\n\014fuel_" + "range_m\030\007 \001(\005\022\033\n\023throttle_percentage\030\010 \001" + "(\002\022\030\n\020brake_percentage\030\t \001(\002\022\033\n\023steering" + "_percentage\030\013 \001(\002\022\032\n\022steering_torque_nm\030" + "\014 \001(\002\022\025\n\rparking_brake\030\r \001(\010\022\r\n\005wiper\030\023 " + "\001(\010\022\030\n\020disengage_status\030\024 \001(\010\0228\n\014driving" + "_mode\030\025 \001(\0162\".apollo.canbus.Chassis.Driv" + "ingMode\0224\n\nerror_code\030\026 \001(\0162 .apollo.can" + "bus.Chassis.ErrorCode\022:\n\rgear_location\030\027" + " \001(\0162#.apollo.canbus.Chassis.GearPositio" + "n\022\032\n\022steering_timestamp\030\030 \001(\001\022%\n\006header\030" + "\031 \001(\0132\025.apollo.common.Header\022\032\n\022chassis_" + "error_mask\030\032 \001(\005\022%\n\006signal\030\033 \001(\0132\025.apoll" + "o.canbus.Signal\022\030\n\020high_beam_signal\030\016 \001(" + "\010\022\027\n\017low_beam_signal\030\017 \001(\010\022\030\n\020left_turn_" + "signal\030\020 \001(\010\022\031\n\021right_turn_signal\030\021 \001(\010\022" + "\014\n\004horn\030\022 \001(\010\"y\n\013DrivingMode\022\023\n\017COMPLETE" + "_MANUAL\020\000\022\027\n\023COMPLETE_AUTO_DRIVE\020\001\022\023\n\017AU" + "TO_STEER_ONLY\020\002\022\023\n\017AUTO_SPEED_ONLY\020\003\022\022\n\016" + "EMERGENCY_MODE\020\004\"\216\001\n\tErrorCode\022\014\n\010NO_ERR" + "OR\020\000\022\025\n\021CMD_NOT_IN_PERIOD\020\001\022\021\n\rCHASSIS_E" + "RROR\020\002\022\027\n\023MANUAL_INTERVENTION\020\003\022\035\n\031CHASS" + "IS_CAN_NOT_IN_PERIOD\020\004\022\021\n\rUNKNOWN_ERROR\020" + "\005\"\203\001\n\014GearPosition\022\020\n\014GEAR_NEUTRAL\020\000\022\016\n\n" + "GEAR_DRIVE\020\001\022\020\n\014GEAR_REVERSE\020\002\022\020\n\014GEAR_P" + "ARKING\020\003\022\014\n\010GEAR_LOW\020\004\022\020\n\014GEAR_INVALID\020\005" + "\022\r\n\tGEAR_NONE\020\006b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 1423); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/canbus/chassis.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto +namespace apollo { +namespace canbus { +const ::google::protobuf::EnumDescriptor* Signal_TurnSignal_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::file_level_enum_descriptors[0]; +} +bool Signal_TurnSignal_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Signal_TurnSignal Signal::TURN_NONE; +const Signal_TurnSignal Signal::TURN_LEFT; +const Signal_TurnSignal Signal::TURN_RIGHT; +const Signal_TurnSignal Signal::TurnSignal_MIN; +const Signal_TurnSignal Signal::TurnSignal_MAX; +const int Signal::TurnSignal_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* Chassis_DrivingMode_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::file_level_enum_descriptors[1]; +} +bool Chassis_DrivingMode_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Chassis_DrivingMode Chassis::COMPLETE_MANUAL; +const Chassis_DrivingMode Chassis::COMPLETE_AUTO_DRIVE; +const Chassis_DrivingMode Chassis::AUTO_STEER_ONLY; +const Chassis_DrivingMode Chassis::AUTO_SPEED_ONLY; +const Chassis_DrivingMode Chassis::EMERGENCY_MODE; +const Chassis_DrivingMode Chassis::DrivingMode_MIN; +const Chassis_DrivingMode Chassis::DrivingMode_MAX; +const int Chassis::DrivingMode_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* Chassis_ErrorCode_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::file_level_enum_descriptors[2]; +} +bool Chassis_ErrorCode_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Chassis_ErrorCode Chassis::NO_ERROR; +const Chassis_ErrorCode Chassis::CMD_NOT_IN_PERIOD; +const Chassis_ErrorCode Chassis::CHASSIS_ERROR; +const Chassis_ErrorCode Chassis::MANUAL_INTERVENTION; +const Chassis_ErrorCode Chassis::CHASSIS_CAN_NOT_IN_PERIOD; +const Chassis_ErrorCode Chassis::UNKNOWN_ERROR; +const Chassis_ErrorCode Chassis::ErrorCode_MIN; +const Chassis_ErrorCode Chassis::ErrorCode_MAX; +const int Chassis::ErrorCode_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* Chassis_GearPosition_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::file_level_enum_descriptors[3]; +} +bool Chassis_GearPosition_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + case 6: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Chassis_GearPosition Chassis::GEAR_NEUTRAL; +const Chassis_GearPosition Chassis::GEAR_DRIVE; +const Chassis_GearPosition Chassis::GEAR_REVERSE; +const Chassis_GearPosition Chassis::GEAR_PARKING; +const Chassis_GearPosition Chassis::GEAR_LOW; +const Chassis_GearPosition Chassis::GEAR_INVALID; +const Chassis_GearPosition Chassis::GEAR_NONE; +const Chassis_GearPosition Chassis::GearPosition_MIN; +const Chassis_GearPosition Chassis::GearPosition_MAX; +const int Chassis::GearPosition_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +// =================================================================== + +void Signal::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Signal::kTurnSignalFieldNumber; +const int Signal::kHighBeamFieldNumber; +const int Signal::kLowBeamFieldNumber; +const int Signal::kHornFieldNumber; +const int Signal::kEmergencyLightFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Signal::Signal() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::scc_info_Signal.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.Signal) +} +Signal::Signal(const Signal& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&turn_signal_, &from.turn_signal_, + static_cast(reinterpret_cast(&emergency_light_) - + reinterpret_cast(&turn_signal_)) + sizeof(emergency_light_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.Signal) +} + +void Signal::SharedCtor() { + ::memset(&turn_signal_, 0, static_cast( + reinterpret_cast(&emergency_light_) - + reinterpret_cast(&turn_signal_)) + sizeof(emergency_light_)); +} + +Signal::~Signal() { + // @@protoc_insertion_point(destructor:apollo.canbus.Signal) + SharedDtor(); +} + +void Signal::SharedDtor() { +} + +void Signal::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Signal::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Signal& Signal::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::scc_info_Signal.base); + return *internal_default_instance(); +} + + +void Signal::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.Signal) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&turn_signal_, 0, static_cast( + reinterpret_cast(&emergency_light_) - + reinterpret_cast(&turn_signal_)) + sizeof(emergency_light_)); + _internal_metadata_.Clear(); +} + +bool Signal::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.Signal) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.canbus.Signal.TurnSignal turn_signal = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_turn_signal(static_cast< ::apollo::canbus::Signal_TurnSignal >(value)); + } else { + goto handle_unusual; + } + break; + } + + // bool high_beam = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &high_beam_))); + } else { + goto handle_unusual; + } + break; + } + + // bool low_beam = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &low_beam_))); + } else { + goto handle_unusual; + } + break; + } + + // bool horn = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &horn_))); + } else { + goto handle_unusual; + } + break; + } + + // bool emergency_light = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(40u /* 40 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &emergency_light_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.Signal) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.Signal) + return false; +#undef DO_ +} + +void Signal::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.Signal) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.canbus.Signal.TurnSignal turn_signal = 1; + if (this->turn_signal() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->turn_signal(), output); + } + + // bool high_beam = 2; + if (this->high_beam() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->high_beam(), output); + } + + // bool low_beam = 3; + if (this->low_beam() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(3, this->low_beam(), output); + } + + // bool horn = 4; + if (this->horn() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(4, this->horn(), output); + } + + // bool emergency_light = 5; + if (this->emergency_light() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(5, this->emergency_light(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.Signal) +} + +::google::protobuf::uint8* Signal::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.Signal) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.canbus.Signal.TurnSignal turn_signal = 1; + if (this->turn_signal() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->turn_signal(), target); + } + + // bool high_beam = 2; + if (this->high_beam() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->high_beam(), target); + } + + // bool low_beam = 3; + if (this->low_beam() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(3, this->low_beam(), target); + } + + // bool horn = 4; + if (this->horn() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(4, this->horn(), target); + } + + // bool emergency_light = 5; + if (this->emergency_light() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(5, this->emergency_light(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.Signal) + return target; +} + +size_t Signal::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.Signal) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.canbus.Signal.TurnSignal turn_signal = 1; + if (this->turn_signal() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->turn_signal()); + } + + // bool high_beam = 2; + if (this->high_beam() != 0) { + total_size += 1 + 1; + } + + // bool low_beam = 3; + if (this->low_beam() != 0) { + total_size += 1 + 1; + } + + // bool horn = 4; + if (this->horn() != 0) { + total_size += 1 + 1; + } + + // bool emergency_light = 5; + if (this->emergency_light() != 0) { + total_size += 1 + 1; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Signal::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.Signal) + GOOGLE_DCHECK_NE(&from, this); + const Signal* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.Signal) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.Signal) + MergeFrom(*source); + } +} + +void Signal::MergeFrom(const Signal& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.Signal) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.turn_signal() != 0) { + set_turn_signal(from.turn_signal()); + } + if (from.high_beam() != 0) { + set_high_beam(from.high_beam()); + } + if (from.low_beam() != 0) { + set_low_beam(from.low_beam()); + } + if (from.horn() != 0) { + set_horn(from.horn()); + } + if (from.emergency_light() != 0) { + set_emergency_light(from.emergency_light()); + } +} + +void Signal::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.Signal) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Signal::CopyFrom(const Signal& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.Signal) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Signal::IsInitialized() const { + return true; +} + +void Signal::Swap(Signal* other) { + if (other == this) return; + InternalSwap(other); +} +void Signal::InternalSwap(Signal* other) { + using std::swap; + swap(turn_signal_, other->turn_signal_); + swap(high_beam_, other->high_beam_); + swap(low_beam_, other->low_beam_); + swap(horn_, other->horn_); + swap(emergency_light_, other->emergency_light_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Signal::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Chassis::InitAsDefaultInstance() { + ::apollo::canbus::_Chassis_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); + ::apollo::canbus::_Chassis_default_instance_._instance.get_mutable()->signal_ = const_cast< ::apollo::canbus::Signal*>( + ::apollo::canbus::Signal::internal_default_instance()); +} +void Chassis::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Chassis::kEngineStartedFieldNumber; +const int Chassis::kEngineRpmFieldNumber; +const int Chassis::kSpeedMpsFieldNumber; +const int Chassis::kOdometerMFieldNumber; +const int Chassis::kFuelRangeMFieldNumber; +const int Chassis::kThrottlePercentageFieldNumber; +const int Chassis::kBrakePercentageFieldNumber; +const int Chassis::kSteeringPercentageFieldNumber; +const int Chassis::kSteeringTorqueNmFieldNumber; +const int Chassis::kParkingBrakeFieldNumber; +const int Chassis::kWiperFieldNumber; +const int Chassis::kDisengageStatusFieldNumber; +const int Chassis::kDrivingModeFieldNumber; +const int Chassis::kErrorCodeFieldNumber; +const int Chassis::kGearLocationFieldNumber; +const int Chassis::kSteeringTimestampFieldNumber; +const int Chassis::kHeaderFieldNumber; +const int Chassis::kChassisErrorMaskFieldNumber; +const int Chassis::kSignalFieldNumber; +const int Chassis::kHighBeamSignalFieldNumber; +const int Chassis::kLowBeamSignalFieldNumber; +const int Chassis::kLeftTurnSignalFieldNumber; +const int Chassis::kRightTurnSignalFieldNumber; +const int Chassis::kHornFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Chassis::Chassis() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::scc_info_Chassis.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.Chassis) +} +Chassis::Chassis(const Chassis& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + if (from.has_signal()) { + signal_ = new ::apollo::canbus::Signal(*from.signal_); + } else { + signal_ = NULL; + } + ::memcpy(&engine_rpm_, &from.engine_rpm_, + static_cast(reinterpret_cast(&chassis_error_mask_) - + reinterpret_cast(&engine_rpm_)) + sizeof(chassis_error_mask_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.Chassis) +} + +void Chassis::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&chassis_error_mask_) - + reinterpret_cast(&header_)) + sizeof(chassis_error_mask_)); +} + +Chassis::~Chassis() { + // @@protoc_insertion_point(destructor:apollo.canbus.Chassis) + SharedDtor(); +} + +void Chassis::SharedDtor() { + if (this != internal_default_instance()) delete header_; + if (this != internal_default_instance()) delete signal_; +} + +void Chassis::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Chassis::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Chassis& Chassis::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::scc_info_Chassis.base); + return *internal_default_instance(); +} + + +void Chassis::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.Chassis) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + if (GetArenaNoVirtual() == NULL && signal_ != NULL) { + delete signal_; + } + signal_ = NULL; + ::memset(&engine_rpm_, 0, static_cast( + reinterpret_cast(&chassis_error_mask_) - + reinterpret_cast(&engine_rpm_)) + sizeof(chassis_error_mask_)); + _internal_metadata_.Clear(); +} + +bool Chassis::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.Chassis) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool engine_started = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &engine_started_))); + } else { + goto handle_unusual; + } + break; + } + + // float engine_rpm = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(37u /* 37 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &engine_rpm_))); + } else { + goto handle_unusual; + } + break; + } + + // float speed_mps = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(45u /* 45 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &speed_mps_))); + } else { + goto handle_unusual; + } + break; + } + + // float odometer_m = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(53u /* 53 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &odometer_m_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 fuel_range_m = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(56u /* 56 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &fuel_range_m_))); + } else { + goto handle_unusual; + } + break; + } + + // float throttle_percentage = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(69u /* 69 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &throttle_percentage_))); + } else { + goto handle_unusual; + } + break; + } + + // float brake_percentage = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(77u /* 77 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &brake_percentage_))); + } else { + goto handle_unusual; + } + break; + } + + // float steering_percentage = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(93u /* 93 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &steering_percentage_))); + } else { + goto handle_unusual; + } + break; + } + + // float steering_torque_nm = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(101u /* 101 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &steering_torque_nm_))); + } else { + goto handle_unusual; + } + break; + } + + // bool parking_brake = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(104u /* 104 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &parking_brake_))); + } else { + goto handle_unusual; + } + break; + } + + // bool high_beam_signal = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(112u /* 112 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &high_beam_signal_))); + } else { + goto handle_unusual; + } + break; + } + + // bool low_beam_signal = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(120u /* 120 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &low_beam_signal_))); + } else { + goto handle_unusual; + } + break; + } + + // bool left_turn_signal = 16; + case 16: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(128u /* 128 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &left_turn_signal_))); + } else { + goto handle_unusual; + } + break; + } + + // bool right_turn_signal = 17; + case 17: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(136u /* 136 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &right_turn_signal_))); + } else { + goto handle_unusual; + } + break; + } + + // bool horn = 18; + case 18: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(144u /* 144 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &horn_))); + } else { + goto handle_unusual; + } + break; + } + + // bool wiper = 19; + case 19: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(152u /* 152 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &wiper_))); + } else { + goto handle_unusual; + } + break; + } + + // bool disengage_status = 20; + case 20: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(160u /* 160 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &disengage_status_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 21; + case 21: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(168u /* 168 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_driving_mode(static_cast< ::apollo::canbus::Chassis_DrivingMode >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Chassis.ErrorCode error_code = 22; + case 22: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(176u /* 176 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_error_code(static_cast< ::apollo::canbus::Chassis_ErrorCode >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Chassis.GearPosition gear_location = 23; + case 23: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(184u /* 184 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_gear_location(static_cast< ::apollo::canbus::Chassis_GearPosition >(value)); + } else { + goto handle_unusual; + } + break; + } + + // double steering_timestamp = 24; + case 24: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(193u /* 193 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steering_timestamp_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Header header = 25; + case 25: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(202u /* 202 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // int32 chassis_error_mask = 26; + case 26: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(208u /* 208 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &chassis_error_mask_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Signal signal = 27; + case 27: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(218u /* 218 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_signal())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.Chassis) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.Chassis) + return false; +#undef DO_ +} + +void Chassis::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.Chassis) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool engine_started = 3; + if (this->engine_started() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(3, this->engine_started(), output); + } + + // float engine_rpm = 4; + if (this->engine_rpm() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->engine_rpm(), output); + } + + // float speed_mps = 5; + if (this->speed_mps() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(5, this->speed_mps(), output); + } + + // float odometer_m = 6; + if (this->odometer_m() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(6, this->odometer_m(), output); + } + + // int32 fuel_range_m = 7; + if (this->fuel_range_m() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(7, this->fuel_range_m(), output); + } + + // float throttle_percentage = 8; + if (this->throttle_percentage() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(8, this->throttle_percentage(), output); + } + + // float brake_percentage = 9; + if (this->brake_percentage() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(9, this->brake_percentage(), output); + } + + // float steering_percentage = 11; + if (this->steering_percentage() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(11, this->steering_percentage(), output); + } + + // float steering_torque_nm = 12; + if (this->steering_torque_nm() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(12, this->steering_torque_nm(), output); + } + + // bool parking_brake = 13; + if (this->parking_brake() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(13, this->parking_brake(), output); + } + + // bool high_beam_signal = 14; + if (this->high_beam_signal() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(14, this->high_beam_signal(), output); + } + + // bool low_beam_signal = 15; + if (this->low_beam_signal() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(15, this->low_beam_signal(), output); + } + + // bool left_turn_signal = 16; + if (this->left_turn_signal() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(16, this->left_turn_signal(), output); + } + + // bool right_turn_signal = 17; + if (this->right_turn_signal() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(17, this->right_turn_signal(), output); + } + + // bool horn = 18; + if (this->horn() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(18, this->horn(), output); + } + + // bool wiper = 19; + if (this->wiper() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(19, this->wiper(), output); + } + + // bool disengage_status = 20; + if (this->disengage_status() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(20, this->disengage_status(), output); + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 21; + if (this->driving_mode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 21, this->driving_mode(), output); + } + + // .apollo.canbus.Chassis.ErrorCode error_code = 22; + if (this->error_code() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 22, this->error_code(), output); + } + + // .apollo.canbus.Chassis.GearPosition gear_location = 23; + if (this->gear_location() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 23, this->gear_location(), output); + } + + // double steering_timestamp = 24; + if (this->steering_timestamp() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(24, this->steering_timestamp(), output); + } + + // .apollo.common.Header header = 25; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 25, this->_internal_header(), output); + } + + // int32 chassis_error_mask = 26; + if (this->chassis_error_mask() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(26, this->chassis_error_mask(), output); + } + + // .apollo.canbus.Signal signal = 27; + if (this->has_signal()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 27, this->_internal_signal(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.Chassis) +} + +::google::protobuf::uint8* Chassis::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.Chassis) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool engine_started = 3; + if (this->engine_started() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(3, this->engine_started(), target); + } + + // float engine_rpm = 4; + if (this->engine_rpm() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->engine_rpm(), target); + } + + // float speed_mps = 5; + if (this->speed_mps() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(5, this->speed_mps(), target); + } + + // float odometer_m = 6; + if (this->odometer_m() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(6, this->odometer_m(), target); + } + + // int32 fuel_range_m = 7; + if (this->fuel_range_m() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(7, this->fuel_range_m(), target); + } + + // float throttle_percentage = 8; + if (this->throttle_percentage() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(8, this->throttle_percentage(), target); + } + + // float brake_percentage = 9; + if (this->brake_percentage() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(9, this->brake_percentage(), target); + } + + // float steering_percentage = 11; + if (this->steering_percentage() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(11, this->steering_percentage(), target); + } + + // float steering_torque_nm = 12; + if (this->steering_torque_nm() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(12, this->steering_torque_nm(), target); + } + + // bool parking_brake = 13; + if (this->parking_brake() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(13, this->parking_brake(), target); + } + + // bool high_beam_signal = 14; + if (this->high_beam_signal() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(14, this->high_beam_signal(), target); + } + + // bool low_beam_signal = 15; + if (this->low_beam_signal() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(15, this->low_beam_signal(), target); + } + + // bool left_turn_signal = 16; + if (this->left_turn_signal() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(16, this->left_turn_signal(), target); + } + + // bool right_turn_signal = 17; + if (this->right_turn_signal() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(17, this->right_turn_signal(), target); + } + + // bool horn = 18; + if (this->horn() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(18, this->horn(), target); + } + + // bool wiper = 19; + if (this->wiper() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(19, this->wiper(), target); + } + + // bool disengage_status = 20; + if (this->disengage_status() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(20, this->disengage_status(), target); + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 21; + if (this->driving_mode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 21, this->driving_mode(), target); + } + + // .apollo.canbus.Chassis.ErrorCode error_code = 22; + if (this->error_code() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 22, this->error_code(), target); + } + + // .apollo.canbus.Chassis.GearPosition gear_location = 23; + if (this->gear_location() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 23, this->gear_location(), target); + } + + // double steering_timestamp = 24; + if (this->steering_timestamp() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(24, this->steering_timestamp(), target); + } + + // .apollo.common.Header header = 25; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 25, this->_internal_header(), deterministic, target); + } + + // int32 chassis_error_mask = 26; + if (this->chassis_error_mask() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(26, this->chassis_error_mask(), target); + } + + // .apollo.canbus.Signal signal = 27; + if (this->has_signal()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 27, this->_internal_signal(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.Chassis) + return target; +} + +size_t Chassis::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.Chassis) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.Header header = 25; + if (this->has_header()) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.canbus.Signal signal = 27; + if (this->has_signal()) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *signal_); + } + + // float engine_rpm = 4; + if (this->engine_rpm() != 0) { + total_size += 1 + 4; + } + + // float speed_mps = 5; + if (this->speed_mps() != 0) { + total_size += 1 + 4; + } + + // float odometer_m = 6; + if (this->odometer_m() != 0) { + total_size += 1 + 4; + } + + // int32 fuel_range_m = 7; + if (this->fuel_range_m() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->fuel_range_m()); + } + + // float throttle_percentage = 8; + if (this->throttle_percentage() != 0) { + total_size += 1 + 4; + } + + // float brake_percentage = 9; + if (this->brake_percentage() != 0) { + total_size += 1 + 4; + } + + // float steering_percentage = 11; + if (this->steering_percentage() != 0) { + total_size += 1 + 4; + } + + // float steering_torque_nm = 12; + if (this->steering_torque_nm() != 0) { + total_size += 1 + 4; + } + + // bool engine_started = 3; + if (this->engine_started() != 0) { + total_size += 1 + 1; + } + + // bool parking_brake = 13; + if (this->parking_brake() != 0) { + total_size += 1 + 1; + } + + // bool wiper = 19; + if (this->wiper() != 0) { + total_size += 2 + 1; + } + + // bool disengage_status = 20; + if (this->disengage_status() != 0) { + total_size += 2 + 1; + } + + // bool high_beam_signal = 14; + if (this->high_beam_signal() != 0) { + total_size += 1 + 1; + } + + // bool low_beam_signal = 15; + if (this->low_beam_signal() != 0) { + total_size += 1 + 1; + } + + // bool left_turn_signal = 16; + if (this->left_turn_signal() != 0) { + total_size += 2 + 1; + } + + // bool right_turn_signal = 17; + if (this->right_turn_signal() != 0) { + total_size += 2 + 1; + } + + // bool horn = 18; + if (this->horn() != 0) { + total_size += 2 + 1; + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 21; + if (this->driving_mode() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->driving_mode()); + } + + // .apollo.canbus.Chassis.ErrorCode error_code = 22; + if (this->error_code() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->error_code()); + } + + // .apollo.canbus.Chassis.GearPosition gear_location = 23; + if (this->gear_location() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->gear_location()); + } + + // double steering_timestamp = 24; + if (this->steering_timestamp() != 0) { + total_size += 2 + 8; + } + + // int32 chassis_error_mask = 26; + if (this->chassis_error_mask() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->chassis_error_mask()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Chassis::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.Chassis) + GOOGLE_DCHECK_NE(&from, this); + const Chassis* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.Chassis) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.Chassis) + MergeFrom(*source); + } +} + +void Chassis::MergeFrom(const Chassis& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.Chassis) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.has_signal()) { + mutable_signal()->::apollo::canbus::Signal::MergeFrom(from.signal()); + } + if (from.engine_rpm() != 0) { + set_engine_rpm(from.engine_rpm()); + } + if (from.speed_mps() != 0) { + set_speed_mps(from.speed_mps()); + } + if (from.odometer_m() != 0) { + set_odometer_m(from.odometer_m()); + } + if (from.fuel_range_m() != 0) { + set_fuel_range_m(from.fuel_range_m()); + } + if (from.throttle_percentage() != 0) { + set_throttle_percentage(from.throttle_percentage()); + } + if (from.brake_percentage() != 0) { + set_brake_percentage(from.brake_percentage()); + } + if (from.steering_percentage() != 0) { + set_steering_percentage(from.steering_percentage()); + } + if (from.steering_torque_nm() != 0) { + set_steering_torque_nm(from.steering_torque_nm()); + } + if (from.engine_started() != 0) { + set_engine_started(from.engine_started()); + } + if (from.parking_brake() != 0) { + set_parking_brake(from.parking_brake()); + } + if (from.wiper() != 0) { + set_wiper(from.wiper()); + } + if (from.disengage_status() != 0) { + set_disengage_status(from.disengage_status()); + } + if (from.high_beam_signal() != 0) { + set_high_beam_signal(from.high_beam_signal()); + } + if (from.low_beam_signal() != 0) { + set_low_beam_signal(from.low_beam_signal()); + } + if (from.left_turn_signal() != 0) { + set_left_turn_signal(from.left_turn_signal()); + } + if (from.right_turn_signal() != 0) { + set_right_turn_signal(from.right_turn_signal()); + } + if (from.horn() != 0) { + set_horn(from.horn()); + } + if (from.driving_mode() != 0) { + set_driving_mode(from.driving_mode()); + } + if (from.error_code() != 0) { + set_error_code(from.error_code()); + } + if (from.gear_location() != 0) { + set_gear_location(from.gear_location()); + } + if (from.steering_timestamp() != 0) { + set_steering_timestamp(from.steering_timestamp()); + } + if (from.chassis_error_mask() != 0) { + set_chassis_error_mask(from.chassis_error_mask()); + } +} + +void Chassis::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.Chassis) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Chassis::CopyFrom(const Chassis& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.Chassis) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Chassis::IsInitialized() const { + return true; +} + +void Chassis::Swap(Chassis* other) { + if (other == this) return; + InternalSwap(other); +} +void Chassis::InternalSwap(Chassis* other) { + using std::swap; + swap(header_, other->header_); + swap(signal_, other->signal_); + swap(engine_rpm_, other->engine_rpm_); + swap(speed_mps_, other->speed_mps_); + swap(odometer_m_, other->odometer_m_); + swap(fuel_range_m_, other->fuel_range_m_); + swap(throttle_percentage_, other->throttle_percentage_); + swap(brake_percentage_, other->brake_percentage_); + swap(steering_percentage_, other->steering_percentage_); + swap(steering_torque_nm_, other->steering_torque_nm_); + swap(engine_started_, other->engine_started_); + swap(parking_brake_, other->parking_brake_); + swap(wiper_, other->wiper_); + swap(disengage_status_, other->disengage_status_); + swap(high_beam_signal_, other->high_beam_signal_); + swap(low_beam_signal_, other->low_beam_signal_); + swap(left_turn_signal_, other->left_turn_signal_); + swap(right_turn_signal_, other->right_turn_signal_); + swap(horn_, other->horn_); + swap(driving_mode_, other->driving_mode_); + swap(error_code_, other->error_code_); + swap(gear_location_, other->gear_location_); + swap(steering_timestamp_, other->steering_timestamp_); + swap(chassis_error_mask_, other->chassis_error_mask_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Chassis::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace canbus +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::Signal* Arena::CreateMaybeMessage< ::apollo::canbus::Signal >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::Signal >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::Chassis* Arena::CreateMaybeMessage< ::apollo::canbus::Chassis >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::Chassis >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/canbus/chassis.pb.h b/apollo_msgs/include/apollo_msgs/proto/canbus/chassis.pb.h new file mode 100644 index 0000000..abdfecd --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/canbus/chassis.pb.h @@ -0,0 +1,1238 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/canbus/chassis.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "apollo_msgs/proto/common/header.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[2]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto +namespace apollo { +namespace canbus { +class Chassis; +class ChassisDefaultTypeInternal; +extern ChassisDefaultTypeInternal _Chassis_default_instance_; +class Signal; +class SignalDefaultTypeInternal; +extern SignalDefaultTypeInternal _Signal_default_instance_; +} // namespace canbus +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::canbus::Chassis* Arena::CreateMaybeMessage<::apollo::canbus::Chassis>(Arena*); +template<> ::apollo::canbus::Signal* Arena::CreateMaybeMessage<::apollo::canbus::Signal>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace canbus { + +enum Signal_TurnSignal { + Signal_TurnSignal_TURN_NONE = 0, + Signal_TurnSignal_TURN_LEFT = 1, + Signal_TurnSignal_TURN_RIGHT = 2, + Signal_TurnSignal_Signal_TurnSignal_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Signal_TurnSignal_Signal_TurnSignal_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Signal_TurnSignal_IsValid(int value); +const Signal_TurnSignal Signal_TurnSignal_TurnSignal_MIN = Signal_TurnSignal_TURN_NONE; +const Signal_TurnSignal Signal_TurnSignal_TurnSignal_MAX = Signal_TurnSignal_TURN_RIGHT; +const int Signal_TurnSignal_TurnSignal_ARRAYSIZE = Signal_TurnSignal_TurnSignal_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Signal_TurnSignal_descriptor(); +inline const ::std::string& Signal_TurnSignal_Name(Signal_TurnSignal value) { + return ::google::protobuf::internal::NameOfEnum( + Signal_TurnSignal_descriptor(), value); +} +inline bool Signal_TurnSignal_Parse( + const ::std::string& name, Signal_TurnSignal* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Signal_TurnSignal_descriptor(), name, value); +} +enum Chassis_DrivingMode { + Chassis_DrivingMode_COMPLETE_MANUAL = 0, + Chassis_DrivingMode_COMPLETE_AUTO_DRIVE = 1, + Chassis_DrivingMode_AUTO_STEER_ONLY = 2, + Chassis_DrivingMode_AUTO_SPEED_ONLY = 3, + Chassis_DrivingMode_EMERGENCY_MODE = 4, + Chassis_DrivingMode_Chassis_DrivingMode_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Chassis_DrivingMode_Chassis_DrivingMode_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Chassis_DrivingMode_IsValid(int value); +const Chassis_DrivingMode Chassis_DrivingMode_DrivingMode_MIN = Chassis_DrivingMode_COMPLETE_MANUAL; +const Chassis_DrivingMode Chassis_DrivingMode_DrivingMode_MAX = Chassis_DrivingMode_EMERGENCY_MODE; +const int Chassis_DrivingMode_DrivingMode_ARRAYSIZE = Chassis_DrivingMode_DrivingMode_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Chassis_DrivingMode_descriptor(); +inline const ::std::string& Chassis_DrivingMode_Name(Chassis_DrivingMode value) { + return ::google::protobuf::internal::NameOfEnum( + Chassis_DrivingMode_descriptor(), value); +} +inline bool Chassis_DrivingMode_Parse( + const ::std::string& name, Chassis_DrivingMode* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Chassis_DrivingMode_descriptor(), name, value); +} +enum Chassis_ErrorCode { + Chassis_ErrorCode_NO_ERROR = 0, + Chassis_ErrorCode_CMD_NOT_IN_PERIOD = 1, + Chassis_ErrorCode_CHASSIS_ERROR = 2, + Chassis_ErrorCode_MANUAL_INTERVENTION = 3, + Chassis_ErrorCode_CHASSIS_CAN_NOT_IN_PERIOD = 4, + Chassis_ErrorCode_UNKNOWN_ERROR = 5, + Chassis_ErrorCode_Chassis_ErrorCode_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Chassis_ErrorCode_Chassis_ErrorCode_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Chassis_ErrorCode_IsValid(int value); +const Chassis_ErrorCode Chassis_ErrorCode_ErrorCode_MIN = Chassis_ErrorCode_NO_ERROR; +const Chassis_ErrorCode Chassis_ErrorCode_ErrorCode_MAX = Chassis_ErrorCode_UNKNOWN_ERROR; +const int Chassis_ErrorCode_ErrorCode_ARRAYSIZE = Chassis_ErrorCode_ErrorCode_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Chassis_ErrorCode_descriptor(); +inline const ::std::string& Chassis_ErrorCode_Name(Chassis_ErrorCode value) { + return ::google::protobuf::internal::NameOfEnum( + Chassis_ErrorCode_descriptor(), value); +} +inline bool Chassis_ErrorCode_Parse( + const ::std::string& name, Chassis_ErrorCode* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Chassis_ErrorCode_descriptor(), name, value); +} +enum Chassis_GearPosition { + Chassis_GearPosition_GEAR_NEUTRAL = 0, + Chassis_GearPosition_GEAR_DRIVE = 1, + Chassis_GearPosition_GEAR_REVERSE = 2, + Chassis_GearPosition_GEAR_PARKING = 3, + Chassis_GearPosition_GEAR_LOW = 4, + Chassis_GearPosition_GEAR_INVALID = 5, + Chassis_GearPosition_GEAR_NONE = 6, + Chassis_GearPosition_Chassis_GearPosition_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Chassis_GearPosition_Chassis_GearPosition_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Chassis_GearPosition_IsValid(int value); +const Chassis_GearPosition Chassis_GearPosition_GearPosition_MIN = Chassis_GearPosition_GEAR_NEUTRAL; +const Chassis_GearPosition Chassis_GearPosition_GearPosition_MAX = Chassis_GearPosition_GEAR_NONE; +const int Chassis_GearPosition_GearPosition_ARRAYSIZE = Chassis_GearPosition_GearPosition_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Chassis_GearPosition_descriptor(); +inline const ::std::string& Chassis_GearPosition_Name(Chassis_GearPosition value) { + return ::google::protobuf::internal::NameOfEnum( + Chassis_GearPosition_descriptor(), value); +} +inline bool Chassis_GearPosition_Parse( + const ::std::string& name, Chassis_GearPosition* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Chassis_GearPosition_descriptor(), name, value); +} +// =================================================================== + +class Signal : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.Signal) */ { + public: + Signal(); + virtual ~Signal(); + + Signal(const Signal& from); + + inline Signal& operator=(const Signal& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Signal(Signal&& from) noexcept + : Signal() { + *this = ::std::move(from); + } + + inline Signal& operator=(Signal&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Signal& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Signal* internal_default_instance() { + return reinterpret_cast( + &_Signal_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(Signal* other); + friend void swap(Signal& a, Signal& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Signal* New() const final { + return CreateMaybeMessage(NULL); + } + + Signal* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Signal& from); + void MergeFrom(const Signal& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Signal* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef Signal_TurnSignal TurnSignal; + static const TurnSignal TURN_NONE = + Signal_TurnSignal_TURN_NONE; + static const TurnSignal TURN_LEFT = + Signal_TurnSignal_TURN_LEFT; + static const TurnSignal TURN_RIGHT = + Signal_TurnSignal_TURN_RIGHT; + static inline bool TurnSignal_IsValid(int value) { + return Signal_TurnSignal_IsValid(value); + } + static const TurnSignal TurnSignal_MIN = + Signal_TurnSignal_TurnSignal_MIN; + static const TurnSignal TurnSignal_MAX = + Signal_TurnSignal_TurnSignal_MAX; + static const int TurnSignal_ARRAYSIZE = + Signal_TurnSignal_TurnSignal_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + TurnSignal_descriptor() { + return Signal_TurnSignal_descriptor(); + } + static inline const ::std::string& TurnSignal_Name(TurnSignal value) { + return Signal_TurnSignal_Name(value); + } + static inline bool TurnSignal_Parse(const ::std::string& name, + TurnSignal* value) { + return Signal_TurnSignal_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // .apollo.canbus.Signal.TurnSignal turn_signal = 1; + void clear_turn_signal(); + static const int kTurnSignalFieldNumber = 1; + ::apollo::canbus::Signal_TurnSignal turn_signal() const; + void set_turn_signal(::apollo::canbus::Signal_TurnSignal value); + + // bool high_beam = 2; + void clear_high_beam(); + static const int kHighBeamFieldNumber = 2; + bool high_beam() const; + void set_high_beam(bool value); + + // bool low_beam = 3; + void clear_low_beam(); + static const int kLowBeamFieldNumber = 3; + bool low_beam() const; + void set_low_beam(bool value); + + // bool horn = 4; + void clear_horn(); + static const int kHornFieldNumber = 4; + bool horn() const; + void set_horn(bool value); + + // bool emergency_light = 5; + void clear_emergency_light(); + static const int kEmergencyLightFieldNumber = 5; + bool emergency_light() const; + void set_emergency_light(bool value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.Signal) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + int turn_signal_; + bool high_beam_; + bool low_beam_; + bool horn_; + bool emergency_light_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Chassis : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.Chassis) */ { + public: + Chassis(); + virtual ~Chassis(); + + Chassis(const Chassis& from); + + inline Chassis& operator=(const Chassis& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Chassis(Chassis&& from) noexcept + : Chassis() { + *this = ::std::move(from); + } + + inline Chassis& operator=(Chassis&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Chassis& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Chassis* internal_default_instance() { + return reinterpret_cast( + &_Chassis_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(Chassis* other); + friend void swap(Chassis& a, Chassis& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Chassis* New() const final { + return CreateMaybeMessage(NULL); + } + + Chassis* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Chassis& from); + void MergeFrom(const Chassis& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Chassis* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef Chassis_DrivingMode DrivingMode; + static const DrivingMode COMPLETE_MANUAL = + Chassis_DrivingMode_COMPLETE_MANUAL; + static const DrivingMode COMPLETE_AUTO_DRIVE = + Chassis_DrivingMode_COMPLETE_AUTO_DRIVE; + static const DrivingMode AUTO_STEER_ONLY = + Chassis_DrivingMode_AUTO_STEER_ONLY; + static const DrivingMode AUTO_SPEED_ONLY = + Chassis_DrivingMode_AUTO_SPEED_ONLY; + static const DrivingMode EMERGENCY_MODE = + Chassis_DrivingMode_EMERGENCY_MODE; + static inline bool DrivingMode_IsValid(int value) { + return Chassis_DrivingMode_IsValid(value); + } + static const DrivingMode DrivingMode_MIN = + Chassis_DrivingMode_DrivingMode_MIN; + static const DrivingMode DrivingMode_MAX = + Chassis_DrivingMode_DrivingMode_MAX; + static const int DrivingMode_ARRAYSIZE = + Chassis_DrivingMode_DrivingMode_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + DrivingMode_descriptor() { + return Chassis_DrivingMode_descriptor(); + } + static inline const ::std::string& DrivingMode_Name(DrivingMode value) { + return Chassis_DrivingMode_Name(value); + } + static inline bool DrivingMode_Parse(const ::std::string& name, + DrivingMode* value) { + return Chassis_DrivingMode_Parse(name, value); + } + + typedef Chassis_ErrorCode ErrorCode; + static const ErrorCode NO_ERROR = + Chassis_ErrorCode_NO_ERROR; + static const ErrorCode CMD_NOT_IN_PERIOD = + Chassis_ErrorCode_CMD_NOT_IN_PERIOD; + static const ErrorCode CHASSIS_ERROR = + Chassis_ErrorCode_CHASSIS_ERROR; + static const ErrorCode MANUAL_INTERVENTION = + Chassis_ErrorCode_MANUAL_INTERVENTION; + static const ErrorCode CHASSIS_CAN_NOT_IN_PERIOD = + Chassis_ErrorCode_CHASSIS_CAN_NOT_IN_PERIOD; + static const ErrorCode UNKNOWN_ERROR = + Chassis_ErrorCode_UNKNOWN_ERROR; + static inline bool ErrorCode_IsValid(int value) { + return Chassis_ErrorCode_IsValid(value); + } + static const ErrorCode ErrorCode_MIN = + Chassis_ErrorCode_ErrorCode_MIN; + static const ErrorCode ErrorCode_MAX = + Chassis_ErrorCode_ErrorCode_MAX; + static const int ErrorCode_ARRAYSIZE = + Chassis_ErrorCode_ErrorCode_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + ErrorCode_descriptor() { + return Chassis_ErrorCode_descriptor(); + } + static inline const ::std::string& ErrorCode_Name(ErrorCode value) { + return Chassis_ErrorCode_Name(value); + } + static inline bool ErrorCode_Parse(const ::std::string& name, + ErrorCode* value) { + return Chassis_ErrorCode_Parse(name, value); + } + + typedef Chassis_GearPosition GearPosition; + static const GearPosition GEAR_NEUTRAL = + Chassis_GearPosition_GEAR_NEUTRAL; + static const GearPosition GEAR_DRIVE = + Chassis_GearPosition_GEAR_DRIVE; + static const GearPosition GEAR_REVERSE = + Chassis_GearPosition_GEAR_REVERSE; + static const GearPosition GEAR_PARKING = + Chassis_GearPosition_GEAR_PARKING; + static const GearPosition GEAR_LOW = + Chassis_GearPosition_GEAR_LOW; + static const GearPosition GEAR_INVALID = + Chassis_GearPosition_GEAR_INVALID; + static const GearPosition GEAR_NONE = + Chassis_GearPosition_GEAR_NONE; + static inline bool GearPosition_IsValid(int value) { + return Chassis_GearPosition_IsValid(value); + } + static const GearPosition GearPosition_MIN = + Chassis_GearPosition_GearPosition_MIN; + static const GearPosition GearPosition_MAX = + Chassis_GearPosition_GearPosition_MAX; + static const int GearPosition_ARRAYSIZE = + Chassis_GearPosition_GearPosition_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + GearPosition_descriptor() { + return Chassis_GearPosition_descriptor(); + } + static inline const ::std::string& GearPosition_Name(GearPosition value) { + return Chassis_GearPosition_Name(value); + } + static inline bool GearPosition_Parse(const ::std::string& name, + GearPosition* value) { + return Chassis_GearPosition_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // .apollo.common.Header header = 25; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 25; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.canbus.Signal signal = 27; + bool has_signal() const; + void clear_signal(); + static const int kSignalFieldNumber = 27; + private: + const ::apollo::canbus::Signal& _internal_signal() const; + public: + const ::apollo::canbus::Signal& signal() const; + ::apollo::canbus::Signal* release_signal(); + ::apollo::canbus::Signal* mutable_signal(); + void set_allocated_signal(::apollo::canbus::Signal* signal); + + // float engine_rpm = 4; + void clear_engine_rpm(); + static const int kEngineRpmFieldNumber = 4; + float engine_rpm() const; + void set_engine_rpm(float value); + + // float speed_mps = 5; + void clear_speed_mps(); + static const int kSpeedMpsFieldNumber = 5; + float speed_mps() const; + void set_speed_mps(float value); + + // float odometer_m = 6; + void clear_odometer_m(); + static const int kOdometerMFieldNumber = 6; + float odometer_m() const; + void set_odometer_m(float value); + + // int32 fuel_range_m = 7; + void clear_fuel_range_m(); + static const int kFuelRangeMFieldNumber = 7; + ::google::protobuf::int32 fuel_range_m() const; + void set_fuel_range_m(::google::protobuf::int32 value); + + // float throttle_percentage = 8; + void clear_throttle_percentage(); + static const int kThrottlePercentageFieldNumber = 8; + float throttle_percentage() const; + void set_throttle_percentage(float value); + + // float brake_percentage = 9; + void clear_brake_percentage(); + static const int kBrakePercentageFieldNumber = 9; + float brake_percentage() const; + void set_brake_percentage(float value); + + // float steering_percentage = 11; + void clear_steering_percentage(); + static const int kSteeringPercentageFieldNumber = 11; + float steering_percentage() const; + void set_steering_percentage(float value); + + // float steering_torque_nm = 12; + void clear_steering_torque_nm(); + static const int kSteeringTorqueNmFieldNumber = 12; + float steering_torque_nm() const; + void set_steering_torque_nm(float value); + + // bool engine_started = 3; + void clear_engine_started(); + static const int kEngineStartedFieldNumber = 3; + bool engine_started() const; + void set_engine_started(bool value); + + // bool parking_brake = 13; + void clear_parking_brake(); + static const int kParkingBrakeFieldNumber = 13; + bool parking_brake() const; + void set_parking_brake(bool value); + + // bool wiper = 19; + void clear_wiper(); + static const int kWiperFieldNumber = 19; + bool wiper() const; + void set_wiper(bool value); + + // bool disengage_status = 20; + void clear_disengage_status(); + static const int kDisengageStatusFieldNumber = 20; + bool disengage_status() const; + void set_disengage_status(bool value); + + // bool high_beam_signal = 14; + void clear_high_beam_signal(); + static const int kHighBeamSignalFieldNumber = 14; + bool high_beam_signal() const; + void set_high_beam_signal(bool value); + + // bool low_beam_signal = 15; + void clear_low_beam_signal(); + static const int kLowBeamSignalFieldNumber = 15; + bool low_beam_signal() const; + void set_low_beam_signal(bool value); + + // bool left_turn_signal = 16; + void clear_left_turn_signal(); + static const int kLeftTurnSignalFieldNumber = 16; + bool left_turn_signal() const; + void set_left_turn_signal(bool value); + + // bool right_turn_signal = 17; + void clear_right_turn_signal(); + static const int kRightTurnSignalFieldNumber = 17; + bool right_turn_signal() const; + void set_right_turn_signal(bool value); + + // bool horn = 18; + void clear_horn(); + static const int kHornFieldNumber = 18; + bool horn() const; + void set_horn(bool value); + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 21; + void clear_driving_mode(); + static const int kDrivingModeFieldNumber = 21; + ::apollo::canbus::Chassis_DrivingMode driving_mode() const; + void set_driving_mode(::apollo::canbus::Chassis_DrivingMode value); + + // .apollo.canbus.Chassis.ErrorCode error_code = 22; + void clear_error_code(); + static const int kErrorCodeFieldNumber = 22; + ::apollo::canbus::Chassis_ErrorCode error_code() const; + void set_error_code(::apollo::canbus::Chassis_ErrorCode value); + + // .apollo.canbus.Chassis.GearPosition gear_location = 23; + void clear_gear_location(); + static const int kGearLocationFieldNumber = 23; + ::apollo::canbus::Chassis_GearPosition gear_location() const; + void set_gear_location(::apollo::canbus::Chassis_GearPosition value); + + // double steering_timestamp = 24; + void clear_steering_timestamp(); + static const int kSteeringTimestampFieldNumber = 24; + double steering_timestamp() const; + void set_steering_timestamp(double value); + + // int32 chassis_error_mask = 26; + void clear_chassis_error_mask(); + static const int kChassisErrorMaskFieldNumber = 26; + ::google::protobuf::int32 chassis_error_mask() const; + void set_chassis_error_mask(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.Chassis) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::Header* header_; + ::apollo::canbus::Signal* signal_; + float engine_rpm_; + float speed_mps_; + float odometer_m_; + ::google::protobuf::int32 fuel_range_m_; + float throttle_percentage_; + float brake_percentage_; + float steering_percentage_; + float steering_torque_nm_; + bool engine_started_; + bool parking_brake_; + bool wiper_; + bool disengage_status_; + bool high_beam_signal_; + bool low_beam_signal_; + bool left_turn_signal_; + bool right_turn_signal_; + bool horn_; + int driving_mode_; + int error_code_; + int gear_location_; + double steering_timestamp_; + ::google::protobuf::int32 chassis_error_mask_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// Signal + +// .apollo.canbus.Signal.TurnSignal turn_signal = 1; +inline void Signal::clear_turn_signal() { + turn_signal_ = 0; +} +inline ::apollo::canbus::Signal_TurnSignal Signal::turn_signal() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Signal.turn_signal) + return static_cast< ::apollo::canbus::Signal_TurnSignal >(turn_signal_); +} +inline void Signal::set_turn_signal(::apollo::canbus::Signal_TurnSignal value) { + + turn_signal_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Signal.turn_signal) +} + +// bool high_beam = 2; +inline void Signal::clear_high_beam() { + high_beam_ = false; +} +inline bool Signal::high_beam() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Signal.high_beam) + return high_beam_; +} +inline void Signal::set_high_beam(bool value) { + + high_beam_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Signal.high_beam) +} + +// bool low_beam = 3; +inline void Signal::clear_low_beam() { + low_beam_ = false; +} +inline bool Signal::low_beam() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Signal.low_beam) + return low_beam_; +} +inline void Signal::set_low_beam(bool value) { + + low_beam_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Signal.low_beam) +} + +// bool horn = 4; +inline void Signal::clear_horn() { + horn_ = false; +} +inline bool Signal::horn() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Signal.horn) + return horn_; +} +inline void Signal::set_horn(bool value) { + + horn_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Signal.horn) +} + +// bool emergency_light = 5; +inline void Signal::clear_emergency_light() { + emergency_light_ = false; +} +inline bool Signal::emergency_light() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Signal.emergency_light) + return emergency_light_; +} +inline void Signal::set_emergency_light(bool value) { + + emergency_light_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Signal.emergency_light) +} + +// ------------------------------------------------------------------- + +// Chassis + +// bool engine_started = 3; +inline void Chassis::clear_engine_started() { + engine_started_ = false; +} +inline bool Chassis::engine_started() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.engine_started) + return engine_started_; +} +inline void Chassis::set_engine_started(bool value) { + + engine_started_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.engine_started) +} + +// float engine_rpm = 4; +inline void Chassis::clear_engine_rpm() { + engine_rpm_ = 0; +} +inline float Chassis::engine_rpm() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.engine_rpm) + return engine_rpm_; +} +inline void Chassis::set_engine_rpm(float value) { + + engine_rpm_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.engine_rpm) +} + +// float speed_mps = 5; +inline void Chassis::clear_speed_mps() { + speed_mps_ = 0; +} +inline float Chassis::speed_mps() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.speed_mps) + return speed_mps_; +} +inline void Chassis::set_speed_mps(float value) { + + speed_mps_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.speed_mps) +} + +// float odometer_m = 6; +inline void Chassis::clear_odometer_m() { + odometer_m_ = 0; +} +inline float Chassis::odometer_m() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.odometer_m) + return odometer_m_; +} +inline void Chassis::set_odometer_m(float value) { + + odometer_m_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.odometer_m) +} + +// int32 fuel_range_m = 7; +inline void Chassis::clear_fuel_range_m() { + fuel_range_m_ = 0; +} +inline ::google::protobuf::int32 Chassis::fuel_range_m() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.fuel_range_m) + return fuel_range_m_; +} +inline void Chassis::set_fuel_range_m(::google::protobuf::int32 value) { + + fuel_range_m_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.fuel_range_m) +} + +// float throttle_percentage = 8; +inline void Chassis::clear_throttle_percentage() { + throttle_percentage_ = 0; +} +inline float Chassis::throttle_percentage() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.throttle_percentage) + return throttle_percentage_; +} +inline void Chassis::set_throttle_percentage(float value) { + + throttle_percentage_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.throttle_percentage) +} + +// float brake_percentage = 9; +inline void Chassis::clear_brake_percentage() { + brake_percentage_ = 0; +} +inline float Chassis::brake_percentage() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.brake_percentage) + return brake_percentage_; +} +inline void Chassis::set_brake_percentage(float value) { + + brake_percentage_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.brake_percentage) +} + +// float steering_percentage = 11; +inline void Chassis::clear_steering_percentage() { + steering_percentage_ = 0; +} +inline float Chassis::steering_percentage() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.steering_percentage) + return steering_percentage_; +} +inline void Chassis::set_steering_percentage(float value) { + + steering_percentage_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.steering_percentage) +} + +// float steering_torque_nm = 12; +inline void Chassis::clear_steering_torque_nm() { + steering_torque_nm_ = 0; +} +inline float Chassis::steering_torque_nm() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.steering_torque_nm) + return steering_torque_nm_; +} +inline void Chassis::set_steering_torque_nm(float value) { + + steering_torque_nm_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.steering_torque_nm) +} + +// bool parking_brake = 13; +inline void Chassis::clear_parking_brake() { + parking_brake_ = false; +} +inline bool Chassis::parking_brake() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.parking_brake) + return parking_brake_; +} +inline void Chassis::set_parking_brake(bool value) { + + parking_brake_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.parking_brake) +} + +// bool wiper = 19; +inline void Chassis::clear_wiper() { + wiper_ = false; +} +inline bool Chassis::wiper() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.wiper) + return wiper_; +} +inline void Chassis::set_wiper(bool value) { + + wiper_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.wiper) +} + +// bool disengage_status = 20; +inline void Chassis::clear_disengage_status() { + disengage_status_ = false; +} +inline bool Chassis::disengage_status() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.disengage_status) + return disengage_status_; +} +inline void Chassis::set_disengage_status(bool value) { + + disengage_status_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.disengage_status) +} + +// .apollo.canbus.Chassis.DrivingMode driving_mode = 21; +inline void Chassis::clear_driving_mode() { + driving_mode_ = 0; +} +inline ::apollo::canbus::Chassis_DrivingMode Chassis::driving_mode() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.driving_mode) + return static_cast< ::apollo::canbus::Chassis_DrivingMode >(driving_mode_); +} +inline void Chassis::set_driving_mode(::apollo::canbus::Chassis_DrivingMode value) { + + driving_mode_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.driving_mode) +} + +// .apollo.canbus.Chassis.ErrorCode error_code = 22; +inline void Chassis::clear_error_code() { + error_code_ = 0; +} +inline ::apollo::canbus::Chassis_ErrorCode Chassis::error_code() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.error_code) + return static_cast< ::apollo::canbus::Chassis_ErrorCode >(error_code_); +} +inline void Chassis::set_error_code(::apollo::canbus::Chassis_ErrorCode value) { + + error_code_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.error_code) +} + +// .apollo.canbus.Chassis.GearPosition gear_location = 23; +inline void Chassis::clear_gear_location() { + gear_location_ = 0; +} +inline ::apollo::canbus::Chassis_GearPosition Chassis::gear_location() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.gear_location) + return static_cast< ::apollo::canbus::Chassis_GearPosition >(gear_location_); +} +inline void Chassis::set_gear_location(::apollo::canbus::Chassis_GearPosition value) { + + gear_location_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.gear_location) +} + +// double steering_timestamp = 24; +inline void Chassis::clear_steering_timestamp() { + steering_timestamp_ = 0; +} +inline double Chassis::steering_timestamp() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.steering_timestamp) + return steering_timestamp_; +} +inline void Chassis::set_steering_timestamp(double value) { + + steering_timestamp_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.steering_timestamp) +} + +// .apollo.common.Header header = 25; +inline bool Chassis::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& Chassis::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& Chassis::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* Chassis::release_header() { + // @@protoc_insertion_point(field_release:apollo.canbus.Chassis.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* Chassis::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.Chassis.header) + return header_; +} +inline void Chassis::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.Chassis.header) +} + +// int32 chassis_error_mask = 26; +inline void Chassis::clear_chassis_error_mask() { + chassis_error_mask_ = 0; +} +inline ::google::protobuf::int32 Chassis::chassis_error_mask() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.chassis_error_mask) + return chassis_error_mask_; +} +inline void Chassis::set_chassis_error_mask(::google::protobuf::int32 value) { + + chassis_error_mask_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.chassis_error_mask) +} + +// .apollo.canbus.Signal signal = 27; +inline bool Chassis::has_signal() const { + return this != internal_default_instance() && signal_ != NULL; +} +inline void Chassis::clear_signal() { + if (GetArenaNoVirtual() == NULL && signal_ != NULL) { + delete signal_; + } + signal_ = NULL; +} +inline const ::apollo::canbus::Signal& Chassis::_internal_signal() const { + return *signal_; +} +inline const ::apollo::canbus::Signal& Chassis::signal() const { + const ::apollo::canbus::Signal* p = signal_; + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.signal) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Signal_default_instance_); +} +inline ::apollo::canbus::Signal* Chassis::release_signal() { + // @@protoc_insertion_point(field_release:apollo.canbus.Chassis.signal) + + ::apollo::canbus::Signal* temp = signal_; + signal_ = NULL; + return temp; +} +inline ::apollo::canbus::Signal* Chassis::mutable_signal() { + + if (signal_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Signal>(GetArenaNoVirtual()); + signal_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.Chassis.signal) + return signal_; +} +inline void Chassis::set_allocated_signal(::apollo::canbus::Signal* signal) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete signal_; + } + if (signal) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + signal = ::google::protobuf::internal::GetOwnedMessage( + message_arena, signal, submessage_arena); + } + + } else { + + } + signal_ = signal; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.Chassis.signal) +} + +// bool high_beam_signal = 14; +inline void Chassis::clear_high_beam_signal() { + high_beam_signal_ = false; +} +inline bool Chassis::high_beam_signal() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.high_beam_signal) + return high_beam_signal_; +} +inline void Chassis::set_high_beam_signal(bool value) { + + high_beam_signal_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.high_beam_signal) +} + +// bool low_beam_signal = 15; +inline void Chassis::clear_low_beam_signal() { + low_beam_signal_ = false; +} +inline bool Chassis::low_beam_signal() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.low_beam_signal) + return low_beam_signal_; +} +inline void Chassis::set_low_beam_signal(bool value) { + + low_beam_signal_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.low_beam_signal) +} + +// bool left_turn_signal = 16; +inline void Chassis::clear_left_turn_signal() { + left_turn_signal_ = false; +} +inline bool Chassis::left_turn_signal() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.left_turn_signal) + return left_turn_signal_; +} +inline void Chassis::set_left_turn_signal(bool value) { + + left_turn_signal_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.left_turn_signal) +} + +// bool right_turn_signal = 17; +inline void Chassis::clear_right_turn_signal() { + right_turn_signal_ = false; +} +inline bool Chassis::right_turn_signal() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.right_turn_signal) + return right_turn_signal_; +} +inline void Chassis::set_right_turn_signal(bool value) { + + right_turn_signal_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.right_turn_signal) +} + +// bool horn = 18; +inline void Chassis::clear_horn() { + horn_ = false; +} +inline bool Chassis::horn() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Chassis.horn) + return horn_; +} +inline void Chassis::set_horn(bool value) { + + horn_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Chassis.horn) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace canbus +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::canbus::Signal_TurnSignal> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Signal_TurnSignal>() { + return ::apollo::canbus::Signal_TurnSignal_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::Chassis_DrivingMode> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Chassis_DrivingMode>() { + return ::apollo::canbus::Chassis_DrivingMode_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::Chassis_ErrorCode> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Chassis_ErrorCode>() { + return ::apollo::canbus::Chassis_ErrorCode_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::Chassis_GearPosition> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Chassis_GearPosition>() { + return ::apollo::canbus::Chassis_GearPosition_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/canbus/chassis_detail.pb.cc b/apollo_msgs/include/apollo_msgs/proto/canbus/chassis_detail.pb.cc new file mode 100644 index 0000000..62c4a96 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/canbus/chassis_detail.pb.cc @@ -0,0 +1,12819 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/canbus/chassis_detail.proto + +#include "apollo_msgs/proto/canbus/chassis_detail.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_BasicInfo; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Battery; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Brake; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_CheckResponseSignal; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Deceleration; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Ems; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Epb; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Eps; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Esp; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Gas; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Gear; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Light; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Safety; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_VehicleSpd; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto +namespace apollo { +namespace canbus { +class ChassisDetailDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ChassisDetail_default_instance_; +class CheckResponseSignalDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _CheckResponseSignal_default_instance_; +class BatteryDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Battery_default_instance_; +class LightDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Light_default_instance_; +class EpsDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Eps_default_instance_; +class VehicleSpdDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _VehicleSpd_default_instance_; +class DecelerationDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Deceleration_default_instance_; +class BrakeDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Brake_default_instance_; +class EpbDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Epb_default_instance_; +class GasDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Gas_default_instance_; +class EspDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Esp_default_instance_; +class EmsDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Ems_default_instance_; +class GearDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Gear_default_instance_; +class SafetyDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Safety_default_instance_; +class BasicInfoDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _BasicInfo_default_instance_; +} // namespace canbus +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto { +static void InitDefaultsChassisDetail() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_ChassisDetail_default_instance_; + new (ptr) ::apollo::canbus::ChassisDetail(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::ChassisDetail::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<14> scc_info_ChassisDetail = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 14, InitDefaultsChassisDetail}, { + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_BasicInfo.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Safety.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Gear.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Ems.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Esp.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Gas.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Epb.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Brake.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Deceleration.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_VehicleSpd.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Eps.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Light.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Battery.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_CheckResponseSignal.base,}}; + +static void InitDefaultsCheckResponseSignal() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_CheckResponseSignal_default_instance_; + new (ptr) ::apollo::canbus::CheckResponseSignal(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::CheckResponseSignal::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_CheckResponseSignal = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsCheckResponseSignal}, {}}; + +static void InitDefaultsBattery() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_Battery_default_instance_; + new (ptr) ::apollo::canbus::Battery(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::Battery::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Battery = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsBattery}, {}}; + +static void InitDefaultsLight() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_Light_default_instance_; + new (ptr) ::apollo::canbus::Light(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::Light::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Light = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsLight}, {}}; + +static void InitDefaultsEps() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_Eps_default_instance_; + new (ptr) ::apollo::canbus::Eps(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::Eps::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Eps = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsEps}, {}}; + +static void InitDefaultsVehicleSpd() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_VehicleSpd_default_instance_; + new (ptr) ::apollo::canbus::VehicleSpd(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::VehicleSpd::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_VehicleSpd = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsVehicleSpd}, {}}; + +static void InitDefaultsDeceleration() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_Deceleration_default_instance_; + new (ptr) ::apollo::canbus::Deceleration(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::Deceleration::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Deceleration = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsDeceleration}, {}}; + +static void InitDefaultsBrake() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_Brake_default_instance_; + new (ptr) ::apollo::canbus::Brake(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::Brake::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Brake = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsBrake}, {}}; + +static void InitDefaultsEpb() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_Epb_default_instance_; + new (ptr) ::apollo::canbus::Epb(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::Epb::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Epb = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsEpb}, {}}; + +static void InitDefaultsGas() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_Gas_default_instance_; + new (ptr) ::apollo::canbus::Gas(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::Gas::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Gas = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsGas}, {}}; + +static void InitDefaultsEsp() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_Esp_default_instance_; + new (ptr) ::apollo::canbus::Esp(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::Esp::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Esp = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsEsp}, {}}; + +static void InitDefaultsEms() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_Ems_default_instance_; + new (ptr) ::apollo::canbus::Ems(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::Ems::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Ems = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsEms}, {}}; + +static void InitDefaultsGear() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_Gear_default_instance_; + new (ptr) ::apollo::canbus::Gear(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::Gear::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Gear = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsGear}, {}}; + +static void InitDefaultsSafety() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_Safety_default_instance_; + new (ptr) ::apollo::canbus::Safety(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::Safety::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Safety = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsSafety}, {}}; + +static void InitDefaultsBasicInfo() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::canbus::_BasicInfo_default_instance_; + new (ptr) ::apollo::canbus::BasicInfo(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::canbus::BasicInfo::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_BasicInfo = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsBasicInfo}, {}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_ChassisDetail.base); + ::google::protobuf::internal::InitSCC(&scc_info_CheckResponseSignal.base); + ::google::protobuf::internal::InitSCC(&scc_info_Battery.base); + ::google::protobuf::internal::InitSCC(&scc_info_Light.base); + ::google::protobuf::internal::InitSCC(&scc_info_Eps.base); + ::google::protobuf::internal::InitSCC(&scc_info_VehicleSpd.base); + ::google::protobuf::internal::InitSCC(&scc_info_Deceleration.base); + ::google::protobuf::internal::InitSCC(&scc_info_Brake.base); + ::google::protobuf::internal::InitSCC(&scc_info_Epb.base); + ::google::protobuf::internal::InitSCC(&scc_info_Gas.base); + ::google::protobuf::internal::InitSCC(&scc_info_Esp.base); + ::google::protobuf::internal::InitSCC(&scc_info_Ems.base); + ::google::protobuf::internal::InitSCC(&scc_info_Gear.base); + ::google::protobuf::internal::InitSCC(&scc_info_Safety.base); + ::google::protobuf::internal::InitSCC(&scc_info_BasicInfo.base); +} + +::google::protobuf::Metadata file_level_metadata[15]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[14]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, car_type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, basic_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, safety_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, gear_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, ems_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, esp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, gas_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, epb_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, brake_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, deceleration_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, vehicle_spd_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, eps_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, light_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, battery_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::ChassisDetail, check_response_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::CheckResponseSignal, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::CheckResponseSignal, is_eps_online_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::CheckResponseSignal, is_epb_online_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::CheckResponseSignal, is_esp_online_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::CheckResponseSignal, is_vtog_online_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::CheckResponseSignal, is_scu_online_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::CheckResponseSignal, is_switch_online_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::CheckResponseSignal, is_vcu_online_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Battery, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Battery, battery_percent_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Battery, fuel_level_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Light, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Light, turn_light_type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Light, lamp_type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Light, is_brake_lamp_on_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Light, is_auto_light_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Light, wiper_gear_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Light, lotion_gear_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Light, is_horn_on_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Light, lincoln_lamp_type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Light, lincoln_wiper_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Light, lincoln_ambient_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, is_eps_fail_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, eps_control_state_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, eps_driver_hand_torq_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, is_steering_angle_valid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, steering_angle_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, steering_angle_spd_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, is_trimming_status_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, is_calibration_status_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, is_failure_status_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, allow_enter_autonomous_mode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, current_driving_mode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, steering_angle_cmd_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, vehicle_speed_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, epas_torque_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, steering_enabled_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, driver_override_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, driver_activity_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, watchdog_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, channel_1_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, channel_2_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, calibration_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, connector_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, timestamp_65_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, major_version_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, minor_version_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Eps, build_number_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, is_vehicle_standstill_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, is_vehicle_spd_valid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, vehicle_spd_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, is_wheel_spd_rr_valid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, wheel_direction_rr_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, wheel_spd_rr_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, is_wheel_spd_rl_valid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, wheel_direction_rl_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, wheel_spd_rl_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, is_wheel_spd_fr_valid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, wheel_direction_fr_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, wheel_spd_fr_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, is_wheel_spd_fl_valid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, wheel_direction_fl_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, wheel_spd_fl_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, is_yaw_rate_valid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, yaw_rate_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, yaw_rate_offset_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, is_ax_valid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, ax_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, ax_offset_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, is_ay_valid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, ay_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, ay_offset_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, lat_acc_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, long_acc_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, vert_acc_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, roll_rate_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, acc_est_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::VehicleSpd, timestamp_sec_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Deceleration, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Deceleration, is_deceleration_available_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Deceleration, is_deceleration_active_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Deceleration, deceleration_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Deceleration, is_evb_fail_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Deceleration, evb_pressure_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Deceleration, brake_pressure_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Deceleration, brake_pressure_spd_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, is_brake_pedal_pressed_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, is_brake_force_exist_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, is_brake_over_heat_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, is_hand_brake_on_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, brake_pedal_position_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, is_brake_valid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, brake_input_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, brake_cmd_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, brake_output_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, boo_input_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, boo_cmd_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, boo_output_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, watchdog_applying_brakes_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, watchdog_source_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, brake_enabled_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, driver_override_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, driver_activity_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, watchdog_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, channel_1_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, channel_2_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, boo_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, connector_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, brake_torque_req_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, hsa_status_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, brake_torque_act_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, hsa_mode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, wheel_torque_act_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, major_version_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, minor_version_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Brake, build_number_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Epb, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Epb, is_epb_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Epb, is_epb_released_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Epb, epb_status_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Epb, parking_brake_status_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, is_gas_pedal_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, is_gas_pedal_pressed_more_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, gas_pedal_position_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, is_gas_valid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, throttle_input_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, throttle_cmd_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, throttle_output_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, watchdog_source_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, throttle_enabled_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, driver_override_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, driver_activity_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, watchdog_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, channel_1_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, channel_2_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, connector_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, accelerator_pedal_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, accelerator_pedal_rate_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, major_version_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, minor_version_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gas, build_number_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Esp, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Esp, is_esp_acc_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Esp, is_esp_on_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Esp, is_esp_active_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Esp, is_abs_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Esp, is_abs_active_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Esp, is_tcsvdc_fail_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Esp, is_abs_enabled_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Esp, is_stab_active_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Esp, is_stab_enabled_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Esp, is_trac_active_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Esp, is_trac_enabled_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Ems, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Ems, is_engine_acc_available_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Ems, is_engine_acc_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Ems, engine_state_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Ems, max_engine_torq_percent_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Ems, min_engine_torq_percent_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Ems, base_engine_torq_constant_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Ems, is_engine_speed_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Ems, engine_speed_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Ems, engine_torque_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Ems, is_over_engine_torque_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Ems, engine_rpm_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gear, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gear, is_shift_position_valid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gear, gear_state_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gear, driver_override_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gear, gear_cmd_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Gear, canbus_fault_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_driver_car_door_close_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_driver_buckled_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, emergency_button_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, has_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_motor_invertor_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_system_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_power_battery_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_motor_invertor_over_temperature_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_small_battery_charge_discharge_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, driving_mode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_passenger_door_open_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_rearleft_door_open_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_rearright_door_open_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_hood_open_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_trunk_open_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_passenger_detected_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_passenger_airbag_enabled_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, is_passenger_buckled_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, front_left_tire_press_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, front_right_tire_press_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, rear_left_tire_press_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, rear_right_tire_press_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::Safety, car_driving_mode_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, is_auto_mode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, power_state_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, is_air_bag_deployed_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, odo_meter_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, drive_range_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, is_system_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, is_human_interrupt_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, acc_on_button_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, acc_off_button_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, acc_res_button_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, acc_cancel_button_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, acc_on_off_button_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, acc_res_cancel_button_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, acc_inc_spd_button_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, acc_dec_spd_button_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, acc_inc_gap_button_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, acc_dec_gap_button_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, lka_button_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, canbus_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, latitude_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, longitude_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, gps_valid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, year_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, month_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, day_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, hours_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, minutes_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, seconds_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, compass_direction_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, pdop_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, is_gps_fault_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, is_inferred_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, altitude_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, heading_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, hdop_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, vdop_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, quality_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, num_satellites_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::canbus::BasicInfo, gps_speed_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::canbus::ChassisDetail)}, + { 20, -1, sizeof(::apollo::canbus::CheckResponseSignal)}, + { 32, -1, sizeof(::apollo::canbus::Battery)}, + { 39, -1, sizeof(::apollo::canbus::Light)}, + { 54, -1, sizeof(::apollo::canbus::Eps)}, + { 85, -1, sizeof(::apollo::canbus::VehicleSpd)}, + { 120, -1, sizeof(::apollo::canbus::Deceleration)}, + { 132, -1, sizeof(::apollo::canbus::Brake)}, + { 167, -1, sizeof(::apollo::canbus::Epb)}, + { 176, -1, sizeof(::apollo::canbus::Gas)}, + { 201, -1, sizeof(::apollo::canbus::Esp)}, + { 217, -1, sizeof(::apollo::canbus::Ems)}, + { 233, -1, sizeof(::apollo::canbus::Gear)}, + { 243, -1, sizeof(::apollo::canbus::Safety)}, + { 271, -1, sizeof(::apollo::canbus::BasicInfo)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::canbus::_ChassisDetail_default_instance_), + reinterpret_cast(&::apollo::canbus::_CheckResponseSignal_default_instance_), + reinterpret_cast(&::apollo::canbus::_Battery_default_instance_), + reinterpret_cast(&::apollo::canbus::_Light_default_instance_), + reinterpret_cast(&::apollo::canbus::_Eps_default_instance_), + reinterpret_cast(&::apollo::canbus::_VehicleSpd_default_instance_), + reinterpret_cast(&::apollo::canbus::_Deceleration_default_instance_), + reinterpret_cast(&::apollo::canbus::_Brake_default_instance_), + reinterpret_cast(&::apollo::canbus::_Epb_default_instance_), + reinterpret_cast(&::apollo::canbus::_Gas_default_instance_), + reinterpret_cast(&::apollo::canbus::_Esp_default_instance_), + reinterpret_cast(&::apollo::canbus::_Ems_default_instance_), + reinterpret_cast(&::apollo::canbus::_Gear_default_instance_), + reinterpret_cast(&::apollo::canbus::_Safety_default_instance_), + reinterpret_cast(&::apollo::canbus::_BasicInfo_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/canbus/chassis_detail.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 15); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n-apollo_msgs/proto/canbus/chassis_detai" + "l.proto\022\rapollo.canbus\032&apollo_msgs/prot" + "o/canbus/chassis.proto\"\235\005\n\rChassisDetail" + "\0223\n\010car_type\030\001 \001(\0162!.apollo.canbus.Chass" + "isDetail.Type\022\'\n\005basic\030\002 \001(\0132\030.apollo.ca" + "nbus.BasicInfo\022%\n\006safety\030\003 \001(\0132\025.apollo." + "canbus.Safety\022!\n\004gear\030\004 \001(\0132\023.apollo.can" + "bus.Gear\022\037\n\003ems\030\005 \001(\0132\022.apollo.canbus.Em" + "s\022\037\n\003esp\030\006 \001(\0132\022.apollo.canbus.Esp\022\037\n\003ga" + "s\030\007 \001(\0132\022.apollo.canbus.Gas\022\037\n\003epb\030\010 \001(\013" + "2\022.apollo.canbus.Epb\022#\n\005brake\030\t \001(\0132\024.ap" + "ollo.canbus.Brake\0221\n\014deceleration\030\n \001(\0132" + "\033.apollo.canbus.Deceleration\022.\n\013vehicle_" + "spd\030\013 \001(\0132\031.apollo.canbus.VehicleSpd\022\037\n\003" + "eps\030\014 \001(\0132\022.apollo.canbus.Eps\022#\n\005light\030\r" + " \001(\0132\024.apollo.canbus.Light\022\'\n\007battery\030\016 " + "\001(\0132\026.apollo.canbus.Battery\022:\n\016check_res" + "ponse\030\017 \001(\0132\".apollo.canbus.CheckRespons" + "eSignal\"-\n\004Type\022\017\n\013QIRUI_EQ_15\020\000\022\024\n\020CHAN" + "GAN_RUICHENG\020\001\"\272\001\n\023CheckResponseSignal\022\025" + "\n\ris_eps_online\030\001 \001(\010\022\025\n\ris_epb_online\030\002" + " \001(\010\022\025\n\ris_esp_online\030\003 \001(\010\022\026\n\016is_vtog_o" + "nline\030\004 \001(\010\022\025\n\ris_scu_online\030\005 \001(\010\022\030\n\020is" + "_switch_online\030\006 \001(\010\022\025\n\ris_vcu_online\030\007 " + "\001(\010\"6\n\007Battery\022\027\n\017battery_percent\030\001 \001(\001\022" + "\022\n\nfuel_level\030\002 \001(\001\"\244\t\n\005Light\022;\n\017turn_li" + "ght_type\030\001 \001(\0162\".apollo.canbus.Light.Tur" + "nLightType\0220\n\tlamp_type\030\002 \001(\0162\035.apollo.c" + "anbus.Light.LampType\022\030\n\020is_brake_lamp_on" + "\030\003 \001(\010\022\025\n\ris_auto_light\030\004 \001(\010\022\022\n\nwiper_g" + "ear\030\005 \001(\005\022\023\n\013lotion_gear\030\006 \001(\005\022\022\n\nis_hor" + "n_on\030\007 \001(\010\022\?\n\021lincoln_lamp_type\030\010 \001(\0162$." + "apollo.canbus.Light.LincolnLampType\022<\n\rl" + "incoln_wiper\030\t \001(\0162%.apollo.canbus.Light" + ".LincolnWiperType\022@\n\017lincoln_ambient\030\n \001" + "(\0162\'.apollo.canbus.Light.LincolnAmbientT" + "ype\"[\n\rTurnLightType\022\022\n\016TURN_LIGHT_OFF\020\000" + "\022\020\n\014TURN_LEFT_ON\020\001\022\021\n\rTURN_RIGHT_ON\020\002\022\021\n" + "\rTURN_LIGHT_ON\020\003\";\n\010LampType\022\014\n\010BEAM_OFF" + "\020\000\022\020\n\014HIGH_BEAM_ON\020\001\022\017\n\013LOW_BEAM_ON\020\002\"Y\n" + "\017LincolnLampType\022\r\n\tBEAM_NULL\020\000\022\026\n\022BEAM_" + "FLASH_TO_PASS\020\001\022\r\n\tBEAM_HIGH\020\002\022\020\n\014BEAM_I" + "NVALID\020\003\"\334\002\n\020LincolnWiperType\022\r\n\tWIPER_O" + "FF\020\000\022\022\n\016WIPER_AUTO_OFF\020\001\022\024\n\020WIPER_OFF_MO" + "VING\020\002\022\024\n\020WIPER_MANUAL_OFF\020\003\022\023\n\017WIPER_MA" + "NUAL_ON\020\004\022\024\n\020WIPER_MANUAL_LOW\020\005\022\025\n\021WIPER" + "_MANUAL_HIGH\020\006\022\024\n\020WIPER_MIST_FLICK\020\007\022\016\n\n" + "WIPER_WASH\020\010\022\022\n\016WIPER_AUTO_LOW\020\t\022\023\n\017WIPE" + "R_AUTO_HIGH\020\n\022\027\n\023WIPER_COURTESY_WIPE\020\013\022\025" + "\n\021WIPER_AUTO_ADJUST\020\014\022\022\n\016WIPER_RESERVED\020" + "\r\022\021\n\rWIPER_STALLED\020\016\022\021\n\rWIPER_NO_DATA\020\017\"" + "\250\001\n\022LincolnAmbientType\022\020\n\014AMBIENT_DARK\020\000" + "\022\021\n\rAMBIENT_LIGHT\020\001\022\024\n\020AMBIENT_TWILIGHT\020" + "\002\022\025\n\021AMBIENT_TUNNEL_ON\020\003\022\026\n\022AMBIENT_TUNN" + "EL_OFF\020\004\022\023\n\017AMBIENT_INVALID\020\005\022\023\n\017AMBIENT" + "_NO_DATA\020\007\"\205\006\n\003Eps\022\023\n\013is_eps_fail\030\001 \001(\010\022" + "2\n\021eps_control_state\030\002 \001(\0162\027.apollo.canb" + "us.Eps.Type\022\034\n\024eps_driver_hand_torq\030\003 \001(" + "\001\022\037\n\027is_steering_angle_valid\030\004 \001(\010\022\026\n\016st" + "eering_angle\030\005 \001(\001\022\032\n\022steering_angle_spd" + "\030\006 \001(\001\022\032\n\022is_trimming_status\030\007 \001(\010\022\035\n\025is" + "_calibration_status\030\010 \001(\010\022\031\n\021is_failure_" + "status\030\t \001(\010\022#\n\033allow_enter_autonomous_m" + "ode\030\n \001(\005\022\034\n\024current_driving_mode\030\013 \001(\005\022" + "\032\n\022steering_angle_cmd\030\014 \001(\001\022\025\n\rvehicle_s" + "peed\030\r \001(\001\022\023\n\013epas_torque\030\016 \001(\001\022\030\n\020steer" + "ing_enabled\030\017 \001(\010\022\027\n\017driver_override\030\020 \001" + "(\010\022\027\n\017driver_activity\030\021 \001(\010\022\026\n\016watchdog_" + "fault\030\022 \001(\010\022\027\n\017channel_1_fault\030\023 \001(\010\022\027\n\017" + "channel_2_fault\030\024 \001(\010\022\031\n\021calibration_fau" + "lt\030\025 \001(\010\022\027\n\017connector_fault\030\026 \001(\010\022\024\n\014tim" + "estamp_65\030\027 \001(\001\022\025\n\rmajor_version\030\030 \001(\005\022\025" + "\n\rminor_version\030\031 \001(\005\022\024\n\014build_number\030\032 " + "\001(\005\"=\n\004Type\022\021\n\rNOT_AVAILABLE\020\000\022\t\n\005READY\020" + "\001\022\n\n\006ACTIVE\020\002\022\013\n\007INVALID\020\003\"\200\007\n\nVehicleSp" + "d\022\035\n\025is_vehicle_standstill\030\001 \001(\010\022\034\n\024is_v" + "ehicle_spd_valid\030\002 \001(\010\022\023\n\013vehicle_spd\030\003 " + "\001(\001\022\035\n\025is_wheel_spd_rr_valid\030\004 \001(\010\022:\n\022wh" + "eel_direction_rr\030\005 \001(\0162\036.apollo.canbus.V" + "ehicleSpd.Type\022\024\n\014wheel_spd_rr\030\006 \001(\001\022\035\n\025" + "is_wheel_spd_rl_valid\030\007 \001(\010\022:\n\022wheel_dir" + "ection_rl\030\010 \001(\0162\036.apollo.canbus.VehicleS" + "pd.Type\022\024\n\014wheel_spd_rl\030\t \001(\001\022\035\n\025is_whee" + "l_spd_fr_valid\030\n \001(\010\022:\n\022wheel_direction_" + "fr\030\013 \001(\0162\036.apollo.canbus.VehicleSpd.Type" + "\022\024\n\014wheel_spd_fr\030\014 \001(\001\022\035\n\025is_wheel_spd_f" + "l_valid\030\r \001(\010\022:\n\022wheel_direction_fl\030\016 \001(" + "\0162\036.apollo.canbus.VehicleSpd.Type\022\024\n\014whe" + "el_spd_fl\030\017 \001(\001\022\031\n\021is_yaw_rate_valid\030\020 \001" + "(\010\022\020\n\010yaw_rate\030\021 \001(\001\022\027\n\017yaw_rate_offset\030" + "\022 \001(\001\022\023\n\013is_ax_valid\030\023 \001(\010\022\n\n\002ax\030\024 \001(\001\022\021" + "\n\tax_offset\030\025 \001(\001\022\023\n\013is_ay_valid\030\026 \001(\010\022\n" + "\n\002ay\030\027 \001(\001\022\021\n\tay_offset\030\030 \001(\001\022\017\n\007lat_acc" + "\030\031 \001(\001\022\020\n\010long_acc\030\032 \001(\001\022\020\n\010vert_acc\030\033 \001" + "(\001\022\021\n\troll_rate\030\034 \001(\001\022\017\n\007acc_est\030\035 \001(\001\022\025" + "\n\rtimestamp_sec\030\036 \001(\001\">\n\004Type\022\013\n\007FORWARD" + "\020\000\022\014\n\010BACKWARD\020\001\022\016\n\nSTANDSTILL\020\002\022\013\n\007INVA" + "LID\020\003\"\306\001\n\014Deceleration\022!\n\031is_deceleratio" + "n_available\030\001 \001(\010\022\036\n\026is_deceleration_act" + "ive\030\002 \001(\010\022\024\n\014deceleration\030\003 \001(\001\022\023\n\013is_ev" + "b_fail\030\004 \001(\001\022\024\n\014evb_pressure\030\005 \001(\001\022\026\n\016br" + "ake_pressure\030\006 \001(\001\022\032\n\022brake_pressure_spd" + "\030\007 \001(\001\"\257\010\n\005Brake\022\036\n\026is_brake_pedal_press" + "ed\030\001 \001(\010\022\034\n\024is_brake_force_exist\030\002 \001(\010\022\032" + "\n\022is_brake_over_heat\030\003 \001(\010\022\030\n\020is_hand_br" + "ake_on\030\004 \001(\010\022\034\n\024brake_pedal_position\030\005 \001" + "(\001\022\026\n\016is_brake_valid\030\006 \001(\010\022\023\n\013brake_inpu" + "t\030\007 \001(\001\022\021\n\tbrake_cmd\030\010 \001(\001\022\024\n\014brake_outp" + "ut\030\t \001(\001\022\021\n\tboo_input\030\n \001(\010\022\017\n\007boo_cmd\030\013" + " \001(\010\022\022\n\nboo_output\030\014 \001(\010\022 \n\030watchdog_app" + "lying_brakes\030\r \001(\010\022\027\n\017watchdog_source\030\016 " + "\001(\005\022\025\n\rbrake_enabled\030\017 \001(\010\022\027\n\017driver_ove" + "rride\030\020 \001(\010\022\027\n\017driver_activity\030\021 \001(\010\022\026\n\016" + "watchdog_fault\030\022 \001(\010\022\027\n\017channel_1_fault\030" + "\023 \001(\010\022\027\n\017channel_2_fault\030\024 \001(\010\022\021\n\tboo_fa" + "ult\030\025 \001(\010\022\027\n\017connector_fault\030\026 \001(\010\022\030\n\020br" + "ake_torque_req\030\027 \001(\005\0226\n\nhsa_status\030\030 \001(\016" + "2\".apollo.canbus.Brake.HSAStatusType\022\030\n\020" + "brake_torque_act\030\031 \001(\005\0222\n\010hsa_mode\030\032 \001(\016" + "2 .apollo.canbus.Brake.HSAModeType\022\030\n\020wh" + "eel_torque_act\030\033 \001(\005\022\025\n\rmajor_version\030\034 " + "\001(\005\022\025\n\rminor_version\030\035 \001(\005\022\024\n\014build_numb" + "er\030\036 \001(\005\"\273\001\n\rHSAStatusType\022\020\n\014HSA_INACTI" + "VE\020\000\022\030\n\024HSA_FINDING_GRADIENT\020\001\022\026\n\022HSA_AC" + "TIVE_PRESSED\020\002\022\027\n\023HSA_ACTIVE_RELEASED\020\003\022" + "\024\n\020HSA_FAST_RELEASE\020\004\022\024\n\020HSA_SLOW_RELEAS" + "E\020\005\022\016\n\nHSA_FAILED\020\006\022\021\n\rHSA_UNDEFINED\020\007\"P" + "\n\013HSAModeType\022\013\n\007HSA_OFF\020\000\022\014\n\010HSA_AUTO\020\001" + "\022\016\n\nHSA_MANUAL\020\002\022\026\n\022HSA_MODE_UNDEFINED\020\003" + "\"\333\001\n\003Epb\022\024\n\014is_epb_error\030\001 \001(\010\022\027\n\017is_epb" + "_released\030\002 \001(\010\022\022\n\nepb_status\030\003 \001(\005\022;\n\024p" + "arking_brake_status\030\004 \001(\0162\035.apollo.canbu" + "s.Epb.PBrakeType\"T\n\nPBrakeType\022\016\n\nPBRAKE" + "_OFF\020\000\022\025\n\021PBRAKE_TRANSITION\020\001\022\r\n\tPBRAKE_" + "ON\020\002\022\020\n\014PBRAKE_FAULT\020\003\"\204\004\n\003Gas\022\032\n\022is_gas" + "_pedal_error\030\001 \001(\010\022!\n\031is_gas_pedal_press" + "ed_more\030\002 \001(\010\022\032\n\022gas_pedal_position\030\003 \001(" + "\001\022\024\n\014is_gas_valid\030\004 \001(\010\022\026\n\016throttle_inpu" + "t\030\005 \001(\001\022\024\n\014throttle_cmd\030\006 \001(\001\022\027\n\017throttl" + "e_output\030\007 \001(\001\022\027\n\017watchdog_source\030\010 \001(\005\022" + "\030\n\020throttle_enabled\030\t \001(\010\022\027\n\017driver_over" + "ride\030\n \001(\010\022\027\n\017driver_activity\030\013 \001(\010\022\026\n\016w" + "atchdog_fault\030\014 \001(\010\022\027\n\017channel_1_fault\030\r" + " \001(\010\022\027\n\017channel_2_fault\030\016 \001(\010\022\027\n\017connect" + "or_fault\030\017 \001(\010\022\031\n\021accelerator_pedal\030\020 \001(" + "\001\022\036\n\026accelerator_pedal_rate\030\021 \001(\001\022\025\n\rmaj" + "or_version\030\022 \001(\005\022\025\n\rminor_version\030\023 \001(\005\022" + "\024\n\014build_number\030\024 \001(\005\"\210\002\n\003Esp\022\030\n\020is_esp_" + "acc_error\030\001 \001(\010\022\021\n\tis_esp_on\030\002 \001(\010\022\025\n\ris" + "_esp_active\030\003 \001(\010\022\024\n\014is_abs_error\030\004 \001(\010\022" + "\025\n\ris_abs_active\030\005 \001(\010\022\026\n\016is_tcsvdc_fail" + "\030\006 \001(\010\022\026\n\016is_abs_enabled\030\007 \001(\010\022\026\n\016is_sta" + "b_active\030\010 \001(\010\022\027\n\017is_stab_enabled\030\t \001(\010\022" + "\026\n\016is_trac_active\030\n \001(\010\022\027\n\017is_trac_enabl" + "ed\030\013 \001(\010\"\215\003\n\003Ems\022\037\n\027is_engine_acc_availa" + "ble\030\001 \001(\010\022\033\n\023is_engine_acc_error\030\002 \001(\010\022-" + "\n\014engine_state\030\003 \001(\0162\027.apollo.canbus.Ems" + ".Type\022\037\n\027max_engine_torq_percent\030\004 \001(\001\022\037" + "\n\027min_engine_torq_percent\030\005 \001(\001\022!\n\031base_" + "engine_torq_constant\030\006 \001(\005\022\035\n\025is_engine_" + "speed_error\030\007 \001(\010\022\024\n\014engine_speed\030\010 \001(\001\022" + "\025\n\rengine_torque\030\t \001(\005\022\035\n\025is_over_engine" + "_torque\030\n \001(\010\022\022\n\nengine_rpm\030\013 \001(\001\"5\n\004Typ" + "e\022\010\n\004STOP\020\000\022\t\n\005CRANK\020\001\022\013\n\007RUNNING\020\002\022\013\n\007I" + "NVALID\020\003\"\306\001\n\004Gear\022\037\n\027is_shift_position_v" + "alid\030\001 \001(\010\0227\n\ngear_state\030\002 \001(\0162#.apollo." + "canbus.Chassis.GearPosition\022\027\n\017driver_ov" + "erride\030\003 \001(\010\0225\n\010gear_cmd\030\004 \001(\0162#.apollo." + "canbus.Chassis.GearPosition\022\024\n\014canbus_fa" + "ult\030\005 \001(\010\"\347\005\n\006Safety\022 \n\030is_driver_car_do" + "or_close\030\001 \001(\010\022\031\n\021is_driver_buckled\030\002 \001(" + "\010\022\030\n\020emergency_button\030\003 \001(\005\022\021\n\thas_error" + "\030\004 \001(\010\022\037\n\027is_motor_invertor_fault\030\005 \001(\010\022" + "\027\n\017is_system_fault\030\006 \001(\010\022\036\n\026is_power_bat" + "tery_fault\030\007 \001(\010\022*\n\"is_motor_invertor_ov" + "er_temperature\030\010 \001(\010\022/\n\'is_small_battery" + "_charge_discharge_fault\030\t \001(\010\022\024\n\014driving" + "_mode\030\n \001(\005\022\036\n\026is_passenger_door_open\030\013 " + "\001(\010\022\035\n\025is_rearleft_door_open\030\014 \001(\010\022\036\n\026is" + "_rearright_door_open\030\r \001(\010\022\024\n\014is_hood_op" + "en\030\016 \001(\010\022\025\n\ris_trunk_open\030\017 \001(\010\022\035\n\025is_pa" + "ssenger_detected\030\020 \001(\010\022#\n\033is_passenger_a" + "irbag_enabled\030\021 \001(\010\022\034\n\024is_passenger_buck" + "led\030\022 \001(\010\022\035\n\025front_left_tire_press\030\023 \001(\005" + "\022\036\n\026front_right_tire_press\030\024 \001(\005\022\034\n\024rear" + "_left_tire_press\030\025 \001(\005\022\035\n\025rear_right_tir" + "e_press\030\026 \001(\005\022<\n\020car_driving_mode\030\027 \001(\0162" + "\".apollo.canbus.Chassis.DrivingMode\"\211\010\n\t" + "BasicInfo\022\024\n\014is_auto_mode\030\001 \001(\010\0222\n\013power" + "_state\030\002 \001(\0162\035.apollo.canbus.BasicInfo.T" + "ype\022\033\n\023is_air_bag_deployed\030\003 \001(\010\022\021\n\todo_" + "meter\030\004 \001(\001\022\023\n\013drive_range\030\005 \001(\001\022\027\n\017is_s" + "ystem_error\030\006 \001(\010\022\032\n\022is_human_interrupt\030" + "\007 \001(\010\022\025\n\racc_on_button\030\010 \001(\010\022\026\n\016acc_off_" + "button\030\t \001(\010\022\026\n\016acc_res_button\030\n \001(\010\022\031\n\021" + "acc_cancel_button\030\013 \001(\010\022\031\n\021acc_on_off_bu" + "tton\030\014 \001(\010\022\035\n\025acc_res_cancel_button\030\r \001(" + "\010\022\032\n\022acc_inc_spd_button\030\016 \001(\010\022\032\n\022acc_dec" + "_spd_button\030\017 \001(\010\022\032\n\022acc_inc_gap_button\030" + "\020 \001(\010\022\032\n\022acc_dec_gap_button\030\021 \001(\010\022\022\n\nlka" + "_button\030\022 \001(\010\022\024\n\014canbus_fault\030\023 \001(\010\022\020\n\010l" + "atitude\030\024 \001(\001\022\021\n\tlongitude\030\025 \001(\001\022\021\n\tgps_" + "valid\030\026 \001(\010\022\014\n\004year\030\027 \001(\005\022\r\n\005month\030\030 \001(\005" + "\022\013\n\003day\030\031 \001(\005\022\r\n\005hours\030\032 \001(\005\022\017\n\007minutes\030" + "\033 \001(\005\022\017\n\007seconds\030\034 \001(\005\022\031\n\021compass_direct" + "ion\030\035 \001(\001\022\014\n\004pdop\030\036 \001(\001\022\024\n\014is_gps_fault\030" + "\037 \001(\010\022\023\n\013is_inferred\030 \001(\010\022\020\n\010altitude\030!" + " \001(\001\022\017\n\007heading\030\" \001(\001\022\014\n\004hdop\030# \001(\001\022\014\n\004v" + "dop\030$ \001(\001\0224\n\007quality\030% \001(\0162#.apollo.canb" + "us.BasicInfo.GpsQuality\022\026\n\016num_satellite" + "s\030& \001(\005\022\021\n\tgps_speed\030\' \001(\001\"8\n\004Type\022\007\n\003OF" + "F\020\000\022\007\n\003ACC\020\001\022\006\n\002ON\020\002\022\t\n\005START\020\003\022\013\n\007INVAL" + "ID\020\004\"A\n\nGpsQuality\022\n\n\006FIX_NO\020\000\022\n\n\006FIX_2D" + "\020\001\022\n\n\006FIX_3D\020\002\022\017\n\013FIX_INVALID\020\003b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 8559); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/canbus/chassis_detail.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto +namespace apollo { +namespace canbus { +const ::google::protobuf::EnumDescriptor* ChassisDetail_Type_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[0]; +} +bool ChassisDetail_Type_IsValid(int value) { + switch (value) { + case 0: + case 1: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const ChassisDetail_Type ChassisDetail::QIRUI_EQ_15; +const ChassisDetail_Type ChassisDetail::CHANGAN_RUICHENG; +const ChassisDetail_Type ChassisDetail::Type_MIN; +const ChassisDetail_Type ChassisDetail::Type_MAX; +const int ChassisDetail::Type_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* Light_TurnLightType_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[1]; +} +bool Light_TurnLightType_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Light_TurnLightType Light::TURN_LIGHT_OFF; +const Light_TurnLightType Light::TURN_LEFT_ON; +const Light_TurnLightType Light::TURN_RIGHT_ON; +const Light_TurnLightType Light::TURN_LIGHT_ON; +const Light_TurnLightType Light::TurnLightType_MIN; +const Light_TurnLightType Light::TurnLightType_MAX; +const int Light::TurnLightType_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* Light_LampType_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[2]; +} +bool Light_LampType_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Light_LampType Light::BEAM_OFF; +const Light_LampType Light::HIGH_BEAM_ON; +const Light_LampType Light::LOW_BEAM_ON; +const Light_LampType Light::LampType_MIN; +const Light_LampType Light::LampType_MAX; +const int Light::LampType_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* Light_LincolnLampType_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[3]; +} +bool Light_LincolnLampType_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Light_LincolnLampType Light::BEAM_NULL; +const Light_LincolnLampType Light::BEAM_FLASH_TO_PASS; +const Light_LincolnLampType Light::BEAM_HIGH; +const Light_LincolnLampType Light::BEAM_INVALID; +const Light_LincolnLampType Light::LincolnLampType_MIN; +const Light_LincolnLampType Light::LincolnLampType_MAX; +const int Light::LincolnLampType_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* Light_LincolnWiperType_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[4]; +} +bool Light_LincolnWiperType_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + case 6: + case 7: + case 8: + case 9: + case 10: + case 11: + case 12: + case 13: + case 14: + case 15: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Light_LincolnWiperType Light::WIPER_OFF; +const Light_LincolnWiperType Light::WIPER_AUTO_OFF; +const Light_LincolnWiperType Light::WIPER_OFF_MOVING; +const Light_LincolnWiperType Light::WIPER_MANUAL_OFF; +const Light_LincolnWiperType Light::WIPER_MANUAL_ON; +const Light_LincolnWiperType Light::WIPER_MANUAL_LOW; +const Light_LincolnWiperType Light::WIPER_MANUAL_HIGH; +const Light_LincolnWiperType Light::WIPER_MIST_FLICK; +const Light_LincolnWiperType Light::WIPER_WASH; +const Light_LincolnWiperType Light::WIPER_AUTO_LOW; +const Light_LincolnWiperType Light::WIPER_AUTO_HIGH; +const Light_LincolnWiperType Light::WIPER_COURTESY_WIPE; +const Light_LincolnWiperType Light::WIPER_AUTO_ADJUST; +const Light_LincolnWiperType Light::WIPER_RESERVED; +const Light_LincolnWiperType Light::WIPER_STALLED; +const Light_LincolnWiperType Light::WIPER_NO_DATA; +const Light_LincolnWiperType Light::LincolnWiperType_MIN; +const Light_LincolnWiperType Light::LincolnWiperType_MAX; +const int Light::LincolnWiperType_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* Light_LincolnAmbientType_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[5]; +} +bool Light_LincolnAmbientType_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + case 7: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Light_LincolnAmbientType Light::AMBIENT_DARK; +const Light_LincolnAmbientType Light::AMBIENT_LIGHT; +const Light_LincolnAmbientType Light::AMBIENT_TWILIGHT; +const Light_LincolnAmbientType Light::AMBIENT_TUNNEL_ON; +const Light_LincolnAmbientType Light::AMBIENT_TUNNEL_OFF; +const Light_LincolnAmbientType Light::AMBIENT_INVALID; +const Light_LincolnAmbientType Light::AMBIENT_NO_DATA; +const Light_LincolnAmbientType Light::LincolnAmbientType_MIN; +const Light_LincolnAmbientType Light::LincolnAmbientType_MAX; +const int Light::LincolnAmbientType_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* Eps_Type_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[6]; +} +bool Eps_Type_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Eps_Type Eps::NOT_AVAILABLE; +const Eps_Type Eps::READY; +const Eps_Type Eps::ACTIVE; +const Eps_Type Eps::INVALID; +const Eps_Type Eps::Type_MIN; +const Eps_Type Eps::Type_MAX; +const int Eps::Type_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* VehicleSpd_Type_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[7]; +} +bool VehicleSpd_Type_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const VehicleSpd_Type VehicleSpd::FORWARD; +const VehicleSpd_Type VehicleSpd::BACKWARD; +const VehicleSpd_Type VehicleSpd::STANDSTILL; +const VehicleSpd_Type VehicleSpd::INVALID; +const VehicleSpd_Type VehicleSpd::Type_MIN; +const VehicleSpd_Type VehicleSpd::Type_MAX; +const int VehicleSpd::Type_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* Brake_HSAStatusType_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[8]; +} +bool Brake_HSAStatusType_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + case 6: + case 7: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Brake_HSAStatusType Brake::HSA_INACTIVE; +const Brake_HSAStatusType Brake::HSA_FINDING_GRADIENT; +const Brake_HSAStatusType Brake::HSA_ACTIVE_PRESSED; +const Brake_HSAStatusType Brake::HSA_ACTIVE_RELEASED; +const Brake_HSAStatusType Brake::HSA_FAST_RELEASE; +const Brake_HSAStatusType Brake::HSA_SLOW_RELEASE; +const Brake_HSAStatusType Brake::HSA_FAILED; +const Brake_HSAStatusType Brake::HSA_UNDEFINED; +const Brake_HSAStatusType Brake::HSAStatusType_MIN; +const Brake_HSAStatusType Brake::HSAStatusType_MAX; +const int Brake::HSAStatusType_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* Brake_HSAModeType_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[9]; +} +bool Brake_HSAModeType_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Brake_HSAModeType Brake::HSA_OFF; +const Brake_HSAModeType Brake::HSA_AUTO; +const Brake_HSAModeType Brake::HSA_MANUAL; +const Brake_HSAModeType Brake::HSA_MODE_UNDEFINED; +const Brake_HSAModeType Brake::HSAModeType_MIN; +const Brake_HSAModeType Brake::HSAModeType_MAX; +const int Brake::HSAModeType_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* Epb_PBrakeType_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[10]; +} +bool Epb_PBrakeType_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Epb_PBrakeType Epb::PBRAKE_OFF; +const Epb_PBrakeType Epb::PBRAKE_TRANSITION; +const Epb_PBrakeType Epb::PBRAKE_ON; +const Epb_PBrakeType Epb::PBRAKE_FAULT; +const Epb_PBrakeType Epb::PBrakeType_MIN; +const Epb_PBrakeType Epb::PBrakeType_MAX; +const int Epb::PBrakeType_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* Ems_Type_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[11]; +} +bool Ems_Type_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Ems_Type Ems::STOP; +const Ems_Type Ems::CRANK; +const Ems_Type Ems::RUNNING; +const Ems_Type Ems::INVALID; +const Ems_Type Ems::Type_MIN; +const Ems_Type Ems::Type_MAX; +const int Ems::Type_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* BasicInfo_Type_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[12]; +} +bool BasicInfo_Type_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const BasicInfo_Type BasicInfo::OFF; +const BasicInfo_Type BasicInfo::ACC; +const BasicInfo_Type BasicInfo::ON; +const BasicInfo_Type BasicInfo::START; +const BasicInfo_Type BasicInfo::INVALID; +const BasicInfo_Type BasicInfo::Type_MIN; +const BasicInfo_Type BasicInfo::Type_MAX; +const int BasicInfo::Type_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* BasicInfo_GpsQuality_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_enum_descriptors[13]; +} +bool BasicInfo_GpsQuality_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const BasicInfo_GpsQuality BasicInfo::FIX_NO; +const BasicInfo_GpsQuality BasicInfo::FIX_2D; +const BasicInfo_GpsQuality BasicInfo::FIX_3D; +const BasicInfo_GpsQuality BasicInfo::FIX_INVALID; +const BasicInfo_GpsQuality BasicInfo::GpsQuality_MIN; +const BasicInfo_GpsQuality BasicInfo::GpsQuality_MAX; +const int BasicInfo::GpsQuality_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +// =================================================================== + +void ChassisDetail::InitAsDefaultInstance() { + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->basic_ = const_cast< ::apollo::canbus::BasicInfo*>( + ::apollo::canbus::BasicInfo::internal_default_instance()); + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->safety_ = const_cast< ::apollo::canbus::Safety*>( + ::apollo::canbus::Safety::internal_default_instance()); + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->gear_ = const_cast< ::apollo::canbus::Gear*>( + ::apollo::canbus::Gear::internal_default_instance()); + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->ems_ = const_cast< ::apollo::canbus::Ems*>( + ::apollo::canbus::Ems::internal_default_instance()); + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->esp_ = const_cast< ::apollo::canbus::Esp*>( + ::apollo::canbus::Esp::internal_default_instance()); + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->gas_ = const_cast< ::apollo::canbus::Gas*>( + ::apollo::canbus::Gas::internal_default_instance()); + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->epb_ = const_cast< ::apollo::canbus::Epb*>( + ::apollo::canbus::Epb::internal_default_instance()); + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->brake_ = const_cast< ::apollo::canbus::Brake*>( + ::apollo::canbus::Brake::internal_default_instance()); + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->deceleration_ = const_cast< ::apollo::canbus::Deceleration*>( + ::apollo::canbus::Deceleration::internal_default_instance()); + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->vehicle_spd_ = const_cast< ::apollo::canbus::VehicleSpd*>( + ::apollo::canbus::VehicleSpd::internal_default_instance()); + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->eps_ = const_cast< ::apollo::canbus::Eps*>( + ::apollo::canbus::Eps::internal_default_instance()); + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->light_ = const_cast< ::apollo::canbus::Light*>( + ::apollo::canbus::Light::internal_default_instance()); + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->battery_ = const_cast< ::apollo::canbus::Battery*>( + ::apollo::canbus::Battery::internal_default_instance()); + ::apollo::canbus::_ChassisDetail_default_instance_._instance.get_mutable()->check_response_ = const_cast< ::apollo::canbus::CheckResponseSignal*>( + ::apollo::canbus::CheckResponseSignal::internal_default_instance()); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ChassisDetail::kCarTypeFieldNumber; +const int ChassisDetail::kBasicFieldNumber; +const int ChassisDetail::kSafetyFieldNumber; +const int ChassisDetail::kGearFieldNumber; +const int ChassisDetail::kEmsFieldNumber; +const int ChassisDetail::kEspFieldNumber; +const int ChassisDetail::kGasFieldNumber; +const int ChassisDetail::kEpbFieldNumber; +const int ChassisDetail::kBrakeFieldNumber; +const int ChassisDetail::kDecelerationFieldNumber; +const int ChassisDetail::kVehicleSpdFieldNumber; +const int ChassisDetail::kEpsFieldNumber; +const int ChassisDetail::kLightFieldNumber; +const int ChassisDetail::kBatteryFieldNumber; +const int ChassisDetail::kCheckResponseFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ChassisDetail::ChassisDetail() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_ChassisDetail.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.ChassisDetail) +} +ChassisDetail::ChassisDetail(const ChassisDetail& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_basic()) { + basic_ = new ::apollo::canbus::BasicInfo(*from.basic_); + } else { + basic_ = NULL; + } + if (from.has_safety()) { + safety_ = new ::apollo::canbus::Safety(*from.safety_); + } else { + safety_ = NULL; + } + if (from.has_gear()) { + gear_ = new ::apollo::canbus::Gear(*from.gear_); + } else { + gear_ = NULL; + } + if (from.has_ems()) { + ems_ = new ::apollo::canbus::Ems(*from.ems_); + } else { + ems_ = NULL; + } + if (from.has_esp()) { + esp_ = new ::apollo::canbus::Esp(*from.esp_); + } else { + esp_ = NULL; + } + if (from.has_gas()) { + gas_ = new ::apollo::canbus::Gas(*from.gas_); + } else { + gas_ = NULL; + } + if (from.has_epb()) { + epb_ = new ::apollo::canbus::Epb(*from.epb_); + } else { + epb_ = NULL; + } + if (from.has_brake()) { + brake_ = new ::apollo::canbus::Brake(*from.brake_); + } else { + brake_ = NULL; + } + if (from.has_deceleration()) { + deceleration_ = new ::apollo::canbus::Deceleration(*from.deceleration_); + } else { + deceleration_ = NULL; + } + if (from.has_vehicle_spd()) { + vehicle_spd_ = new ::apollo::canbus::VehicleSpd(*from.vehicle_spd_); + } else { + vehicle_spd_ = NULL; + } + if (from.has_eps()) { + eps_ = new ::apollo::canbus::Eps(*from.eps_); + } else { + eps_ = NULL; + } + if (from.has_light()) { + light_ = new ::apollo::canbus::Light(*from.light_); + } else { + light_ = NULL; + } + if (from.has_battery()) { + battery_ = new ::apollo::canbus::Battery(*from.battery_); + } else { + battery_ = NULL; + } + if (from.has_check_response()) { + check_response_ = new ::apollo::canbus::CheckResponseSignal(*from.check_response_); + } else { + check_response_ = NULL; + } + car_type_ = from.car_type_; + // @@protoc_insertion_point(copy_constructor:apollo.canbus.ChassisDetail) +} + +void ChassisDetail::SharedCtor() { + ::memset(&basic_, 0, static_cast( + reinterpret_cast(&car_type_) - + reinterpret_cast(&basic_)) + sizeof(car_type_)); +} + +ChassisDetail::~ChassisDetail() { + // @@protoc_insertion_point(destructor:apollo.canbus.ChassisDetail) + SharedDtor(); +} + +void ChassisDetail::SharedDtor() { + if (this != internal_default_instance()) delete basic_; + if (this != internal_default_instance()) delete safety_; + if (this != internal_default_instance()) delete gear_; + if (this != internal_default_instance()) delete ems_; + if (this != internal_default_instance()) delete esp_; + if (this != internal_default_instance()) delete gas_; + if (this != internal_default_instance()) delete epb_; + if (this != internal_default_instance()) delete brake_; + if (this != internal_default_instance()) delete deceleration_; + if (this != internal_default_instance()) delete vehicle_spd_; + if (this != internal_default_instance()) delete eps_; + if (this != internal_default_instance()) delete light_; + if (this != internal_default_instance()) delete battery_; + if (this != internal_default_instance()) delete check_response_; +} + +void ChassisDetail::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ChassisDetail::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ChassisDetail& ChassisDetail::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_ChassisDetail.base); + return *internal_default_instance(); +} + + +void ChassisDetail::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.ChassisDetail) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && basic_ != NULL) { + delete basic_; + } + basic_ = NULL; + if (GetArenaNoVirtual() == NULL && safety_ != NULL) { + delete safety_; + } + safety_ = NULL; + if (GetArenaNoVirtual() == NULL && gear_ != NULL) { + delete gear_; + } + gear_ = NULL; + if (GetArenaNoVirtual() == NULL && ems_ != NULL) { + delete ems_; + } + ems_ = NULL; + if (GetArenaNoVirtual() == NULL && esp_ != NULL) { + delete esp_; + } + esp_ = NULL; + if (GetArenaNoVirtual() == NULL && gas_ != NULL) { + delete gas_; + } + gas_ = NULL; + if (GetArenaNoVirtual() == NULL && epb_ != NULL) { + delete epb_; + } + epb_ = NULL; + if (GetArenaNoVirtual() == NULL && brake_ != NULL) { + delete brake_; + } + brake_ = NULL; + if (GetArenaNoVirtual() == NULL && deceleration_ != NULL) { + delete deceleration_; + } + deceleration_ = NULL; + if (GetArenaNoVirtual() == NULL && vehicle_spd_ != NULL) { + delete vehicle_spd_; + } + vehicle_spd_ = NULL; + if (GetArenaNoVirtual() == NULL && eps_ != NULL) { + delete eps_; + } + eps_ = NULL; + if (GetArenaNoVirtual() == NULL && light_ != NULL) { + delete light_; + } + light_ = NULL; + if (GetArenaNoVirtual() == NULL && battery_ != NULL) { + delete battery_; + } + battery_ = NULL; + if (GetArenaNoVirtual() == NULL && check_response_ != NULL) { + delete check_response_; + } + check_response_ = NULL; + car_type_ = 0; + _internal_metadata_.Clear(); +} + +bool ChassisDetail::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.ChassisDetail) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.canbus.ChassisDetail.Type car_type = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_car_type(static_cast< ::apollo::canbus::ChassisDetail_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.BasicInfo basic = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_basic())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Safety safety = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_safety())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Gear gear = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_gear())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Ems ems = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_ems())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Esp esp = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(50u /* 50 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_esp())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Gas gas = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(58u /* 58 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_gas())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Epb epb = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(66u /* 66 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_epb())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Brake brake = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(74u /* 74 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_brake())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Deceleration deceleration = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(82u /* 82 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_deceleration())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.VehicleSpd vehicle_spd = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(90u /* 90 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_vehicle_spd())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Eps eps = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(98u /* 98 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_eps())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Light light = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(106u /* 106 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_light())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Battery battery = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(114u /* 114 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_battery())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.CheckResponseSignal check_response = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(122u /* 122 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_check_response())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.ChassisDetail) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.ChassisDetail) + return false; +#undef DO_ +} + +void ChassisDetail::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.ChassisDetail) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.canbus.ChassisDetail.Type car_type = 1; + if (this->car_type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->car_type(), output); + } + + // .apollo.canbus.BasicInfo basic = 2; + if (this->has_basic()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_basic(), output); + } + + // .apollo.canbus.Safety safety = 3; + if (this->has_safety()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_safety(), output); + } + + // .apollo.canbus.Gear gear = 4; + if (this->has_gear()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, this->_internal_gear(), output); + } + + // .apollo.canbus.Ems ems = 5; + if (this->has_ems()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, this->_internal_ems(), output); + } + + // .apollo.canbus.Esp esp = 6; + if (this->has_esp()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 6, this->_internal_esp(), output); + } + + // .apollo.canbus.Gas gas = 7; + if (this->has_gas()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 7, this->_internal_gas(), output); + } + + // .apollo.canbus.Epb epb = 8; + if (this->has_epb()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 8, this->_internal_epb(), output); + } + + // .apollo.canbus.Brake brake = 9; + if (this->has_brake()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 9, this->_internal_brake(), output); + } + + // .apollo.canbus.Deceleration deceleration = 10; + if (this->has_deceleration()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 10, this->_internal_deceleration(), output); + } + + // .apollo.canbus.VehicleSpd vehicle_spd = 11; + if (this->has_vehicle_spd()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 11, this->_internal_vehicle_spd(), output); + } + + // .apollo.canbus.Eps eps = 12; + if (this->has_eps()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 12, this->_internal_eps(), output); + } + + // .apollo.canbus.Light light = 13; + if (this->has_light()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 13, this->_internal_light(), output); + } + + // .apollo.canbus.Battery battery = 14; + if (this->has_battery()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 14, this->_internal_battery(), output); + } + + // .apollo.canbus.CheckResponseSignal check_response = 15; + if (this->has_check_response()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 15, this->_internal_check_response(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.ChassisDetail) +} + +::google::protobuf::uint8* ChassisDetail::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.ChassisDetail) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.canbus.ChassisDetail.Type car_type = 1; + if (this->car_type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->car_type(), target); + } + + // .apollo.canbus.BasicInfo basic = 2; + if (this->has_basic()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_basic(), deterministic, target); + } + + // .apollo.canbus.Safety safety = 3; + if (this->has_safety()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_safety(), deterministic, target); + } + + // .apollo.canbus.Gear gear = 4; + if (this->has_gear()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->_internal_gear(), deterministic, target); + } + + // .apollo.canbus.Ems ems = 5; + if (this->has_ems()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 5, this->_internal_ems(), deterministic, target); + } + + // .apollo.canbus.Esp esp = 6; + if (this->has_esp()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 6, this->_internal_esp(), deterministic, target); + } + + // .apollo.canbus.Gas gas = 7; + if (this->has_gas()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 7, this->_internal_gas(), deterministic, target); + } + + // .apollo.canbus.Epb epb = 8; + if (this->has_epb()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 8, this->_internal_epb(), deterministic, target); + } + + // .apollo.canbus.Brake brake = 9; + if (this->has_brake()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 9, this->_internal_brake(), deterministic, target); + } + + // .apollo.canbus.Deceleration deceleration = 10; + if (this->has_deceleration()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 10, this->_internal_deceleration(), deterministic, target); + } + + // .apollo.canbus.VehicleSpd vehicle_spd = 11; + if (this->has_vehicle_spd()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 11, this->_internal_vehicle_spd(), deterministic, target); + } + + // .apollo.canbus.Eps eps = 12; + if (this->has_eps()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 12, this->_internal_eps(), deterministic, target); + } + + // .apollo.canbus.Light light = 13; + if (this->has_light()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 13, this->_internal_light(), deterministic, target); + } + + // .apollo.canbus.Battery battery = 14; + if (this->has_battery()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 14, this->_internal_battery(), deterministic, target); + } + + // .apollo.canbus.CheckResponseSignal check_response = 15; + if (this->has_check_response()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 15, this->_internal_check_response(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.ChassisDetail) + return target; +} + +size_t ChassisDetail::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.ChassisDetail) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.canbus.BasicInfo basic = 2; + if (this->has_basic()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *basic_); + } + + // .apollo.canbus.Safety safety = 3; + if (this->has_safety()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *safety_); + } + + // .apollo.canbus.Gear gear = 4; + if (this->has_gear()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *gear_); + } + + // .apollo.canbus.Ems ems = 5; + if (this->has_ems()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *ems_); + } + + // .apollo.canbus.Esp esp = 6; + if (this->has_esp()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *esp_); + } + + // .apollo.canbus.Gas gas = 7; + if (this->has_gas()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *gas_); + } + + // .apollo.canbus.Epb epb = 8; + if (this->has_epb()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *epb_); + } + + // .apollo.canbus.Brake brake = 9; + if (this->has_brake()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *brake_); + } + + // .apollo.canbus.Deceleration deceleration = 10; + if (this->has_deceleration()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *deceleration_); + } + + // .apollo.canbus.VehicleSpd vehicle_spd = 11; + if (this->has_vehicle_spd()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *vehicle_spd_); + } + + // .apollo.canbus.Eps eps = 12; + if (this->has_eps()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *eps_); + } + + // .apollo.canbus.Light light = 13; + if (this->has_light()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *light_); + } + + // .apollo.canbus.Battery battery = 14; + if (this->has_battery()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *battery_); + } + + // .apollo.canbus.CheckResponseSignal check_response = 15; + if (this->has_check_response()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *check_response_); + } + + // .apollo.canbus.ChassisDetail.Type car_type = 1; + if (this->car_type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->car_type()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ChassisDetail::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.ChassisDetail) + GOOGLE_DCHECK_NE(&from, this); + const ChassisDetail* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.ChassisDetail) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.ChassisDetail) + MergeFrom(*source); + } +} + +void ChassisDetail::MergeFrom(const ChassisDetail& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.ChassisDetail) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_basic()) { + mutable_basic()->::apollo::canbus::BasicInfo::MergeFrom(from.basic()); + } + if (from.has_safety()) { + mutable_safety()->::apollo::canbus::Safety::MergeFrom(from.safety()); + } + if (from.has_gear()) { + mutable_gear()->::apollo::canbus::Gear::MergeFrom(from.gear()); + } + if (from.has_ems()) { + mutable_ems()->::apollo::canbus::Ems::MergeFrom(from.ems()); + } + if (from.has_esp()) { + mutable_esp()->::apollo::canbus::Esp::MergeFrom(from.esp()); + } + if (from.has_gas()) { + mutable_gas()->::apollo::canbus::Gas::MergeFrom(from.gas()); + } + if (from.has_epb()) { + mutable_epb()->::apollo::canbus::Epb::MergeFrom(from.epb()); + } + if (from.has_brake()) { + mutable_brake()->::apollo::canbus::Brake::MergeFrom(from.brake()); + } + if (from.has_deceleration()) { + mutable_deceleration()->::apollo::canbus::Deceleration::MergeFrom(from.deceleration()); + } + if (from.has_vehicle_spd()) { + mutable_vehicle_spd()->::apollo::canbus::VehicleSpd::MergeFrom(from.vehicle_spd()); + } + if (from.has_eps()) { + mutable_eps()->::apollo::canbus::Eps::MergeFrom(from.eps()); + } + if (from.has_light()) { + mutable_light()->::apollo::canbus::Light::MergeFrom(from.light()); + } + if (from.has_battery()) { + mutable_battery()->::apollo::canbus::Battery::MergeFrom(from.battery()); + } + if (from.has_check_response()) { + mutable_check_response()->::apollo::canbus::CheckResponseSignal::MergeFrom(from.check_response()); + } + if (from.car_type() != 0) { + set_car_type(from.car_type()); + } +} + +void ChassisDetail::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.ChassisDetail) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ChassisDetail::CopyFrom(const ChassisDetail& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.ChassisDetail) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ChassisDetail::IsInitialized() const { + return true; +} + +void ChassisDetail::Swap(ChassisDetail* other) { + if (other == this) return; + InternalSwap(other); +} +void ChassisDetail::InternalSwap(ChassisDetail* other) { + using std::swap; + swap(basic_, other->basic_); + swap(safety_, other->safety_); + swap(gear_, other->gear_); + swap(ems_, other->ems_); + swap(esp_, other->esp_); + swap(gas_, other->gas_); + swap(epb_, other->epb_); + swap(brake_, other->brake_); + swap(deceleration_, other->deceleration_); + swap(vehicle_spd_, other->vehicle_spd_); + swap(eps_, other->eps_); + swap(light_, other->light_); + swap(battery_, other->battery_); + swap(check_response_, other->check_response_); + swap(car_type_, other->car_type_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ChassisDetail::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void CheckResponseSignal::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int CheckResponseSignal::kIsEpsOnlineFieldNumber; +const int CheckResponseSignal::kIsEpbOnlineFieldNumber; +const int CheckResponseSignal::kIsEspOnlineFieldNumber; +const int CheckResponseSignal::kIsVtogOnlineFieldNumber; +const int CheckResponseSignal::kIsScuOnlineFieldNumber; +const int CheckResponseSignal::kIsSwitchOnlineFieldNumber; +const int CheckResponseSignal::kIsVcuOnlineFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +CheckResponseSignal::CheckResponseSignal() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_CheckResponseSignal.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.CheckResponseSignal) +} +CheckResponseSignal::CheckResponseSignal(const CheckResponseSignal& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&is_eps_online_, &from.is_eps_online_, + static_cast(reinterpret_cast(&is_vcu_online_) - + reinterpret_cast(&is_eps_online_)) + sizeof(is_vcu_online_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.CheckResponseSignal) +} + +void CheckResponseSignal::SharedCtor() { + ::memset(&is_eps_online_, 0, static_cast( + reinterpret_cast(&is_vcu_online_) - + reinterpret_cast(&is_eps_online_)) + sizeof(is_vcu_online_)); +} + +CheckResponseSignal::~CheckResponseSignal() { + // @@protoc_insertion_point(destructor:apollo.canbus.CheckResponseSignal) + SharedDtor(); +} + +void CheckResponseSignal::SharedDtor() { +} + +void CheckResponseSignal::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* CheckResponseSignal::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const CheckResponseSignal& CheckResponseSignal::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_CheckResponseSignal.base); + return *internal_default_instance(); +} + + +void CheckResponseSignal::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.CheckResponseSignal) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&is_eps_online_, 0, static_cast( + reinterpret_cast(&is_vcu_online_) - + reinterpret_cast(&is_eps_online_)) + sizeof(is_vcu_online_)); + _internal_metadata_.Clear(); +} + +bool CheckResponseSignal::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.CheckResponseSignal) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_eps_online = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_eps_online_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_epb_online = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_epb_online_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_esp_online = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_esp_online_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_vtog_online = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_vtog_online_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_scu_online = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(40u /* 40 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_scu_online_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_switch_online = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(48u /* 48 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_switch_online_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_vcu_online = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(56u /* 56 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_vcu_online_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.CheckResponseSignal) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.CheckResponseSignal) + return false; +#undef DO_ +} + +void CheckResponseSignal::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.CheckResponseSignal) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_eps_online = 1; + if (this->is_eps_online() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_eps_online(), output); + } + + // bool is_epb_online = 2; + if (this->is_epb_online() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_epb_online(), output); + } + + // bool is_esp_online = 3; + if (this->is_esp_online() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(3, this->is_esp_online(), output); + } + + // bool is_vtog_online = 4; + if (this->is_vtog_online() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(4, this->is_vtog_online(), output); + } + + // bool is_scu_online = 5; + if (this->is_scu_online() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(5, this->is_scu_online(), output); + } + + // bool is_switch_online = 6; + if (this->is_switch_online() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(6, this->is_switch_online(), output); + } + + // bool is_vcu_online = 7; + if (this->is_vcu_online() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(7, this->is_vcu_online(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.CheckResponseSignal) +} + +::google::protobuf::uint8* CheckResponseSignal::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.CheckResponseSignal) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_eps_online = 1; + if (this->is_eps_online() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_eps_online(), target); + } + + // bool is_epb_online = 2; + if (this->is_epb_online() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_epb_online(), target); + } + + // bool is_esp_online = 3; + if (this->is_esp_online() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(3, this->is_esp_online(), target); + } + + // bool is_vtog_online = 4; + if (this->is_vtog_online() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(4, this->is_vtog_online(), target); + } + + // bool is_scu_online = 5; + if (this->is_scu_online() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(5, this->is_scu_online(), target); + } + + // bool is_switch_online = 6; + if (this->is_switch_online() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(6, this->is_switch_online(), target); + } + + // bool is_vcu_online = 7; + if (this->is_vcu_online() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(7, this->is_vcu_online(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.CheckResponseSignal) + return target; +} + +size_t CheckResponseSignal::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.CheckResponseSignal) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // bool is_eps_online = 1; + if (this->is_eps_online() != 0) { + total_size += 1 + 1; + } + + // bool is_epb_online = 2; + if (this->is_epb_online() != 0) { + total_size += 1 + 1; + } + + // bool is_esp_online = 3; + if (this->is_esp_online() != 0) { + total_size += 1 + 1; + } + + // bool is_vtog_online = 4; + if (this->is_vtog_online() != 0) { + total_size += 1 + 1; + } + + // bool is_scu_online = 5; + if (this->is_scu_online() != 0) { + total_size += 1 + 1; + } + + // bool is_switch_online = 6; + if (this->is_switch_online() != 0) { + total_size += 1 + 1; + } + + // bool is_vcu_online = 7; + if (this->is_vcu_online() != 0) { + total_size += 1 + 1; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void CheckResponseSignal::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.CheckResponseSignal) + GOOGLE_DCHECK_NE(&from, this); + const CheckResponseSignal* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.CheckResponseSignal) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.CheckResponseSignal) + MergeFrom(*source); + } +} + +void CheckResponseSignal::MergeFrom(const CheckResponseSignal& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.CheckResponseSignal) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.is_eps_online() != 0) { + set_is_eps_online(from.is_eps_online()); + } + if (from.is_epb_online() != 0) { + set_is_epb_online(from.is_epb_online()); + } + if (from.is_esp_online() != 0) { + set_is_esp_online(from.is_esp_online()); + } + if (from.is_vtog_online() != 0) { + set_is_vtog_online(from.is_vtog_online()); + } + if (from.is_scu_online() != 0) { + set_is_scu_online(from.is_scu_online()); + } + if (from.is_switch_online() != 0) { + set_is_switch_online(from.is_switch_online()); + } + if (from.is_vcu_online() != 0) { + set_is_vcu_online(from.is_vcu_online()); + } +} + +void CheckResponseSignal::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.CheckResponseSignal) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void CheckResponseSignal::CopyFrom(const CheckResponseSignal& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.CheckResponseSignal) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool CheckResponseSignal::IsInitialized() const { + return true; +} + +void CheckResponseSignal::Swap(CheckResponseSignal* other) { + if (other == this) return; + InternalSwap(other); +} +void CheckResponseSignal::InternalSwap(CheckResponseSignal* other) { + using std::swap; + swap(is_eps_online_, other->is_eps_online_); + swap(is_epb_online_, other->is_epb_online_); + swap(is_esp_online_, other->is_esp_online_); + swap(is_vtog_online_, other->is_vtog_online_); + swap(is_scu_online_, other->is_scu_online_); + swap(is_switch_online_, other->is_switch_online_); + swap(is_vcu_online_, other->is_vcu_online_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata CheckResponseSignal::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Battery::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Battery::kBatteryPercentFieldNumber; +const int Battery::kFuelLevelFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Battery::Battery() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Battery.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.Battery) +} +Battery::Battery(const Battery& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&battery_percent_, &from.battery_percent_, + static_cast(reinterpret_cast(&fuel_level_) - + reinterpret_cast(&battery_percent_)) + sizeof(fuel_level_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.Battery) +} + +void Battery::SharedCtor() { + ::memset(&battery_percent_, 0, static_cast( + reinterpret_cast(&fuel_level_) - + reinterpret_cast(&battery_percent_)) + sizeof(fuel_level_)); +} + +Battery::~Battery() { + // @@protoc_insertion_point(destructor:apollo.canbus.Battery) + SharedDtor(); +} + +void Battery::SharedDtor() { +} + +void Battery::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Battery::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Battery& Battery::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Battery.base); + return *internal_default_instance(); +} + + +void Battery::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.Battery) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&battery_percent_, 0, static_cast( + reinterpret_cast(&fuel_level_) - + reinterpret_cast(&battery_percent_)) + sizeof(fuel_level_)); + _internal_metadata_.Clear(); +} + +bool Battery::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.Battery) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double battery_percent = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &battery_percent_))); + } else { + goto handle_unusual; + } + break; + } + + // double fuel_level = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &fuel_level_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.Battery) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.Battery) + return false; +#undef DO_ +} + +void Battery::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.Battery) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double battery_percent = 1; + if (this->battery_percent() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->battery_percent(), output); + } + + // double fuel_level = 2; + if (this->fuel_level() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->fuel_level(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.Battery) +} + +::google::protobuf::uint8* Battery::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.Battery) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double battery_percent = 1; + if (this->battery_percent() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->battery_percent(), target); + } + + // double fuel_level = 2; + if (this->fuel_level() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->fuel_level(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.Battery) + return target; +} + +size_t Battery::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.Battery) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double battery_percent = 1; + if (this->battery_percent() != 0) { + total_size += 1 + 8; + } + + // double fuel_level = 2; + if (this->fuel_level() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Battery::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.Battery) + GOOGLE_DCHECK_NE(&from, this); + const Battery* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.Battery) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.Battery) + MergeFrom(*source); + } +} + +void Battery::MergeFrom(const Battery& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.Battery) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.battery_percent() != 0) { + set_battery_percent(from.battery_percent()); + } + if (from.fuel_level() != 0) { + set_fuel_level(from.fuel_level()); + } +} + +void Battery::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.Battery) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Battery::CopyFrom(const Battery& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.Battery) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Battery::IsInitialized() const { + return true; +} + +void Battery::Swap(Battery* other) { + if (other == this) return; + InternalSwap(other); +} +void Battery::InternalSwap(Battery* other) { + using std::swap; + swap(battery_percent_, other->battery_percent_); + swap(fuel_level_, other->fuel_level_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Battery::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Light::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Light::kTurnLightTypeFieldNumber; +const int Light::kLampTypeFieldNumber; +const int Light::kIsBrakeLampOnFieldNumber; +const int Light::kIsAutoLightFieldNumber; +const int Light::kWiperGearFieldNumber; +const int Light::kLotionGearFieldNumber; +const int Light::kIsHornOnFieldNumber; +const int Light::kLincolnLampTypeFieldNumber; +const int Light::kLincolnWiperFieldNumber; +const int Light::kLincolnAmbientFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Light::Light() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Light.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.Light) +} +Light::Light(const Light& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&turn_light_type_, &from.turn_light_type_, + static_cast(reinterpret_cast(&lincoln_ambient_) - + reinterpret_cast(&turn_light_type_)) + sizeof(lincoln_ambient_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.Light) +} + +void Light::SharedCtor() { + ::memset(&turn_light_type_, 0, static_cast( + reinterpret_cast(&lincoln_ambient_) - + reinterpret_cast(&turn_light_type_)) + sizeof(lincoln_ambient_)); +} + +Light::~Light() { + // @@protoc_insertion_point(destructor:apollo.canbus.Light) + SharedDtor(); +} + +void Light::SharedDtor() { +} + +void Light::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Light::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Light& Light::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Light.base); + return *internal_default_instance(); +} + + +void Light::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.Light) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&turn_light_type_, 0, static_cast( + reinterpret_cast(&lincoln_ambient_) - + reinterpret_cast(&turn_light_type_)) + sizeof(lincoln_ambient_)); + _internal_metadata_.Clear(); +} + +bool Light::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.Light) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.canbus.Light.TurnLightType turn_light_type = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_turn_light_type(static_cast< ::apollo::canbus::Light_TurnLightType >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Light.LampType lamp_type = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_lamp_type(static_cast< ::apollo::canbus::Light_LampType >(value)); + } else { + goto handle_unusual; + } + break; + } + + // bool is_brake_lamp_on = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_brake_lamp_on_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_auto_light = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_auto_light_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 wiper_gear = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(40u /* 40 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &wiper_gear_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 lotion_gear = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(48u /* 48 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &lotion_gear_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_horn_on = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(56u /* 56 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_horn_on_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Light.LincolnLampType lincoln_lamp_type = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(64u /* 64 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_lincoln_lamp_type(static_cast< ::apollo::canbus::Light_LincolnLampType >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Light.LincolnWiperType lincoln_wiper = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(72u /* 72 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_lincoln_wiper(static_cast< ::apollo::canbus::Light_LincolnWiperType >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Light.LincolnAmbientType lincoln_ambient = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(80u /* 80 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_lincoln_ambient(static_cast< ::apollo::canbus::Light_LincolnAmbientType >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.Light) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.Light) + return false; +#undef DO_ +} + +void Light::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.Light) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.canbus.Light.TurnLightType turn_light_type = 1; + if (this->turn_light_type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->turn_light_type(), output); + } + + // .apollo.canbus.Light.LampType lamp_type = 2; + if (this->lamp_type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 2, this->lamp_type(), output); + } + + // bool is_brake_lamp_on = 3; + if (this->is_brake_lamp_on() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(3, this->is_brake_lamp_on(), output); + } + + // bool is_auto_light = 4; + if (this->is_auto_light() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(4, this->is_auto_light(), output); + } + + // int32 wiper_gear = 5; + if (this->wiper_gear() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(5, this->wiper_gear(), output); + } + + // int32 lotion_gear = 6; + if (this->lotion_gear() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(6, this->lotion_gear(), output); + } + + // bool is_horn_on = 7; + if (this->is_horn_on() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(7, this->is_horn_on(), output); + } + + // .apollo.canbus.Light.LincolnLampType lincoln_lamp_type = 8; + if (this->lincoln_lamp_type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 8, this->lincoln_lamp_type(), output); + } + + // .apollo.canbus.Light.LincolnWiperType lincoln_wiper = 9; + if (this->lincoln_wiper() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 9, this->lincoln_wiper(), output); + } + + // .apollo.canbus.Light.LincolnAmbientType lincoln_ambient = 10; + if (this->lincoln_ambient() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 10, this->lincoln_ambient(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.Light) +} + +::google::protobuf::uint8* Light::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.Light) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.canbus.Light.TurnLightType turn_light_type = 1; + if (this->turn_light_type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->turn_light_type(), target); + } + + // .apollo.canbus.Light.LampType lamp_type = 2; + if (this->lamp_type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 2, this->lamp_type(), target); + } + + // bool is_brake_lamp_on = 3; + if (this->is_brake_lamp_on() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(3, this->is_brake_lamp_on(), target); + } + + // bool is_auto_light = 4; + if (this->is_auto_light() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(4, this->is_auto_light(), target); + } + + // int32 wiper_gear = 5; + if (this->wiper_gear() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(5, this->wiper_gear(), target); + } + + // int32 lotion_gear = 6; + if (this->lotion_gear() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(6, this->lotion_gear(), target); + } + + // bool is_horn_on = 7; + if (this->is_horn_on() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(7, this->is_horn_on(), target); + } + + // .apollo.canbus.Light.LincolnLampType lincoln_lamp_type = 8; + if (this->lincoln_lamp_type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 8, this->lincoln_lamp_type(), target); + } + + // .apollo.canbus.Light.LincolnWiperType lincoln_wiper = 9; + if (this->lincoln_wiper() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 9, this->lincoln_wiper(), target); + } + + // .apollo.canbus.Light.LincolnAmbientType lincoln_ambient = 10; + if (this->lincoln_ambient() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 10, this->lincoln_ambient(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.Light) + return target; +} + +size_t Light::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.Light) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.canbus.Light.TurnLightType turn_light_type = 1; + if (this->turn_light_type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->turn_light_type()); + } + + // .apollo.canbus.Light.LampType lamp_type = 2; + if (this->lamp_type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->lamp_type()); + } + + // bool is_brake_lamp_on = 3; + if (this->is_brake_lamp_on() != 0) { + total_size += 1 + 1; + } + + // bool is_auto_light = 4; + if (this->is_auto_light() != 0) { + total_size += 1 + 1; + } + + // bool is_horn_on = 7; + if (this->is_horn_on() != 0) { + total_size += 1 + 1; + } + + // int32 wiper_gear = 5; + if (this->wiper_gear() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->wiper_gear()); + } + + // int32 lotion_gear = 6; + if (this->lotion_gear() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->lotion_gear()); + } + + // .apollo.canbus.Light.LincolnLampType lincoln_lamp_type = 8; + if (this->lincoln_lamp_type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->lincoln_lamp_type()); + } + + // .apollo.canbus.Light.LincolnWiperType lincoln_wiper = 9; + if (this->lincoln_wiper() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->lincoln_wiper()); + } + + // .apollo.canbus.Light.LincolnAmbientType lincoln_ambient = 10; + if (this->lincoln_ambient() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->lincoln_ambient()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Light::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.Light) + GOOGLE_DCHECK_NE(&from, this); + const Light* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.Light) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.Light) + MergeFrom(*source); + } +} + +void Light::MergeFrom(const Light& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.Light) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.turn_light_type() != 0) { + set_turn_light_type(from.turn_light_type()); + } + if (from.lamp_type() != 0) { + set_lamp_type(from.lamp_type()); + } + if (from.is_brake_lamp_on() != 0) { + set_is_brake_lamp_on(from.is_brake_lamp_on()); + } + if (from.is_auto_light() != 0) { + set_is_auto_light(from.is_auto_light()); + } + if (from.is_horn_on() != 0) { + set_is_horn_on(from.is_horn_on()); + } + if (from.wiper_gear() != 0) { + set_wiper_gear(from.wiper_gear()); + } + if (from.lotion_gear() != 0) { + set_lotion_gear(from.lotion_gear()); + } + if (from.lincoln_lamp_type() != 0) { + set_lincoln_lamp_type(from.lincoln_lamp_type()); + } + if (from.lincoln_wiper() != 0) { + set_lincoln_wiper(from.lincoln_wiper()); + } + if (from.lincoln_ambient() != 0) { + set_lincoln_ambient(from.lincoln_ambient()); + } +} + +void Light::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.Light) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Light::CopyFrom(const Light& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.Light) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Light::IsInitialized() const { + return true; +} + +void Light::Swap(Light* other) { + if (other == this) return; + InternalSwap(other); +} +void Light::InternalSwap(Light* other) { + using std::swap; + swap(turn_light_type_, other->turn_light_type_); + swap(lamp_type_, other->lamp_type_); + swap(is_brake_lamp_on_, other->is_brake_lamp_on_); + swap(is_auto_light_, other->is_auto_light_); + swap(is_horn_on_, other->is_horn_on_); + swap(wiper_gear_, other->wiper_gear_); + swap(lotion_gear_, other->lotion_gear_); + swap(lincoln_lamp_type_, other->lincoln_lamp_type_); + swap(lincoln_wiper_, other->lincoln_wiper_); + swap(lincoln_ambient_, other->lincoln_ambient_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Light::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Eps::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Eps::kIsEpsFailFieldNumber; +const int Eps::kEpsControlStateFieldNumber; +const int Eps::kEpsDriverHandTorqFieldNumber; +const int Eps::kIsSteeringAngleValidFieldNumber; +const int Eps::kSteeringAngleFieldNumber; +const int Eps::kSteeringAngleSpdFieldNumber; +const int Eps::kIsTrimmingStatusFieldNumber; +const int Eps::kIsCalibrationStatusFieldNumber; +const int Eps::kIsFailureStatusFieldNumber; +const int Eps::kAllowEnterAutonomousModeFieldNumber; +const int Eps::kCurrentDrivingModeFieldNumber; +const int Eps::kSteeringAngleCmdFieldNumber; +const int Eps::kVehicleSpeedFieldNumber; +const int Eps::kEpasTorqueFieldNumber; +const int Eps::kSteeringEnabledFieldNumber; +const int Eps::kDriverOverrideFieldNumber; +const int Eps::kDriverActivityFieldNumber; +const int Eps::kWatchdogFaultFieldNumber; +const int Eps::kChannel1FaultFieldNumber; +const int Eps::kChannel2FaultFieldNumber; +const int Eps::kCalibrationFaultFieldNumber; +const int Eps::kConnectorFaultFieldNumber; +const int Eps::kTimestamp65FieldNumber; +const int Eps::kMajorVersionFieldNumber; +const int Eps::kMinorVersionFieldNumber; +const int Eps::kBuildNumberFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Eps::Eps() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Eps.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.Eps) +} +Eps::Eps(const Eps& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&eps_driver_hand_torq_, &from.eps_driver_hand_torq_, + static_cast(reinterpret_cast(&build_number_) - + reinterpret_cast(&eps_driver_hand_torq_)) + sizeof(build_number_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.Eps) +} + +void Eps::SharedCtor() { + ::memset(&eps_driver_hand_torq_, 0, static_cast( + reinterpret_cast(&build_number_) - + reinterpret_cast(&eps_driver_hand_torq_)) + sizeof(build_number_)); +} + +Eps::~Eps() { + // @@protoc_insertion_point(destructor:apollo.canbus.Eps) + SharedDtor(); +} + +void Eps::SharedDtor() { +} + +void Eps::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Eps::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Eps& Eps::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Eps.base); + return *internal_default_instance(); +} + + +void Eps::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.Eps) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&eps_driver_hand_torq_, 0, static_cast( + reinterpret_cast(&build_number_) - + reinterpret_cast(&eps_driver_hand_torq_)) + sizeof(build_number_)); + _internal_metadata_.Clear(); +} + +bool Eps::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.Eps) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_eps_fail = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_eps_fail_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Eps.Type eps_control_state = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_eps_control_state(static_cast< ::apollo::canbus::Eps_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // double eps_driver_hand_torq = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &eps_driver_hand_torq_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_steering_angle_valid = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_steering_angle_valid_))); + } else { + goto handle_unusual; + } + break; + } + + // double steering_angle = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steering_angle_))); + } else { + goto handle_unusual; + } + break; + } + + // double steering_angle_spd = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steering_angle_spd_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_trimming_status = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(56u /* 56 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_trimming_status_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_calibration_status = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(64u /* 64 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_calibration_status_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_failure_status = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(72u /* 72 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_failure_status_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 allow_enter_autonomous_mode = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(80u /* 80 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &allow_enter_autonomous_mode_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 current_driving_mode = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(88u /* 88 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, ¤t_driving_mode_))); + } else { + goto handle_unusual; + } + break; + } + + // double steering_angle_cmd = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(97u /* 97 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steering_angle_cmd_))); + } else { + goto handle_unusual; + } + break; + } + + // double vehicle_speed = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(105u /* 105 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &vehicle_speed_))); + } else { + goto handle_unusual; + } + break; + } + + // double epas_torque = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(113u /* 113 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &epas_torque_))); + } else { + goto handle_unusual; + } + break; + } + + // bool steering_enabled = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(120u /* 120 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &steering_enabled_))); + } else { + goto handle_unusual; + } + break; + } + + // bool driver_override = 16; + case 16: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(128u /* 128 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &driver_override_))); + } else { + goto handle_unusual; + } + break; + } + + // bool driver_activity = 17; + case 17: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(136u /* 136 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &driver_activity_))); + } else { + goto handle_unusual; + } + break; + } + + // bool watchdog_fault = 18; + case 18: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(144u /* 144 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &watchdog_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool channel_1_fault = 19; + case 19: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(152u /* 152 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &channel_1_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool channel_2_fault = 20; + case 20: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(160u /* 160 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &channel_2_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool calibration_fault = 21; + case 21: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(168u /* 168 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &calibration_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool connector_fault = 22; + case 22: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(176u /* 176 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &connector_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // double timestamp_65 = 23; + case 23: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(185u /* 185 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, ×tamp_65_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 major_version = 24; + case 24: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(192u /* 192 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &major_version_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 minor_version = 25; + case 25: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(200u /* 200 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &minor_version_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 build_number = 26; + case 26: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(208u /* 208 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &build_number_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.Eps) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.Eps) + return false; +#undef DO_ +} + +void Eps::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.Eps) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_eps_fail = 1; + if (this->is_eps_fail() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_eps_fail(), output); + } + + // .apollo.canbus.Eps.Type eps_control_state = 2; + if (this->eps_control_state() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 2, this->eps_control_state(), output); + } + + // double eps_driver_hand_torq = 3; + if (this->eps_driver_hand_torq() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->eps_driver_hand_torq(), output); + } + + // bool is_steering_angle_valid = 4; + if (this->is_steering_angle_valid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(4, this->is_steering_angle_valid(), output); + } + + // double steering_angle = 5; + if (this->steering_angle() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->steering_angle(), output); + } + + // double steering_angle_spd = 6; + if (this->steering_angle_spd() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->steering_angle_spd(), output); + } + + // bool is_trimming_status = 7; + if (this->is_trimming_status() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(7, this->is_trimming_status(), output); + } + + // bool is_calibration_status = 8; + if (this->is_calibration_status() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(8, this->is_calibration_status(), output); + } + + // bool is_failure_status = 9; + if (this->is_failure_status() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(9, this->is_failure_status(), output); + } + + // int32 allow_enter_autonomous_mode = 10; + if (this->allow_enter_autonomous_mode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(10, this->allow_enter_autonomous_mode(), output); + } + + // int32 current_driving_mode = 11; + if (this->current_driving_mode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(11, this->current_driving_mode(), output); + } + + // double steering_angle_cmd = 12; + if (this->steering_angle_cmd() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(12, this->steering_angle_cmd(), output); + } + + // double vehicle_speed = 13; + if (this->vehicle_speed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(13, this->vehicle_speed(), output); + } + + // double epas_torque = 14; + if (this->epas_torque() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(14, this->epas_torque(), output); + } + + // bool steering_enabled = 15; + if (this->steering_enabled() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(15, this->steering_enabled(), output); + } + + // bool driver_override = 16; + if (this->driver_override() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(16, this->driver_override(), output); + } + + // bool driver_activity = 17; + if (this->driver_activity() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(17, this->driver_activity(), output); + } + + // bool watchdog_fault = 18; + if (this->watchdog_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(18, this->watchdog_fault(), output); + } + + // bool channel_1_fault = 19; + if (this->channel_1_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(19, this->channel_1_fault(), output); + } + + // bool channel_2_fault = 20; + if (this->channel_2_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(20, this->channel_2_fault(), output); + } + + // bool calibration_fault = 21; + if (this->calibration_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(21, this->calibration_fault(), output); + } + + // bool connector_fault = 22; + if (this->connector_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(22, this->connector_fault(), output); + } + + // double timestamp_65 = 23; + if (this->timestamp_65() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(23, this->timestamp_65(), output); + } + + // int32 major_version = 24; + if (this->major_version() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(24, this->major_version(), output); + } + + // int32 minor_version = 25; + if (this->minor_version() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(25, this->minor_version(), output); + } + + // int32 build_number = 26; + if (this->build_number() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(26, this->build_number(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.Eps) +} + +::google::protobuf::uint8* Eps::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.Eps) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_eps_fail = 1; + if (this->is_eps_fail() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_eps_fail(), target); + } + + // .apollo.canbus.Eps.Type eps_control_state = 2; + if (this->eps_control_state() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 2, this->eps_control_state(), target); + } + + // double eps_driver_hand_torq = 3; + if (this->eps_driver_hand_torq() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->eps_driver_hand_torq(), target); + } + + // bool is_steering_angle_valid = 4; + if (this->is_steering_angle_valid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(4, this->is_steering_angle_valid(), target); + } + + // double steering_angle = 5; + if (this->steering_angle() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->steering_angle(), target); + } + + // double steering_angle_spd = 6; + if (this->steering_angle_spd() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->steering_angle_spd(), target); + } + + // bool is_trimming_status = 7; + if (this->is_trimming_status() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(7, this->is_trimming_status(), target); + } + + // bool is_calibration_status = 8; + if (this->is_calibration_status() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(8, this->is_calibration_status(), target); + } + + // bool is_failure_status = 9; + if (this->is_failure_status() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(9, this->is_failure_status(), target); + } + + // int32 allow_enter_autonomous_mode = 10; + if (this->allow_enter_autonomous_mode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(10, this->allow_enter_autonomous_mode(), target); + } + + // int32 current_driving_mode = 11; + if (this->current_driving_mode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(11, this->current_driving_mode(), target); + } + + // double steering_angle_cmd = 12; + if (this->steering_angle_cmd() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(12, this->steering_angle_cmd(), target); + } + + // double vehicle_speed = 13; + if (this->vehicle_speed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(13, this->vehicle_speed(), target); + } + + // double epas_torque = 14; + if (this->epas_torque() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(14, this->epas_torque(), target); + } + + // bool steering_enabled = 15; + if (this->steering_enabled() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(15, this->steering_enabled(), target); + } + + // bool driver_override = 16; + if (this->driver_override() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(16, this->driver_override(), target); + } + + // bool driver_activity = 17; + if (this->driver_activity() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(17, this->driver_activity(), target); + } + + // bool watchdog_fault = 18; + if (this->watchdog_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(18, this->watchdog_fault(), target); + } + + // bool channel_1_fault = 19; + if (this->channel_1_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(19, this->channel_1_fault(), target); + } + + // bool channel_2_fault = 20; + if (this->channel_2_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(20, this->channel_2_fault(), target); + } + + // bool calibration_fault = 21; + if (this->calibration_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(21, this->calibration_fault(), target); + } + + // bool connector_fault = 22; + if (this->connector_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(22, this->connector_fault(), target); + } + + // double timestamp_65 = 23; + if (this->timestamp_65() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(23, this->timestamp_65(), target); + } + + // int32 major_version = 24; + if (this->major_version() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(24, this->major_version(), target); + } + + // int32 minor_version = 25; + if (this->minor_version() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(25, this->minor_version(), target); + } + + // int32 build_number = 26; + if (this->build_number() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(26, this->build_number(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.Eps) + return target; +} + +size_t Eps::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.Eps) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double eps_driver_hand_torq = 3; + if (this->eps_driver_hand_torq() != 0) { + total_size += 1 + 8; + } + + // .apollo.canbus.Eps.Type eps_control_state = 2; + if (this->eps_control_state() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->eps_control_state()); + } + + // bool is_eps_fail = 1; + if (this->is_eps_fail() != 0) { + total_size += 1 + 1; + } + + // bool is_steering_angle_valid = 4; + if (this->is_steering_angle_valid() != 0) { + total_size += 1 + 1; + } + + // bool is_trimming_status = 7; + if (this->is_trimming_status() != 0) { + total_size += 1 + 1; + } + + // bool is_calibration_status = 8; + if (this->is_calibration_status() != 0) { + total_size += 1 + 1; + } + + // double steering_angle = 5; + if (this->steering_angle() != 0) { + total_size += 1 + 8; + } + + // double steering_angle_spd = 6; + if (this->steering_angle_spd() != 0) { + total_size += 1 + 8; + } + + // int32 allow_enter_autonomous_mode = 10; + if (this->allow_enter_autonomous_mode() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->allow_enter_autonomous_mode()); + } + + // int32 current_driving_mode = 11; + if (this->current_driving_mode() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->current_driving_mode()); + } + + // double steering_angle_cmd = 12; + if (this->steering_angle_cmd() != 0) { + total_size += 1 + 8; + } + + // double vehicle_speed = 13; + if (this->vehicle_speed() != 0) { + total_size += 1 + 8; + } + + // double epas_torque = 14; + if (this->epas_torque() != 0) { + total_size += 1 + 8; + } + + // bool is_failure_status = 9; + if (this->is_failure_status() != 0) { + total_size += 1 + 1; + } + + // bool steering_enabled = 15; + if (this->steering_enabled() != 0) { + total_size += 1 + 1; + } + + // bool driver_override = 16; + if (this->driver_override() != 0) { + total_size += 2 + 1; + } + + // bool driver_activity = 17; + if (this->driver_activity() != 0) { + total_size += 2 + 1; + } + + // bool watchdog_fault = 18; + if (this->watchdog_fault() != 0) { + total_size += 2 + 1; + } + + // bool channel_1_fault = 19; + if (this->channel_1_fault() != 0) { + total_size += 2 + 1; + } + + // bool channel_2_fault = 20; + if (this->channel_2_fault() != 0) { + total_size += 2 + 1; + } + + // bool calibration_fault = 21; + if (this->calibration_fault() != 0) { + total_size += 2 + 1; + } + + // double timestamp_65 = 23; + if (this->timestamp_65() != 0) { + total_size += 2 + 8; + } + + // bool connector_fault = 22; + if (this->connector_fault() != 0) { + total_size += 2 + 1; + } + + // int32 major_version = 24; + if (this->major_version() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->major_version()); + } + + // int32 minor_version = 25; + if (this->minor_version() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->minor_version()); + } + + // int32 build_number = 26; + if (this->build_number() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->build_number()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Eps::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.Eps) + GOOGLE_DCHECK_NE(&from, this); + const Eps* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.Eps) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.Eps) + MergeFrom(*source); + } +} + +void Eps::MergeFrom(const Eps& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.Eps) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.eps_driver_hand_torq() != 0) { + set_eps_driver_hand_torq(from.eps_driver_hand_torq()); + } + if (from.eps_control_state() != 0) { + set_eps_control_state(from.eps_control_state()); + } + if (from.is_eps_fail() != 0) { + set_is_eps_fail(from.is_eps_fail()); + } + if (from.is_steering_angle_valid() != 0) { + set_is_steering_angle_valid(from.is_steering_angle_valid()); + } + if (from.is_trimming_status() != 0) { + set_is_trimming_status(from.is_trimming_status()); + } + if (from.is_calibration_status() != 0) { + set_is_calibration_status(from.is_calibration_status()); + } + if (from.steering_angle() != 0) { + set_steering_angle(from.steering_angle()); + } + if (from.steering_angle_spd() != 0) { + set_steering_angle_spd(from.steering_angle_spd()); + } + if (from.allow_enter_autonomous_mode() != 0) { + set_allow_enter_autonomous_mode(from.allow_enter_autonomous_mode()); + } + if (from.current_driving_mode() != 0) { + set_current_driving_mode(from.current_driving_mode()); + } + if (from.steering_angle_cmd() != 0) { + set_steering_angle_cmd(from.steering_angle_cmd()); + } + if (from.vehicle_speed() != 0) { + set_vehicle_speed(from.vehicle_speed()); + } + if (from.epas_torque() != 0) { + set_epas_torque(from.epas_torque()); + } + if (from.is_failure_status() != 0) { + set_is_failure_status(from.is_failure_status()); + } + if (from.steering_enabled() != 0) { + set_steering_enabled(from.steering_enabled()); + } + if (from.driver_override() != 0) { + set_driver_override(from.driver_override()); + } + if (from.driver_activity() != 0) { + set_driver_activity(from.driver_activity()); + } + if (from.watchdog_fault() != 0) { + set_watchdog_fault(from.watchdog_fault()); + } + if (from.channel_1_fault() != 0) { + set_channel_1_fault(from.channel_1_fault()); + } + if (from.channel_2_fault() != 0) { + set_channel_2_fault(from.channel_2_fault()); + } + if (from.calibration_fault() != 0) { + set_calibration_fault(from.calibration_fault()); + } + if (from.timestamp_65() != 0) { + set_timestamp_65(from.timestamp_65()); + } + if (from.connector_fault() != 0) { + set_connector_fault(from.connector_fault()); + } + if (from.major_version() != 0) { + set_major_version(from.major_version()); + } + if (from.minor_version() != 0) { + set_minor_version(from.minor_version()); + } + if (from.build_number() != 0) { + set_build_number(from.build_number()); + } +} + +void Eps::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.Eps) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Eps::CopyFrom(const Eps& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.Eps) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Eps::IsInitialized() const { + return true; +} + +void Eps::Swap(Eps* other) { + if (other == this) return; + InternalSwap(other); +} +void Eps::InternalSwap(Eps* other) { + using std::swap; + swap(eps_driver_hand_torq_, other->eps_driver_hand_torq_); + swap(eps_control_state_, other->eps_control_state_); + swap(is_eps_fail_, other->is_eps_fail_); + swap(is_steering_angle_valid_, other->is_steering_angle_valid_); + swap(is_trimming_status_, other->is_trimming_status_); + swap(is_calibration_status_, other->is_calibration_status_); + swap(steering_angle_, other->steering_angle_); + swap(steering_angle_spd_, other->steering_angle_spd_); + swap(allow_enter_autonomous_mode_, other->allow_enter_autonomous_mode_); + swap(current_driving_mode_, other->current_driving_mode_); + swap(steering_angle_cmd_, other->steering_angle_cmd_); + swap(vehicle_speed_, other->vehicle_speed_); + swap(epas_torque_, other->epas_torque_); + swap(is_failure_status_, other->is_failure_status_); + swap(steering_enabled_, other->steering_enabled_); + swap(driver_override_, other->driver_override_); + swap(driver_activity_, other->driver_activity_); + swap(watchdog_fault_, other->watchdog_fault_); + swap(channel_1_fault_, other->channel_1_fault_); + swap(channel_2_fault_, other->channel_2_fault_); + swap(calibration_fault_, other->calibration_fault_); + swap(timestamp_65_, other->timestamp_65_); + swap(connector_fault_, other->connector_fault_); + swap(major_version_, other->major_version_); + swap(minor_version_, other->minor_version_); + swap(build_number_, other->build_number_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Eps::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void VehicleSpd::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int VehicleSpd::kIsVehicleStandstillFieldNumber; +const int VehicleSpd::kIsVehicleSpdValidFieldNumber; +const int VehicleSpd::kVehicleSpdFieldNumber; +const int VehicleSpd::kIsWheelSpdRrValidFieldNumber; +const int VehicleSpd::kWheelDirectionRrFieldNumber; +const int VehicleSpd::kWheelSpdRrFieldNumber; +const int VehicleSpd::kIsWheelSpdRlValidFieldNumber; +const int VehicleSpd::kWheelDirectionRlFieldNumber; +const int VehicleSpd::kWheelSpdRlFieldNumber; +const int VehicleSpd::kIsWheelSpdFrValidFieldNumber; +const int VehicleSpd::kWheelDirectionFrFieldNumber; +const int VehicleSpd::kWheelSpdFrFieldNumber; +const int VehicleSpd::kIsWheelSpdFlValidFieldNumber; +const int VehicleSpd::kWheelDirectionFlFieldNumber; +const int VehicleSpd::kWheelSpdFlFieldNumber; +const int VehicleSpd::kIsYawRateValidFieldNumber; +const int VehicleSpd::kYawRateFieldNumber; +const int VehicleSpd::kYawRateOffsetFieldNumber; +const int VehicleSpd::kIsAxValidFieldNumber; +const int VehicleSpd::kAxFieldNumber; +const int VehicleSpd::kAxOffsetFieldNumber; +const int VehicleSpd::kIsAyValidFieldNumber; +const int VehicleSpd::kAyFieldNumber; +const int VehicleSpd::kAyOffsetFieldNumber; +const int VehicleSpd::kLatAccFieldNumber; +const int VehicleSpd::kLongAccFieldNumber; +const int VehicleSpd::kVertAccFieldNumber; +const int VehicleSpd::kRollRateFieldNumber; +const int VehicleSpd::kAccEstFieldNumber; +const int VehicleSpd::kTimestampSecFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +VehicleSpd::VehicleSpd() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_VehicleSpd.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.VehicleSpd) +} +VehicleSpd::VehicleSpd(const VehicleSpd& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&vehicle_spd_, &from.vehicle_spd_, + static_cast(reinterpret_cast(&is_ay_valid_) - + reinterpret_cast(&vehicle_spd_)) + sizeof(is_ay_valid_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.VehicleSpd) +} + +void VehicleSpd::SharedCtor() { + ::memset(&vehicle_spd_, 0, static_cast( + reinterpret_cast(&is_ay_valid_) - + reinterpret_cast(&vehicle_spd_)) + sizeof(is_ay_valid_)); +} + +VehicleSpd::~VehicleSpd() { + // @@protoc_insertion_point(destructor:apollo.canbus.VehicleSpd) + SharedDtor(); +} + +void VehicleSpd::SharedDtor() { +} + +void VehicleSpd::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* VehicleSpd::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const VehicleSpd& VehicleSpd::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_VehicleSpd.base); + return *internal_default_instance(); +} + + +void VehicleSpd::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.VehicleSpd) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&vehicle_spd_, 0, static_cast( + reinterpret_cast(&is_ay_valid_) - + reinterpret_cast(&vehicle_spd_)) + sizeof(is_ay_valid_)); + _internal_metadata_.Clear(); +} + +bool VehicleSpd::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.VehicleSpd) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_vehicle_standstill = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_vehicle_standstill_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_vehicle_spd_valid = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_vehicle_spd_valid_))); + } else { + goto handle_unusual; + } + break; + } + + // double vehicle_spd = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &vehicle_spd_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_wheel_spd_rr_valid = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_wheel_spd_rr_valid_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_rr = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(40u /* 40 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_wheel_direction_rr(static_cast< ::apollo::canbus::VehicleSpd_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // double wheel_spd_rr = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &wheel_spd_rr_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_wheel_spd_rl_valid = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(56u /* 56 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_wheel_spd_rl_valid_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_rl = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(64u /* 64 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_wheel_direction_rl(static_cast< ::apollo::canbus::VehicleSpd_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // double wheel_spd_rl = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(73u /* 73 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &wheel_spd_rl_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_wheel_spd_fr_valid = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(80u /* 80 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_wheel_spd_fr_valid_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_fr = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(88u /* 88 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_wheel_direction_fr(static_cast< ::apollo::canbus::VehicleSpd_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // double wheel_spd_fr = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(97u /* 97 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &wheel_spd_fr_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_wheel_spd_fl_valid = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(104u /* 104 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_wheel_spd_fl_valid_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_fl = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(112u /* 112 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_wheel_direction_fl(static_cast< ::apollo::canbus::VehicleSpd_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // double wheel_spd_fl = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(121u /* 121 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &wheel_spd_fl_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_yaw_rate_valid = 16; + case 16: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(128u /* 128 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_yaw_rate_valid_))); + } else { + goto handle_unusual; + } + break; + } + + // double yaw_rate = 17; + case 17: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(137u /* 137 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &yaw_rate_))); + } else { + goto handle_unusual; + } + break; + } + + // double yaw_rate_offset = 18; + case 18: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(145u /* 145 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &yaw_rate_offset_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_ax_valid = 19; + case 19: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(152u /* 152 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_ax_valid_))); + } else { + goto handle_unusual; + } + break; + } + + // double ax = 20; + case 20: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(161u /* 161 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &ax_))); + } else { + goto handle_unusual; + } + break; + } + + // double ax_offset = 21; + case 21: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(169u /* 169 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &ax_offset_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_ay_valid = 22; + case 22: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(176u /* 176 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_ay_valid_))); + } else { + goto handle_unusual; + } + break; + } + + // double ay = 23; + case 23: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(185u /* 185 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &ay_))); + } else { + goto handle_unusual; + } + break; + } + + // double ay_offset = 24; + case 24: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(193u /* 193 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &ay_offset_))); + } else { + goto handle_unusual; + } + break; + } + + // double lat_acc = 25; + case 25: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(201u /* 201 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lat_acc_))); + } else { + goto handle_unusual; + } + break; + } + + // double long_acc = 26; + case 26: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(209u /* 209 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &long_acc_))); + } else { + goto handle_unusual; + } + break; + } + + // double vert_acc = 27; + case 27: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(217u /* 217 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &vert_acc_))); + } else { + goto handle_unusual; + } + break; + } + + // double roll_rate = 28; + case 28: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(225u /* 225 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &roll_rate_))); + } else { + goto handle_unusual; + } + break; + } + + // double acc_est = 29; + case 29: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(233u /* 233 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &acc_est_))); + } else { + goto handle_unusual; + } + break; + } + + // double timestamp_sec = 30; + case 30: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(241u /* 241 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, ×tamp_sec_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.VehicleSpd) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.VehicleSpd) + return false; +#undef DO_ +} + +void VehicleSpd::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.VehicleSpd) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_vehicle_standstill = 1; + if (this->is_vehicle_standstill() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_vehicle_standstill(), output); + } + + // bool is_vehicle_spd_valid = 2; + if (this->is_vehicle_spd_valid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_vehicle_spd_valid(), output); + } + + // double vehicle_spd = 3; + if (this->vehicle_spd() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->vehicle_spd(), output); + } + + // bool is_wheel_spd_rr_valid = 4; + if (this->is_wheel_spd_rr_valid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(4, this->is_wheel_spd_rr_valid(), output); + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_rr = 5; + if (this->wheel_direction_rr() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 5, this->wheel_direction_rr(), output); + } + + // double wheel_spd_rr = 6; + if (this->wheel_spd_rr() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->wheel_spd_rr(), output); + } + + // bool is_wheel_spd_rl_valid = 7; + if (this->is_wheel_spd_rl_valid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(7, this->is_wheel_spd_rl_valid(), output); + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_rl = 8; + if (this->wheel_direction_rl() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 8, this->wheel_direction_rl(), output); + } + + // double wheel_spd_rl = 9; + if (this->wheel_spd_rl() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->wheel_spd_rl(), output); + } + + // bool is_wheel_spd_fr_valid = 10; + if (this->is_wheel_spd_fr_valid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(10, this->is_wheel_spd_fr_valid(), output); + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_fr = 11; + if (this->wheel_direction_fr() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 11, this->wheel_direction_fr(), output); + } + + // double wheel_spd_fr = 12; + if (this->wheel_spd_fr() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(12, this->wheel_spd_fr(), output); + } + + // bool is_wheel_spd_fl_valid = 13; + if (this->is_wheel_spd_fl_valid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(13, this->is_wheel_spd_fl_valid(), output); + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_fl = 14; + if (this->wheel_direction_fl() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 14, this->wheel_direction_fl(), output); + } + + // double wheel_spd_fl = 15; + if (this->wheel_spd_fl() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(15, this->wheel_spd_fl(), output); + } + + // bool is_yaw_rate_valid = 16; + if (this->is_yaw_rate_valid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(16, this->is_yaw_rate_valid(), output); + } + + // double yaw_rate = 17; + if (this->yaw_rate() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(17, this->yaw_rate(), output); + } + + // double yaw_rate_offset = 18; + if (this->yaw_rate_offset() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(18, this->yaw_rate_offset(), output); + } + + // bool is_ax_valid = 19; + if (this->is_ax_valid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(19, this->is_ax_valid(), output); + } + + // double ax = 20; + if (this->ax() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(20, this->ax(), output); + } + + // double ax_offset = 21; + if (this->ax_offset() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(21, this->ax_offset(), output); + } + + // bool is_ay_valid = 22; + if (this->is_ay_valid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(22, this->is_ay_valid(), output); + } + + // double ay = 23; + if (this->ay() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(23, this->ay(), output); + } + + // double ay_offset = 24; + if (this->ay_offset() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(24, this->ay_offset(), output); + } + + // double lat_acc = 25; + if (this->lat_acc() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(25, this->lat_acc(), output); + } + + // double long_acc = 26; + if (this->long_acc() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(26, this->long_acc(), output); + } + + // double vert_acc = 27; + if (this->vert_acc() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(27, this->vert_acc(), output); + } + + // double roll_rate = 28; + if (this->roll_rate() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(28, this->roll_rate(), output); + } + + // double acc_est = 29; + if (this->acc_est() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(29, this->acc_est(), output); + } + + // double timestamp_sec = 30; + if (this->timestamp_sec() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(30, this->timestamp_sec(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.VehicleSpd) +} + +::google::protobuf::uint8* VehicleSpd::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.VehicleSpd) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_vehicle_standstill = 1; + if (this->is_vehicle_standstill() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_vehicle_standstill(), target); + } + + // bool is_vehicle_spd_valid = 2; + if (this->is_vehicle_spd_valid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_vehicle_spd_valid(), target); + } + + // double vehicle_spd = 3; + if (this->vehicle_spd() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->vehicle_spd(), target); + } + + // bool is_wheel_spd_rr_valid = 4; + if (this->is_wheel_spd_rr_valid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(4, this->is_wheel_spd_rr_valid(), target); + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_rr = 5; + if (this->wheel_direction_rr() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 5, this->wheel_direction_rr(), target); + } + + // double wheel_spd_rr = 6; + if (this->wheel_spd_rr() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->wheel_spd_rr(), target); + } + + // bool is_wheel_spd_rl_valid = 7; + if (this->is_wheel_spd_rl_valid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(7, this->is_wheel_spd_rl_valid(), target); + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_rl = 8; + if (this->wheel_direction_rl() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 8, this->wheel_direction_rl(), target); + } + + // double wheel_spd_rl = 9; + if (this->wheel_spd_rl() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->wheel_spd_rl(), target); + } + + // bool is_wheel_spd_fr_valid = 10; + if (this->is_wheel_spd_fr_valid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(10, this->is_wheel_spd_fr_valid(), target); + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_fr = 11; + if (this->wheel_direction_fr() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 11, this->wheel_direction_fr(), target); + } + + // double wheel_spd_fr = 12; + if (this->wheel_spd_fr() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(12, this->wheel_spd_fr(), target); + } + + // bool is_wheel_spd_fl_valid = 13; + if (this->is_wheel_spd_fl_valid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(13, this->is_wheel_spd_fl_valid(), target); + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_fl = 14; + if (this->wheel_direction_fl() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 14, this->wheel_direction_fl(), target); + } + + // double wheel_spd_fl = 15; + if (this->wheel_spd_fl() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(15, this->wheel_spd_fl(), target); + } + + // bool is_yaw_rate_valid = 16; + if (this->is_yaw_rate_valid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(16, this->is_yaw_rate_valid(), target); + } + + // double yaw_rate = 17; + if (this->yaw_rate() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(17, this->yaw_rate(), target); + } + + // double yaw_rate_offset = 18; + if (this->yaw_rate_offset() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(18, this->yaw_rate_offset(), target); + } + + // bool is_ax_valid = 19; + if (this->is_ax_valid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(19, this->is_ax_valid(), target); + } + + // double ax = 20; + if (this->ax() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(20, this->ax(), target); + } + + // double ax_offset = 21; + if (this->ax_offset() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(21, this->ax_offset(), target); + } + + // bool is_ay_valid = 22; + if (this->is_ay_valid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(22, this->is_ay_valid(), target); + } + + // double ay = 23; + if (this->ay() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(23, this->ay(), target); + } + + // double ay_offset = 24; + if (this->ay_offset() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(24, this->ay_offset(), target); + } + + // double lat_acc = 25; + if (this->lat_acc() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(25, this->lat_acc(), target); + } + + // double long_acc = 26; + if (this->long_acc() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(26, this->long_acc(), target); + } + + // double vert_acc = 27; + if (this->vert_acc() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(27, this->vert_acc(), target); + } + + // double roll_rate = 28; + if (this->roll_rate() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(28, this->roll_rate(), target); + } + + // double acc_est = 29; + if (this->acc_est() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(29, this->acc_est(), target); + } + + // double timestamp_sec = 30; + if (this->timestamp_sec() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(30, this->timestamp_sec(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.VehicleSpd) + return target; +} + +size_t VehicleSpd::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.VehicleSpd) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double vehicle_spd = 3; + if (this->vehicle_spd() != 0) { + total_size += 1 + 8; + } + + // bool is_vehicle_standstill = 1; + if (this->is_vehicle_standstill() != 0) { + total_size += 1 + 1; + } + + // bool is_vehicle_spd_valid = 2; + if (this->is_vehicle_spd_valid() != 0) { + total_size += 1 + 1; + } + + // bool is_wheel_spd_rr_valid = 4; + if (this->is_wheel_spd_rr_valid() != 0) { + total_size += 1 + 1; + } + + // bool is_wheel_spd_rl_valid = 7; + if (this->is_wheel_spd_rl_valid() != 0) { + total_size += 1 + 1; + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_rr = 5; + if (this->wheel_direction_rr() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->wheel_direction_rr()); + } + + // double wheel_spd_rr = 6; + if (this->wheel_spd_rr() != 0) { + total_size += 1 + 8; + } + + // double wheel_spd_rl = 9; + if (this->wheel_spd_rl() != 0) { + total_size += 1 + 8; + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_rl = 8; + if (this->wheel_direction_rl() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->wheel_direction_rl()); + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_fr = 11; + if (this->wheel_direction_fr() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->wheel_direction_fr()); + } + + // double wheel_spd_fr = 12; + if (this->wheel_spd_fr() != 0) { + total_size += 1 + 8; + } + + // .apollo.canbus.VehicleSpd.Type wheel_direction_fl = 14; + if (this->wheel_direction_fl() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->wheel_direction_fl()); + } + + // bool is_wheel_spd_fr_valid = 10; + if (this->is_wheel_spd_fr_valid() != 0) { + total_size += 1 + 1; + } + + // bool is_wheel_spd_fl_valid = 13; + if (this->is_wheel_spd_fl_valid() != 0) { + total_size += 1 + 1; + } + + // bool is_yaw_rate_valid = 16; + if (this->is_yaw_rate_valid() != 0) { + total_size += 2 + 1; + } + + // bool is_ax_valid = 19; + if (this->is_ax_valid() != 0) { + total_size += 2 + 1; + } + + // double wheel_spd_fl = 15; + if (this->wheel_spd_fl() != 0) { + total_size += 1 + 8; + } + + // double yaw_rate = 17; + if (this->yaw_rate() != 0) { + total_size += 2 + 8; + } + + // double yaw_rate_offset = 18; + if (this->yaw_rate_offset() != 0) { + total_size += 2 + 8; + } + + // double ax = 20; + if (this->ax() != 0) { + total_size += 2 + 8; + } + + // double ax_offset = 21; + if (this->ax_offset() != 0) { + total_size += 2 + 8; + } + + // double ay = 23; + if (this->ay() != 0) { + total_size += 2 + 8; + } + + // double ay_offset = 24; + if (this->ay_offset() != 0) { + total_size += 2 + 8; + } + + // double lat_acc = 25; + if (this->lat_acc() != 0) { + total_size += 2 + 8; + } + + // double long_acc = 26; + if (this->long_acc() != 0) { + total_size += 2 + 8; + } + + // double vert_acc = 27; + if (this->vert_acc() != 0) { + total_size += 2 + 8; + } + + // double roll_rate = 28; + if (this->roll_rate() != 0) { + total_size += 2 + 8; + } + + // double acc_est = 29; + if (this->acc_est() != 0) { + total_size += 2 + 8; + } + + // double timestamp_sec = 30; + if (this->timestamp_sec() != 0) { + total_size += 2 + 8; + } + + // bool is_ay_valid = 22; + if (this->is_ay_valid() != 0) { + total_size += 2 + 1; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void VehicleSpd::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.VehicleSpd) + GOOGLE_DCHECK_NE(&from, this); + const VehicleSpd* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.VehicleSpd) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.VehicleSpd) + MergeFrom(*source); + } +} + +void VehicleSpd::MergeFrom(const VehicleSpd& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.VehicleSpd) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.vehicle_spd() != 0) { + set_vehicle_spd(from.vehicle_spd()); + } + if (from.is_vehicle_standstill() != 0) { + set_is_vehicle_standstill(from.is_vehicle_standstill()); + } + if (from.is_vehicle_spd_valid() != 0) { + set_is_vehicle_spd_valid(from.is_vehicle_spd_valid()); + } + if (from.is_wheel_spd_rr_valid() != 0) { + set_is_wheel_spd_rr_valid(from.is_wheel_spd_rr_valid()); + } + if (from.is_wheel_spd_rl_valid() != 0) { + set_is_wheel_spd_rl_valid(from.is_wheel_spd_rl_valid()); + } + if (from.wheel_direction_rr() != 0) { + set_wheel_direction_rr(from.wheel_direction_rr()); + } + if (from.wheel_spd_rr() != 0) { + set_wheel_spd_rr(from.wheel_spd_rr()); + } + if (from.wheel_spd_rl() != 0) { + set_wheel_spd_rl(from.wheel_spd_rl()); + } + if (from.wheel_direction_rl() != 0) { + set_wheel_direction_rl(from.wheel_direction_rl()); + } + if (from.wheel_direction_fr() != 0) { + set_wheel_direction_fr(from.wheel_direction_fr()); + } + if (from.wheel_spd_fr() != 0) { + set_wheel_spd_fr(from.wheel_spd_fr()); + } + if (from.wheel_direction_fl() != 0) { + set_wheel_direction_fl(from.wheel_direction_fl()); + } + if (from.is_wheel_spd_fr_valid() != 0) { + set_is_wheel_spd_fr_valid(from.is_wheel_spd_fr_valid()); + } + if (from.is_wheel_spd_fl_valid() != 0) { + set_is_wheel_spd_fl_valid(from.is_wheel_spd_fl_valid()); + } + if (from.is_yaw_rate_valid() != 0) { + set_is_yaw_rate_valid(from.is_yaw_rate_valid()); + } + if (from.is_ax_valid() != 0) { + set_is_ax_valid(from.is_ax_valid()); + } + if (from.wheel_spd_fl() != 0) { + set_wheel_spd_fl(from.wheel_spd_fl()); + } + if (from.yaw_rate() != 0) { + set_yaw_rate(from.yaw_rate()); + } + if (from.yaw_rate_offset() != 0) { + set_yaw_rate_offset(from.yaw_rate_offset()); + } + if (from.ax() != 0) { + set_ax(from.ax()); + } + if (from.ax_offset() != 0) { + set_ax_offset(from.ax_offset()); + } + if (from.ay() != 0) { + set_ay(from.ay()); + } + if (from.ay_offset() != 0) { + set_ay_offset(from.ay_offset()); + } + if (from.lat_acc() != 0) { + set_lat_acc(from.lat_acc()); + } + if (from.long_acc() != 0) { + set_long_acc(from.long_acc()); + } + if (from.vert_acc() != 0) { + set_vert_acc(from.vert_acc()); + } + if (from.roll_rate() != 0) { + set_roll_rate(from.roll_rate()); + } + if (from.acc_est() != 0) { + set_acc_est(from.acc_est()); + } + if (from.timestamp_sec() != 0) { + set_timestamp_sec(from.timestamp_sec()); + } + if (from.is_ay_valid() != 0) { + set_is_ay_valid(from.is_ay_valid()); + } +} + +void VehicleSpd::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.VehicleSpd) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void VehicleSpd::CopyFrom(const VehicleSpd& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.VehicleSpd) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool VehicleSpd::IsInitialized() const { + return true; +} + +void VehicleSpd::Swap(VehicleSpd* other) { + if (other == this) return; + InternalSwap(other); +} +void VehicleSpd::InternalSwap(VehicleSpd* other) { + using std::swap; + swap(vehicle_spd_, other->vehicle_spd_); + swap(is_vehicle_standstill_, other->is_vehicle_standstill_); + swap(is_vehicle_spd_valid_, other->is_vehicle_spd_valid_); + swap(is_wheel_spd_rr_valid_, other->is_wheel_spd_rr_valid_); + swap(is_wheel_spd_rl_valid_, other->is_wheel_spd_rl_valid_); + swap(wheel_direction_rr_, other->wheel_direction_rr_); + swap(wheel_spd_rr_, other->wheel_spd_rr_); + swap(wheel_spd_rl_, other->wheel_spd_rl_); + swap(wheel_direction_rl_, other->wheel_direction_rl_); + swap(wheel_direction_fr_, other->wheel_direction_fr_); + swap(wheel_spd_fr_, other->wheel_spd_fr_); + swap(wheel_direction_fl_, other->wheel_direction_fl_); + swap(is_wheel_spd_fr_valid_, other->is_wheel_spd_fr_valid_); + swap(is_wheel_spd_fl_valid_, other->is_wheel_spd_fl_valid_); + swap(is_yaw_rate_valid_, other->is_yaw_rate_valid_); + swap(is_ax_valid_, other->is_ax_valid_); + swap(wheel_spd_fl_, other->wheel_spd_fl_); + swap(yaw_rate_, other->yaw_rate_); + swap(yaw_rate_offset_, other->yaw_rate_offset_); + swap(ax_, other->ax_); + swap(ax_offset_, other->ax_offset_); + swap(ay_, other->ay_); + swap(ay_offset_, other->ay_offset_); + swap(lat_acc_, other->lat_acc_); + swap(long_acc_, other->long_acc_); + swap(vert_acc_, other->vert_acc_); + swap(roll_rate_, other->roll_rate_); + swap(acc_est_, other->acc_est_); + swap(timestamp_sec_, other->timestamp_sec_); + swap(is_ay_valid_, other->is_ay_valid_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata VehicleSpd::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Deceleration::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Deceleration::kIsDecelerationAvailableFieldNumber; +const int Deceleration::kIsDecelerationActiveFieldNumber; +const int Deceleration::kDecelerationFieldNumber; +const int Deceleration::kIsEvbFailFieldNumber; +const int Deceleration::kEvbPressureFieldNumber; +const int Deceleration::kBrakePressureFieldNumber; +const int Deceleration::kBrakePressureSpdFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Deceleration::Deceleration() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Deceleration.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.Deceleration) +} +Deceleration::Deceleration(const Deceleration& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&deceleration_, &from.deceleration_, + static_cast(reinterpret_cast(&is_deceleration_active_) - + reinterpret_cast(&deceleration_)) + sizeof(is_deceleration_active_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.Deceleration) +} + +void Deceleration::SharedCtor() { + ::memset(&deceleration_, 0, static_cast( + reinterpret_cast(&is_deceleration_active_) - + reinterpret_cast(&deceleration_)) + sizeof(is_deceleration_active_)); +} + +Deceleration::~Deceleration() { + // @@protoc_insertion_point(destructor:apollo.canbus.Deceleration) + SharedDtor(); +} + +void Deceleration::SharedDtor() { +} + +void Deceleration::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Deceleration::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Deceleration& Deceleration::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Deceleration.base); + return *internal_default_instance(); +} + + +void Deceleration::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.Deceleration) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&deceleration_, 0, static_cast( + reinterpret_cast(&is_deceleration_active_) - + reinterpret_cast(&deceleration_)) + sizeof(is_deceleration_active_)); + _internal_metadata_.Clear(); +} + +bool Deceleration::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.Deceleration) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_deceleration_available = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_deceleration_available_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_deceleration_active = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_deceleration_active_))); + } else { + goto handle_unusual; + } + break; + } + + // double deceleration = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &deceleration_))); + } else { + goto handle_unusual; + } + break; + } + + // double is_evb_fail = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &is_evb_fail_))); + } else { + goto handle_unusual; + } + break; + } + + // double evb_pressure = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &evb_pressure_))); + } else { + goto handle_unusual; + } + break; + } + + // double brake_pressure = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &brake_pressure_))); + } else { + goto handle_unusual; + } + break; + } + + // double brake_pressure_spd = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &brake_pressure_spd_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.Deceleration) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.Deceleration) + return false; +#undef DO_ +} + +void Deceleration::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.Deceleration) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_deceleration_available = 1; + if (this->is_deceleration_available() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_deceleration_available(), output); + } + + // bool is_deceleration_active = 2; + if (this->is_deceleration_active() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_deceleration_active(), output); + } + + // double deceleration = 3; + if (this->deceleration() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->deceleration(), output); + } + + // double is_evb_fail = 4; + if (this->is_evb_fail() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->is_evb_fail(), output); + } + + // double evb_pressure = 5; + if (this->evb_pressure() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->evb_pressure(), output); + } + + // double brake_pressure = 6; + if (this->brake_pressure() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->brake_pressure(), output); + } + + // double brake_pressure_spd = 7; + if (this->brake_pressure_spd() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->brake_pressure_spd(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.Deceleration) +} + +::google::protobuf::uint8* Deceleration::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.Deceleration) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_deceleration_available = 1; + if (this->is_deceleration_available() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_deceleration_available(), target); + } + + // bool is_deceleration_active = 2; + if (this->is_deceleration_active() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_deceleration_active(), target); + } + + // double deceleration = 3; + if (this->deceleration() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->deceleration(), target); + } + + // double is_evb_fail = 4; + if (this->is_evb_fail() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->is_evb_fail(), target); + } + + // double evb_pressure = 5; + if (this->evb_pressure() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->evb_pressure(), target); + } + + // double brake_pressure = 6; + if (this->brake_pressure() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->brake_pressure(), target); + } + + // double brake_pressure_spd = 7; + if (this->brake_pressure_spd() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->brake_pressure_spd(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.Deceleration) + return target; +} + +size_t Deceleration::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.Deceleration) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double deceleration = 3; + if (this->deceleration() != 0) { + total_size += 1 + 8; + } + + // double is_evb_fail = 4; + if (this->is_evb_fail() != 0) { + total_size += 1 + 8; + } + + // double evb_pressure = 5; + if (this->evb_pressure() != 0) { + total_size += 1 + 8; + } + + // double brake_pressure = 6; + if (this->brake_pressure() != 0) { + total_size += 1 + 8; + } + + // double brake_pressure_spd = 7; + if (this->brake_pressure_spd() != 0) { + total_size += 1 + 8; + } + + // bool is_deceleration_available = 1; + if (this->is_deceleration_available() != 0) { + total_size += 1 + 1; + } + + // bool is_deceleration_active = 2; + if (this->is_deceleration_active() != 0) { + total_size += 1 + 1; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Deceleration::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.Deceleration) + GOOGLE_DCHECK_NE(&from, this); + const Deceleration* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.Deceleration) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.Deceleration) + MergeFrom(*source); + } +} + +void Deceleration::MergeFrom(const Deceleration& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.Deceleration) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.deceleration() != 0) { + set_deceleration(from.deceleration()); + } + if (from.is_evb_fail() != 0) { + set_is_evb_fail(from.is_evb_fail()); + } + if (from.evb_pressure() != 0) { + set_evb_pressure(from.evb_pressure()); + } + if (from.brake_pressure() != 0) { + set_brake_pressure(from.brake_pressure()); + } + if (from.brake_pressure_spd() != 0) { + set_brake_pressure_spd(from.brake_pressure_spd()); + } + if (from.is_deceleration_available() != 0) { + set_is_deceleration_available(from.is_deceleration_available()); + } + if (from.is_deceleration_active() != 0) { + set_is_deceleration_active(from.is_deceleration_active()); + } +} + +void Deceleration::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.Deceleration) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Deceleration::CopyFrom(const Deceleration& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.Deceleration) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Deceleration::IsInitialized() const { + return true; +} + +void Deceleration::Swap(Deceleration* other) { + if (other == this) return; + InternalSwap(other); +} +void Deceleration::InternalSwap(Deceleration* other) { + using std::swap; + swap(deceleration_, other->deceleration_); + swap(is_evb_fail_, other->is_evb_fail_); + swap(evb_pressure_, other->evb_pressure_); + swap(brake_pressure_, other->brake_pressure_); + swap(brake_pressure_spd_, other->brake_pressure_spd_); + swap(is_deceleration_available_, other->is_deceleration_available_); + swap(is_deceleration_active_, other->is_deceleration_active_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Deceleration::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Brake::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Brake::kIsBrakePedalPressedFieldNumber; +const int Brake::kIsBrakeForceExistFieldNumber; +const int Brake::kIsBrakeOverHeatFieldNumber; +const int Brake::kIsHandBrakeOnFieldNumber; +const int Brake::kBrakePedalPositionFieldNumber; +const int Brake::kIsBrakeValidFieldNumber; +const int Brake::kBrakeInputFieldNumber; +const int Brake::kBrakeCmdFieldNumber; +const int Brake::kBrakeOutputFieldNumber; +const int Brake::kBooInputFieldNumber; +const int Brake::kBooCmdFieldNumber; +const int Brake::kBooOutputFieldNumber; +const int Brake::kWatchdogApplyingBrakesFieldNumber; +const int Brake::kWatchdogSourceFieldNumber; +const int Brake::kBrakeEnabledFieldNumber; +const int Brake::kDriverOverrideFieldNumber; +const int Brake::kDriverActivityFieldNumber; +const int Brake::kWatchdogFaultFieldNumber; +const int Brake::kChannel1FaultFieldNumber; +const int Brake::kChannel2FaultFieldNumber; +const int Brake::kBooFaultFieldNumber; +const int Brake::kConnectorFaultFieldNumber; +const int Brake::kBrakeTorqueReqFieldNumber; +const int Brake::kHsaStatusFieldNumber; +const int Brake::kBrakeTorqueActFieldNumber; +const int Brake::kHsaModeFieldNumber; +const int Brake::kWheelTorqueActFieldNumber; +const int Brake::kMajorVersionFieldNumber; +const int Brake::kMinorVersionFieldNumber; +const int Brake::kBuildNumberFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Brake::Brake() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Brake.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.Brake) +} +Brake::Brake(const Brake& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&brake_pedal_position_, &from.brake_pedal_position_, + static_cast(reinterpret_cast(&build_number_) - + reinterpret_cast(&brake_pedal_position_)) + sizeof(build_number_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.Brake) +} + +void Brake::SharedCtor() { + ::memset(&brake_pedal_position_, 0, static_cast( + reinterpret_cast(&build_number_) - + reinterpret_cast(&brake_pedal_position_)) + sizeof(build_number_)); +} + +Brake::~Brake() { + // @@protoc_insertion_point(destructor:apollo.canbus.Brake) + SharedDtor(); +} + +void Brake::SharedDtor() { +} + +void Brake::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Brake::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Brake& Brake::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Brake.base); + return *internal_default_instance(); +} + + +void Brake::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.Brake) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&brake_pedal_position_, 0, static_cast( + reinterpret_cast(&build_number_) - + reinterpret_cast(&brake_pedal_position_)) + sizeof(build_number_)); + _internal_metadata_.Clear(); +} + +bool Brake::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.Brake) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_brake_pedal_pressed = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_brake_pedal_pressed_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_brake_force_exist = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_brake_force_exist_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_brake_over_heat = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_brake_over_heat_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_hand_brake_on = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_hand_brake_on_))); + } else { + goto handle_unusual; + } + break; + } + + // double brake_pedal_position = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &brake_pedal_position_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_brake_valid = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(48u /* 48 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_brake_valid_))); + } else { + goto handle_unusual; + } + break; + } + + // double brake_input = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &brake_input_))); + } else { + goto handle_unusual; + } + break; + } + + // double brake_cmd = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(65u /* 65 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &brake_cmd_))); + } else { + goto handle_unusual; + } + break; + } + + // double brake_output = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(73u /* 73 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &brake_output_))); + } else { + goto handle_unusual; + } + break; + } + + // bool boo_input = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(80u /* 80 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &boo_input_))); + } else { + goto handle_unusual; + } + break; + } + + // bool boo_cmd = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(88u /* 88 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &boo_cmd_))); + } else { + goto handle_unusual; + } + break; + } + + // bool boo_output = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(96u /* 96 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &boo_output_))); + } else { + goto handle_unusual; + } + break; + } + + // bool watchdog_applying_brakes = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(104u /* 104 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &watchdog_applying_brakes_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 watchdog_source = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(112u /* 112 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &watchdog_source_))); + } else { + goto handle_unusual; + } + break; + } + + // bool brake_enabled = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(120u /* 120 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &brake_enabled_))); + } else { + goto handle_unusual; + } + break; + } + + // bool driver_override = 16; + case 16: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(128u /* 128 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &driver_override_))); + } else { + goto handle_unusual; + } + break; + } + + // bool driver_activity = 17; + case 17: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(136u /* 136 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &driver_activity_))); + } else { + goto handle_unusual; + } + break; + } + + // bool watchdog_fault = 18; + case 18: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(144u /* 144 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &watchdog_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool channel_1_fault = 19; + case 19: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(152u /* 152 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &channel_1_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool channel_2_fault = 20; + case 20: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(160u /* 160 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &channel_2_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool boo_fault = 21; + case 21: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(168u /* 168 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &boo_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool connector_fault = 22; + case 22: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(176u /* 176 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &connector_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 brake_torque_req = 23; + case 23: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(184u /* 184 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &brake_torque_req_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Brake.HSAStatusType hsa_status = 24; + case 24: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(192u /* 192 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_hsa_status(static_cast< ::apollo::canbus::Brake_HSAStatusType >(value)); + } else { + goto handle_unusual; + } + break; + } + + // int32 brake_torque_act = 25; + case 25: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(200u /* 200 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &brake_torque_act_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Brake.HSAModeType hsa_mode = 26; + case 26: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(208u /* 208 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_hsa_mode(static_cast< ::apollo::canbus::Brake_HSAModeType >(value)); + } else { + goto handle_unusual; + } + break; + } + + // int32 wheel_torque_act = 27; + case 27: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(216u /* 216 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &wheel_torque_act_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 major_version = 28; + case 28: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(224u /* 224 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &major_version_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 minor_version = 29; + case 29: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(232u /* 232 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &minor_version_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 build_number = 30; + case 30: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(240u /* 240 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &build_number_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.Brake) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.Brake) + return false; +#undef DO_ +} + +void Brake::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.Brake) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_brake_pedal_pressed = 1; + if (this->is_brake_pedal_pressed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_brake_pedal_pressed(), output); + } + + // bool is_brake_force_exist = 2; + if (this->is_brake_force_exist() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_brake_force_exist(), output); + } + + // bool is_brake_over_heat = 3; + if (this->is_brake_over_heat() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(3, this->is_brake_over_heat(), output); + } + + // bool is_hand_brake_on = 4; + if (this->is_hand_brake_on() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(4, this->is_hand_brake_on(), output); + } + + // double brake_pedal_position = 5; + if (this->brake_pedal_position() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->brake_pedal_position(), output); + } + + // bool is_brake_valid = 6; + if (this->is_brake_valid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(6, this->is_brake_valid(), output); + } + + // double brake_input = 7; + if (this->brake_input() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->brake_input(), output); + } + + // double brake_cmd = 8; + if (this->brake_cmd() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(8, this->brake_cmd(), output); + } + + // double brake_output = 9; + if (this->brake_output() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->brake_output(), output); + } + + // bool boo_input = 10; + if (this->boo_input() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(10, this->boo_input(), output); + } + + // bool boo_cmd = 11; + if (this->boo_cmd() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(11, this->boo_cmd(), output); + } + + // bool boo_output = 12; + if (this->boo_output() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(12, this->boo_output(), output); + } + + // bool watchdog_applying_brakes = 13; + if (this->watchdog_applying_brakes() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(13, this->watchdog_applying_brakes(), output); + } + + // int32 watchdog_source = 14; + if (this->watchdog_source() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(14, this->watchdog_source(), output); + } + + // bool brake_enabled = 15; + if (this->brake_enabled() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(15, this->brake_enabled(), output); + } + + // bool driver_override = 16; + if (this->driver_override() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(16, this->driver_override(), output); + } + + // bool driver_activity = 17; + if (this->driver_activity() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(17, this->driver_activity(), output); + } + + // bool watchdog_fault = 18; + if (this->watchdog_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(18, this->watchdog_fault(), output); + } + + // bool channel_1_fault = 19; + if (this->channel_1_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(19, this->channel_1_fault(), output); + } + + // bool channel_2_fault = 20; + if (this->channel_2_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(20, this->channel_2_fault(), output); + } + + // bool boo_fault = 21; + if (this->boo_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(21, this->boo_fault(), output); + } + + // bool connector_fault = 22; + if (this->connector_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(22, this->connector_fault(), output); + } + + // int32 brake_torque_req = 23; + if (this->brake_torque_req() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(23, this->brake_torque_req(), output); + } + + // .apollo.canbus.Brake.HSAStatusType hsa_status = 24; + if (this->hsa_status() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 24, this->hsa_status(), output); + } + + // int32 brake_torque_act = 25; + if (this->brake_torque_act() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(25, this->brake_torque_act(), output); + } + + // .apollo.canbus.Brake.HSAModeType hsa_mode = 26; + if (this->hsa_mode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 26, this->hsa_mode(), output); + } + + // int32 wheel_torque_act = 27; + if (this->wheel_torque_act() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(27, this->wheel_torque_act(), output); + } + + // int32 major_version = 28; + if (this->major_version() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(28, this->major_version(), output); + } + + // int32 minor_version = 29; + if (this->minor_version() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(29, this->minor_version(), output); + } + + // int32 build_number = 30; + if (this->build_number() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(30, this->build_number(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.Brake) +} + +::google::protobuf::uint8* Brake::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.Brake) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_brake_pedal_pressed = 1; + if (this->is_brake_pedal_pressed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_brake_pedal_pressed(), target); + } + + // bool is_brake_force_exist = 2; + if (this->is_brake_force_exist() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_brake_force_exist(), target); + } + + // bool is_brake_over_heat = 3; + if (this->is_brake_over_heat() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(3, this->is_brake_over_heat(), target); + } + + // bool is_hand_brake_on = 4; + if (this->is_hand_brake_on() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(4, this->is_hand_brake_on(), target); + } + + // double brake_pedal_position = 5; + if (this->brake_pedal_position() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->brake_pedal_position(), target); + } + + // bool is_brake_valid = 6; + if (this->is_brake_valid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(6, this->is_brake_valid(), target); + } + + // double brake_input = 7; + if (this->brake_input() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->brake_input(), target); + } + + // double brake_cmd = 8; + if (this->brake_cmd() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(8, this->brake_cmd(), target); + } + + // double brake_output = 9; + if (this->brake_output() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->brake_output(), target); + } + + // bool boo_input = 10; + if (this->boo_input() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(10, this->boo_input(), target); + } + + // bool boo_cmd = 11; + if (this->boo_cmd() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(11, this->boo_cmd(), target); + } + + // bool boo_output = 12; + if (this->boo_output() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(12, this->boo_output(), target); + } + + // bool watchdog_applying_brakes = 13; + if (this->watchdog_applying_brakes() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(13, this->watchdog_applying_brakes(), target); + } + + // int32 watchdog_source = 14; + if (this->watchdog_source() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(14, this->watchdog_source(), target); + } + + // bool brake_enabled = 15; + if (this->brake_enabled() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(15, this->brake_enabled(), target); + } + + // bool driver_override = 16; + if (this->driver_override() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(16, this->driver_override(), target); + } + + // bool driver_activity = 17; + if (this->driver_activity() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(17, this->driver_activity(), target); + } + + // bool watchdog_fault = 18; + if (this->watchdog_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(18, this->watchdog_fault(), target); + } + + // bool channel_1_fault = 19; + if (this->channel_1_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(19, this->channel_1_fault(), target); + } + + // bool channel_2_fault = 20; + if (this->channel_2_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(20, this->channel_2_fault(), target); + } + + // bool boo_fault = 21; + if (this->boo_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(21, this->boo_fault(), target); + } + + // bool connector_fault = 22; + if (this->connector_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(22, this->connector_fault(), target); + } + + // int32 brake_torque_req = 23; + if (this->brake_torque_req() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(23, this->brake_torque_req(), target); + } + + // .apollo.canbus.Brake.HSAStatusType hsa_status = 24; + if (this->hsa_status() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 24, this->hsa_status(), target); + } + + // int32 brake_torque_act = 25; + if (this->brake_torque_act() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(25, this->brake_torque_act(), target); + } + + // .apollo.canbus.Brake.HSAModeType hsa_mode = 26; + if (this->hsa_mode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 26, this->hsa_mode(), target); + } + + // int32 wheel_torque_act = 27; + if (this->wheel_torque_act() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(27, this->wheel_torque_act(), target); + } + + // int32 major_version = 28; + if (this->major_version() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(28, this->major_version(), target); + } + + // int32 minor_version = 29; + if (this->minor_version() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(29, this->minor_version(), target); + } + + // int32 build_number = 30; + if (this->build_number() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(30, this->build_number(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.Brake) + return target; +} + +size_t Brake::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.Brake) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double brake_pedal_position = 5; + if (this->brake_pedal_position() != 0) { + total_size += 1 + 8; + } + + // bool is_brake_pedal_pressed = 1; + if (this->is_brake_pedal_pressed() != 0) { + total_size += 1 + 1; + } + + // bool is_brake_force_exist = 2; + if (this->is_brake_force_exist() != 0) { + total_size += 1 + 1; + } + + // bool is_brake_over_heat = 3; + if (this->is_brake_over_heat() != 0) { + total_size += 1 + 1; + } + + // bool is_hand_brake_on = 4; + if (this->is_hand_brake_on() != 0) { + total_size += 1 + 1; + } + + // bool is_brake_valid = 6; + if (this->is_brake_valid() != 0) { + total_size += 1 + 1; + } + + // bool boo_input = 10; + if (this->boo_input() != 0) { + total_size += 1 + 1; + } + + // bool boo_cmd = 11; + if (this->boo_cmd() != 0) { + total_size += 1 + 1; + } + + // bool boo_output = 12; + if (this->boo_output() != 0) { + total_size += 1 + 1; + } + + // double brake_input = 7; + if (this->brake_input() != 0) { + total_size += 1 + 8; + } + + // double brake_cmd = 8; + if (this->brake_cmd() != 0) { + total_size += 1 + 8; + } + + // double brake_output = 9; + if (this->brake_output() != 0) { + total_size += 1 + 8; + } + + // int32 watchdog_source = 14; + if (this->watchdog_source() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->watchdog_source()); + } + + // bool watchdog_applying_brakes = 13; + if (this->watchdog_applying_brakes() != 0) { + total_size += 1 + 1; + } + + // bool brake_enabled = 15; + if (this->brake_enabled() != 0) { + total_size += 1 + 1; + } + + // bool driver_override = 16; + if (this->driver_override() != 0) { + total_size += 2 + 1; + } + + // bool driver_activity = 17; + if (this->driver_activity() != 0) { + total_size += 2 + 1; + } + + // bool watchdog_fault = 18; + if (this->watchdog_fault() != 0) { + total_size += 2 + 1; + } + + // bool channel_1_fault = 19; + if (this->channel_1_fault() != 0) { + total_size += 2 + 1; + } + + // bool channel_2_fault = 20; + if (this->channel_2_fault() != 0) { + total_size += 2 + 1; + } + + // bool boo_fault = 21; + if (this->boo_fault() != 0) { + total_size += 2 + 1; + } + + // bool connector_fault = 22; + if (this->connector_fault() != 0) { + total_size += 2 + 1; + } + + // int32 brake_torque_req = 23; + if (this->brake_torque_req() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->brake_torque_req()); + } + + // .apollo.canbus.Brake.HSAStatusType hsa_status = 24; + if (this->hsa_status() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->hsa_status()); + } + + // int32 brake_torque_act = 25; + if (this->brake_torque_act() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->brake_torque_act()); + } + + // .apollo.canbus.Brake.HSAModeType hsa_mode = 26; + if (this->hsa_mode() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->hsa_mode()); + } + + // int32 wheel_torque_act = 27; + if (this->wheel_torque_act() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->wheel_torque_act()); + } + + // int32 major_version = 28; + if (this->major_version() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->major_version()); + } + + // int32 minor_version = 29; + if (this->minor_version() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->minor_version()); + } + + // int32 build_number = 30; + if (this->build_number() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->build_number()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Brake::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.Brake) + GOOGLE_DCHECK_NE(&from, this); + const Brake* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.Brake) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.Brake) + MergeFrom(*source); + } +} + +void Brake::MergeFrom(const Brake& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.Brake) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.brake_pedal_position() != 0) { + set_brake_pedal_position(from.brake_pedal_position()); + } + if (from.is_brake_pedal_pressed() != 0) { + set_is_brake_pedal_pressed(from.is_brake_pedal_pressed()); + } + if (from.is_brake_force_exist() != 0) { + set_is_brake_force_exist(from.is_brake_force_exist()); + } + if (from.is_brake_over_heat() != 0) { + set_is_brake_over_heat(from.is_brake_over_heat()); + } + if (from.is_hand_brake_on() != 0) { + set_is_hand_brake_on(from.is_hand_brake_on()); + } + if (from.is_brake_valid() != 0) { + set_is_brake_valid(from.is_brake_valid()); + } + if (from.boo_input() != 0) { + set_boo_input(from.boo_input()); + } + if (from.boo_cmd() != 0) { + set_boo_cmd(from.boo_cmd()); + } + if (from.boo_output() != 0) { + set_boo_output(from.boo_output()); + } + if (from.brake_input() != 0) { + set_brake_input(from.brake_input()); + } + if (from.brake_cmd() != 0) { + set_brake_cmd(from.brake_cmd()); + } + if (from.brake_output() != 0) { + set_brake_output(from.brake_output()); + } + if (from.watchdog_source() != 0) { + set_watchdog_source(from.watchdog_source()); + } + if (from.watchdog_applying_brakes() != 0) { + set_watchdog_applying_brakes(from.watchdog_applying_brakes()); + } + if (from.brake_enabled() != 0) { + set_brake_enabled(from.brake_enabled()); + } + if (from.driver_override() != 0) { + set_driver_override(from.driver_override()); + } + if (from.driver_activity() != 0) { + set_driver_activity(from.driver_activity()); + } + if (from.watchdog_fault() != 0) { + set_watchdog_fault(from.watchdog_fault()); + } + if (from.channel_1_fault() != 0) { + set_channel_1_fault(from.channel_1_fault()); + } + if (from.channel_2_fault() != 0) { + set_channel_2_fault(from.channel_2_fault()); + } + if (from.boo_fault() != 0) { + set_boo_fault(from.boo_fault()); + } + if (from.connector_fault() != 0) { + set_connector_fault(from.connector_fault()); + } + if (from.brake_torque_req() != 0) { + set_brake_torque_req(from.brake_torque_req()); + } + if (from.hsa_status() != 0) { + set_hsa_status(from.hsa_status()); + } + if (from.brake_torque_act() != 0) { + set_brake_torque_act(from.brake_torque_act()); + } + if (from.hsa_mode() != 0) { + set_hsa_mode(from.hsa_mode()); + } + if (from.wheel_torque_act() != 0) { + set_wheel_torque_act(from.wheel_torque_act()); + } + if (from.major_version() != 0) { + set_major_version(from.major_version()); + } + if (from.minor_version() != 0) { + set_minor_version(from.minor_version()); + } + if (from.build_number() != 0) { + set_build_number(from.build_number()); + } +} + +void Brake::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.Brake) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Brake::CopyFrom(const Brake& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.Brake) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Brake::IsInitialized() const { + return true; +} + +void Brake::Swap(Brake* other) { + if (other == this) return; + InternalSwap(other); +} +void Brake::InternalSwap(Brake* other) { + using std::swap; + swap(brake_pedal_position_, other->brake_pedal_position_); + swap(is_brake_pedal_pressed_, other->is_brake_pedal_pressed_); + swap(is_brake_force_exist_, other->is_brake_force_exist_); + swap(is_brake_over_heat_, other->is_brake_over_heat_); + swap(is_hand_brake_on_, other->is_hand_brake_on_); + swap(is_brake_valid_, other->is_brake_valid_); + swap(boo_input_, other->boo_input_); + swap(boo_cmd_, other->boo_cmd_); + swap(boo_output_, other->boo_output_); + swap(brake_input_, other->brake_input_); + swap(brake_cmd_, other->brake_cmd_); + swap(brake_output_, other->brake_output_); + swap(watchdog_source_, other->watchdog_source_); + swap(watchdog_applying_brakes_, other->watchdog_applying_brakes_); + swap(brake_enabled_, other->brake_enabled_); + swap(driver_override_, other->driver_override_); + swap(driver_activity_, other->driver_activity_); + swap(watchdog_fault_, other->watchdog_fault_); + swap(channel_1_fault_, other->channel_1_fault_); + swap(channel_2_fault_, other->channel_2_fault_); + swap(boo_fault_, other->boo_fault_); + swap(connector_fault_, other->connector_fault_); + swap(brake_torque_req_, other->brake_torque_req_); + swap(hsa_status_, other->hsa_status_); + swap(brake_torque_act_, other->brake_torque_act_); + swap(hsa_mode_, other->hsa_mode_); + swap(wheel_torque_act_, other->wheel_torque_act_); + swap(major_version_, other->major_version_); + swap(minor_version_, other->minor_version_); + swap(build_number_, other->build_number_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Brake::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Epb::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Epb::kIsEpbErrorFieldNumber; +const int Epb::kIsEpbReleasedFieldNumber; +const int Epb::kEpbStatusFieldNumber; +const int Epb::kParkingBrakeStatusFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Epb::Epb() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Epb.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.Epb) +} +Epb::Epb(const Epb& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&is_epb_error_, &from.is_epb_error_, + static_cast(reinterpret_cast(&parking_brake_status_) - + reinterpret_cast(&is_epb_error_)) + sizeof(parking_brake_status_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.Epb) +} + +void Epb::SharedCtor() { + ::memset(&is_epb_error_, 0, static_cast( + reinterpret_cast(&parking_brake_status_) - + reinterpret_cast(&is_epb_error_)) + sizeof(parking_brake_status_)); +} + +Epb::~Epb() { + // @@protoc_insertion_point(destructor:apollo.canbus.Epb) + SharedDtor(); +} + +void Epb::SharedDtor() { +} + +void Epb::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Epb::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Epb& Epb::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Epb.base); + return *internal_default_instance(); +} + + +void Epb::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.Epb) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&is_epb_error_, 0, static_cast( + reinterpret_cast(&parking_brake_status_) - + reinterpret_cast(&is_epb_error_)) + sizeof(parking_brake_status_)); + _internal_metadata_.Clear(); +} + +bool Epb::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.Epb) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_epb_error = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_epb_error_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_epb_released = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_epb_released_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 epb_status = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &epb_status_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Epb.PBrakeType parking_brake_status = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_parking_brake_status(static_cast< ::apollo::canbus::Epb_PBrakeType >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.Epb) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.Epb) + return false; +#undef DO_ +} + +void Epb::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.Epb) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_epb_error = 1; + if (this->is_epb_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_epb_error(), output); + } + + // bool is_epb_released = 2; + if (this->is_epb_released() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_epb_released(), output); + } + + // int32 epb_status = 3; + if (this->epb_status() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(3, this->epb_status(), output); + } + + // .apollo.canbus.Epb.PBrakeType parking_brake_status = 4; + if (this->parking_brake_status() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 4, this->parking_brake_status(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.Epb) +} + +::google::protobuf::uint8* Epb::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.Epb) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_epb_error = 1; + if (this->is_epb_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_epb_error(), target); + } + + // bool is_epb_released = 2; + if (this->is_epb_released() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_epb_released(), target); + } + + // int32 epb_status = 3; + if (this->epb_status() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(3, this->epb_status(), target); + } + + // .apollo.canbus.Epb.PBrakeType parking_brake_status = 4; + if (this->parking_brake_status() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 4, this->parking_brake_status(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.Epb) + return target; +} + +size_t Epb::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.Epb) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // bool is_epb_error = 1; + if (this->is_epb_error() != 0) { + total_size += 1 + 1; + } + + // bool is_epb_released = 2; + if (this->is_epb_released() != 0) { + total_size += 1 + 1; + } + + // int32 epb_status = 3; + if (this->epb_status() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->epb_status()); + } + + // .apollo.canbus.Epb.PBrakeType parking_brake_status = 4; + if (this->parking_brake_status() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->parking_brake_status()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Epb::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.Epb) + GOOGLE_DCHECK_NE(&from, this); + const Epb* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.Epb) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.Epb) + MergeFrom(*source); + } +} + +void Epb::MergeFrom(const Epb& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.Epb) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.is_epb_error() != 0) { + set_is_epb_error(from.is_epb_error()); + } + if (from.is_epb_released() != 0) { + set_is_epb_released(from.is_epb_released()); + } + if (from.epb_status() != 0) { + set_epb_status(from.epb_status()); + } + if (from.parking_brake_status() != 0) { + set_parking_brake_status(from.parking_brake_status()); + } +} + +void Epb::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.Epb) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Epb::CopyFrom(const Epb& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.Epb) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Epb::IsInitialized() const { + return true; +} + +void Epb::Swap(Epb* other) { + if (other == this) return; + InternalSwap(other); +} +void Epb::InternalSwap(Epb* other) { + using std::swap; + swap(is_epb_error_, other->is_epb_error_); + swap(is_epb_released_, other->is_epb_released_); + swap(epb_status_, other->epb_status_); + swap(parking_brake_status_, other->parking_brake_status_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Epb::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Gas::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Gas::kIsGasPedalErrorFieldNumber; +const int Gas::kIsGasPedalPressedMoreFieldNumber; +const int Gas::kGasPedalPositionFieldNumber; +const int Gas::kIsGasValidFieldNumber; +const int Gas::kThrottleInputFieldNumber; +const int Gas::kThrottleCmdFieldNumber; +const int Gas::kThrottleOutputFieldNumber; +const int Gas::kWatchdogSourceFieldNumber; +const int Gas::kThrottleEnabledFieldNumber; +const int Gas::kDriverOverrideFieldNumber; +const int Gas::kDriverActivityFieldNumber; +const int Gas::kWatchdogFaultFieldNumber; +const int Gas::kChannel1FaultFieldNumber; +const int Gas::kChannel2FaultFieldNumber; +const int Gas::kConnectorFaultFieldNumber; +const int Gas::kAcceleratorPedalFieldNumber; +const int Gas::kAcceleratorPedalRateFieldNumber; +const int Gas::kMajorVersionFieldNumber; +const int Gas::kMinorVersionFieldNumber; +const int Gas::kBuildNumberFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Gas::Gas() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Gas.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.Gas) +} +Gas::Gas(const Gas& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&gas_pedal_position_, &from.gas_pedal_position_, + static_cast(reinterpret_cast(&build_number_) - + reinterpret_cast(&gas_pedal_position_)) + sizeof(build_number_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.Gas) +} + +void Gas::SharedCtor() { + ::memset(&gas_pedal_position_, 0, static_cast( + reinterpret_cast(&build_number_) - + reinterpret_cast(&gas_pedal_position_)) + sizeof(build_number_)); +} + +Gas::~Gas() { + // @@protoc_insertion_point(destructor:apollo.canbus.Gas) + SharedDtor(); +} + +void Gas::SharedDtor() { +} + +void Gas::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Gas::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Gas& Gas::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Gas.base); + return *internal_default_instance(); +} + + +void Gas::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.Gas) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&gas_pedal_position_, 0, static_cast( + reinterpret_cast(&build_number_) - + reinterpret_cast(&gas_pedal_position_)) + sizeof(build_number_)); + _internal_metadata_.Clear(); +} + +bool Gas::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.Gas) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_gas_pedal_error = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_gas_pedal_error_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_gas_pedal_pressed_more = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_gas_pedal_pressed_more_))); + } else { + goto handle_unusual; + } + break; + } + + // double gas_pedal_position = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &gas_pedal_position_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_gas_valid = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_gas_valid_))); + } else { + goto handle_unusual; + } + break; + } + + // double throttle_input = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &throttle_input_))); + } else { + goto handle_unusual; + } + break; + } + + // double throttle_cmd = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &throttle_cmd_))); + } else { + goto handle_unusual; + } + break; + } + + // double throttle_output = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &throttle_output_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 watchdog_source = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(64u /* 64 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &watchdog_source_))); + } else { + goto handle_unusual; + } + break; + } + + // bool throttle_enabled = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(72u /* 72 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &throttle_enabled_))); + } else { + goto handle_unusual; + } + break; + } + + // bool driver_override = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(80u /* 80 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &driver_override_))); + } else { + goto handle_unusual; + } + break; + } + + // bool driver_activity = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(88u /* 88 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &driver_activity_))); + } else { + goto handle_unusual; + } + break; + } + + // bool watchdog_fault = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(96u /* 96 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &watchdog_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool channel_1_fault = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(104u /* 104 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &channel_1_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool channel_2_fault = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(112u /* 112 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &channel_2_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool connector_fault = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(120u /* 120 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &connector_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // double accelerator_pedal = 16; + case 16: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(129u /* 129 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &accelerator_pedal_))); + } else { + goto handle_unusual; + } + break; + } + + // double accelerator_pedal_rate = 17; + case 17: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(137u /* 137 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &accelerator_pedal_rate_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 major_version = 18; + case 18: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(144u /* 144 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &major_version_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 minor_version = 19; + case 19: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(152u /* 152 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &minor_version_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 build_number = 20; + case 20: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(160u /* 160 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &build_number_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.Gas) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.Gas) + return false; +#undef DO_ +} + +void Gas::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.Gas) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_gas_pedal_error = 1; + if (this->is_gas_pedal_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_gas_pedal_error(), output); + } + + // bool is_gas_pedal_pressed_more = 2; + if (this->is_gas_pedal_pressed_more() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_gas_pedal_pressed_more(), output); + } + + // double gas_pedal_position = 3; + if (this->gas_pedal_position() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->gas_pedal_position(), output); + } + + // bool is_gas_valid = 4; + if (this->is_gas_valid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(4, this->is_gas_valid(), output); + } + + // double throttle_input = 5; + if (this->throttle_input() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->throttle_input(), output); + } + + // double throttle_cmd = 6; + if (this->throttle_cmd() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->throttle_cmd(), output); + } + + // double throttle_output = 7; + if (this->throttle_output() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->throttle_output(), output); + } + + // int32 watchdog_source = 8; + if (this->watchdog_source() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(8, this->watchdog_source(), output); + } + + // bool throttle_enabled = 9; + if (this->throttle_enabled() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(9, this->throttle_enabled(), output); + } + + // bool driver_override = 10; + if (this->driver_override() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(10, this->driver_override(), output); + } + + // bool driver_activity = 11; + if (this->driver_activity() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(11, this->driver_activity(), output); + } + + // bool watchdog_fault = 12; + if (this->watchdog_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(12, this->watchdog_fault(), output); + } + + // bool channel_1_fault = 13; + if (this->channel_1_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(13, this->channel_1_fault(), output); + } + + // bool channel_2_fault = 14; + if (this->channel_2_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(14, this->channel_2_fault(), output); + } + + // bool connector_fault = 15; + if (this->connector_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(15, this->connector_fault(), output); + } + + // double accelerator_pedal = 16; + if (this->accelerator_pedal() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(16, this->accelerator_pedal(), output); + } + + // double accelerator_pedal_rate = 17; + if (this->accelerator_pedal_rate() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(17, this->accelerator_pedal_rate(), output); + } + + // int32 major_version = 18; + if (this->major_version() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(18, this->major_version(), output); + } + + // int32 minor_version = 19; + if (this->minor_version() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(19, this->minor_version(), output); + } + + // int32 build_number = 20; + if (this->build_number() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(20, this->build_number(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.Gas) +} + +::google::protobuf::uint8* Gas::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.Gas) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_gas_pedal_error = 1; + if (this->is_gas_pedal_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_gas_pedal_error(), target); + } + + // bool is_gas_pedal_pressed_more = 2; + if (this->is_gas_pedal_pressed_more() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_gas_pedal_pressed_more(), target); + } + + // double gas_pedal_position = 3; + if (this->gas_pedal_position() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->gas_pedal_position(), target); + } + + // bool is_gas_valid = 4; + if (this->is_gas_valid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(4, this->is_gas_valid(), target); + } + + // double throttle_input = 5; + if (this->throttle_input() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->throttle_input(), target); + } + + // double throttle_cmd = 6; + if (this->throttle_cmd() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->throttle_cmd(), target); + } + + // double throttle_output = 7; + if (this->throttle_output() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->throttle_output(), target); + } + + // int32 watchdog_source = 8; + if (this->watchdog_source() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(8, this->watchdog_source(), target); + } + + // bool throttle_enabled = 9; + if (this->throttle_enabled() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(9, this->throttle_enabled(), target); + } + + // bool driver_override = 10; + if (this->driver_override() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(10, this->driver_override(), target); + } + + // bool driver_activity = 11; + if (this->driver_activity() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(11, this->driver_activity(), target); + } + + // bool watchdog_fault = 12; + if (this->watchdog_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(12, this->watchdog_fault(), target); + } + + // bool channel_1_fault = 13; + if (this->channel_1_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(13, this->channel_1_fault(), target); + } + + // bool channel_2_fault = 14; + if (this->channel_2_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(14, this->channel_2_fault(), target); + } + + // bool connector_fault = 15; + if (this->connector_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(15, this->connector_fault(), target); + } + + // double accelerator_pedal = 16; + if (this->accelerator_pedal() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(16, this->accelerator_pedal(), target); + } + + // double accelerator_pedal_rate = 17; + if (this->accelerator_pedal_rate() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(17, this->accelerator_pedal_rate(), target); + } + + // int32 major_version = 18; + if (this->major_version() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(18, this->major_version(), target); + } + + // int32 minor_version = 19; + if (this->minor_version() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(19, this->minor_version(), target); + } + + // int32 build_number = 20; + if (this->build_number() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(20, this->build_number(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.Gas) + return target; +} + +size_t Gas::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.Gas) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double gas_pedal_position = 3; + if (this->gas_pedal_position() != 0) { + total_size += 1 + 8; + } + + // bool is_gas_pedal_error = 1; + if (this->is_gas_pedal_error() != 0) { + total_size += 1 + 1; + } + + // bool is_gas_pedal_pressed_more = 2; + if (this->is_gas_pedal_pressed_more() != 0) { + total_size += 1 + 1; + } + + // bool is_gas_valid = 4; + if (this->is_gas_valid() != 0) { + total_size += 1 + 1; + } + + // bool throttle_enabled = 9; + if (this->throttle_enabled() != 0) { + total_size += 1 + 1; + } + + // int32 watchdog_source = 8; + if (this->watchdog_source() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->watchdog_source()); + } + + // double throttle_input = 5; + if (this->throttle_input() != 0) { + total_size += 1 + 8; + } + + // double throttle_cmd = 6; + if (this->throttle_cmd() != 0) { + total_size += 1 + 8; + } + + // double throttle_output = 7; + if (this->throttle_output() != 0) { + total_size += 1 + 8; + } + + // bool driver_override = 10; + if (this->driver_override() != 0) { + total_size += 1 + 1; + } + + // bool driver_activity = 11; + if (this->driver_activity() != 0) { + total_size += 1 + 1; + } + + // bool watchdog_fault = 12; + if (this->watchdog_fault() != 0) { + total_size += 1 + 1; + } + + // bool channel_1_fault = 13; + if (this->channel_1_fault() != 0) { + total_size += 1 + 1; + } + + // bool channel_2_fault = 14; + if (this->channel_2_fault() != 0) { + total_size += 1 + 1; + } + + // bool connector_fault = 15; + if (this->connector_fault() != 0) { + total_size += 1 + 1; + } + + // double accelerator_pedal = 16; + if (this->accelerator_pedal() != 0) { + total_size += 2 + 8; + } + + // double accelerator_pedal_rate = 17; + if (this->accelerator_pedal_rate() != 0) { + total_size += 2 + 8; + } + + // int32 major_version = 18; + if (this->major_version() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->major_version()); + } + + // int32 minor_version = 19; + if (this->minor_version() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->minor_version()); + } + + // int32 build_number = 20; + if (this->build_number() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->build_number()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Gas::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.Gas) + GOOGLE_DCHECK_NE(&from, this); + const Gas* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.Gas) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.Gas) + MergeFrom(*source); + } +} + +void Gas::MergeFrom(const Gas& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.Gas) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.gas_pedal_position() != 0) { + set_gas_pedal_position(from.gas_pedal_position()); + } + if (from.is_gas_pedal_error() != 0) { + set_is_gas_pedal_error(from.is_gas_pedal_error()); + } + if (from.is_gas_pedal_pressed_more() != 0) { + set_is_gas_pedal_pressed_more(from.is_gas_pedal_pressed_more()); + } + if (from.is_gas_valid() != 0) { + set_is_gas_valid(from.is_gas_valid()); + } + if (from.throttle_enabled() != 0) { + set_throttle_enabled(from.throttle_enabled()); + } + if (from.watchdog_source() != 0) { + set_watchdog_source(from.watchdog_source()); + } + if (from.throttle_input() != 0) { + set_throttle_input(from.throttle_input()); + } + if (from.throttle_cmd() != 0) { + set_throttle_cmd(from.throttle_cmd()); + } + if (from.throttle_output() != 0) { + set_throttle_output(from.throttle_output()); + } + if (from.driver_override() != 0) { + set_driver_override(from.driver_override()); + } + if (from.driver_activity() != 0) { + set_driver_activity(from.driver_activity()); + } + if (from.watchdog_fault() != 0) { + set_watchdog_fault(from.watchdog_fault()); + } + if (from.channel_1_fault() != 0) { + set_channel_1_fault(from.channel_1_fault()); + } + if (from.channel_2_fault() != 0) { + set_channel_2_fault(from.channel_2_fault()); + } + if (from.connector_fault() != 0) { + set_connector_fault(from.connector_fault()); + } + if (from.accelerator_pedal() != 0) { + set_accelerator_pedal(from.accelerator_pedal()); + } + if (from.accelerator_pedal_rate() != 0) { + set_accelerator_pedal_rate(from.accelerator_pedal_rate()); + } + if (from.major_version() != 0) { + set_major_version(from.major_version()); + } + if (from.minor_version() != 0) { + set_minor_version(from.minor_version()); + } + if (from.build_number() != 0) { + set_build_number(from.build_number()); + } +} + +void Gas::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.Gas) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Gas::CopyFrom(const Gas& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.Gas) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Gas::IsInitialized() const { + return true; +} + +void Gas::Swap(Gas* other) { + if (other == this) return; + InternalSwap(other); +} +void Gas::InternalSwap(Gas* other) { + using std::swap; + swap(gas_pedal_position_, other->gas_pedal_position_); + swap(is_gas_pedal_error_, other->is_gas_pedal_error_); + swap(is_gas_pedal_pressed_more_, other->is_gas_pedal_pressed_more_); + swap(is_gas_valid_, other->is_gas_valid_); + swap(throttle_enabled_, other->throttle_enabled_); + swap(watchdog_source_, other->watchdog_source_); + swap(throttle_input_, other->throttle_input_); + swap(throttle_cmd_, other->throttle_cmd_); + swap(throttle_output_, other->throttle_output_); + swap(driver_override_, other->driver_override_); + swap(driver_activity_, other->driver_activity_); + swap(watchdog_fault_, other->watchdog_fault_); + swap(channel_1_fault_, other->channel_1_fault_); + swap(channel_2_fault_, other->channel_2_fault_); + swap(connector_fault_, other->connector_fault_); + swap(accelerator_pedal_, other->accelerator_pedal_); + swap(accelerator_pedal_rate_, other->accelerator_pedal_rate_); + swap(major_version_, other->major_version_); + swap(minor_version_, other->minor_version_); + swap(build_number_, other->build_number_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Gas::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Esp::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Esp::kIsEspAccErrorFieldNumber; +const int Esp::kIsEspOnFieldNumber; +const int Esp::kIsEspActiveFieldNumber; +const int Esp::kIsAbsErrorFieldNumber; +const int Esp::kIsAbsActiveFieldNumber; +const int Esp::kIsTcsvdcFailFieldNumber; +const int Esp::kIsAbsEnabledFieldNumber; +const int Esp::kIsStabActiveFieldNumber; +const int Esp::kIsStabEnabledFieldNumber; +const int Esp::kIsTracActiveFieldNumber; +const int Esp::kIsTracEnabledFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Esp::Esp() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Esp.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.Esp) +} +Esp::Esp(const Esp& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&is_esp_acc_error_, &from.is_esp_acc_error_, + static_cast(reinterpret_cast(&is_trac_enabled_) - + reinterpret_cast(&is_esp_acc_error_)) + sizeof(is_trac_enabled_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.Esp) +} + +void Esp::SharedCtor() { + ::memset(&is_esp_acc_error_, 0, static_cast( + reinterpret_cast(&is_trac_enabled_) - + reinterpret_cast(&is_esp_acc_error_)) + sizeof(is_trac_enabled_)); +} + +Esp::~Esp() { + // @@protoc_insertion_point(destructor:apollo.canbus.Esp) + SharedDtor(); +} + +void Esp::SharedDtor() { +} + +void Esp::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Esp::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Esp& Esp::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Esp.base); + return *internal_default_instance(); +} + + +void Esp::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.Esp) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&is_esp_acc_error_, 0, static_cast( + reinterpret_cast(&is_trac_enabled_) - + reinterpret_cast(&is_esp_acc_error_)) + sizeof(is_trac_enabled_)); + _internal_metadata_.Clear(); +} + +bool Esp::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.Esp) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_esp_acc_error = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_esp_acc_error_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_esp_on = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_esp_on_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_esp_active = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_esp_active_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_abs_error = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_abs_error_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_abs_active = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(40u /* 40 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_abs_active_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_tcsvdc_fail = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(48u /* 48 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_tcsvdc_fail_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_abs_enabled = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(56u /* 56 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_abs_enabled_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_stab_active = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(64u /* 64 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_stab_active_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_stab_enabled = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(72u /* 72 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_stab_enabled_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_trac_active = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(80u /* 80 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_trac_active_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_trac_enabled = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(88u /* 88 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_trac_enabled_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.Esp) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.Esp) + return false; +#undef DO_ +} + +void Esp::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.Esp) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_esp_acc_error = 1; + if (this->is_esp_acc_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_esp_acc_error(), output); + } + + // bool is_esp_on = 2; + if (this->is_esp_on() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_esp_on(), output); + } + + // bool is_esp_active = 3; + if (this->is_esp_active() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(3, this->is_esp_active(), output); + } + + // bool is_abs_error = 4; + if (this->is_abs_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(4, this->is_abs_error(), output); + } + + // bool is_abs_active = 5; + if (this->is_abs_active() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(5, this->is_abs_active(), output); + } + + // bool is_tcsvdc_fail = 6; + if (this->is_tcsvdc_fail() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(6, this->is_tcsvdc_fail(), output); + } + + // bool is_abs_enabled = 7; + if (this->is_abs_enabled() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(7, this->is_abs_enabled(), output); + } + + // bool is_stab_active = 8; + if (this->is_stab_active() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(8, this->is_stab_active(), output); + } + + // bool is_stab_enabled = 9; + if (this->is_stab_enabled() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(9, this->is_stab_enabled(), output); + } + + // bool is_trac_active = 10; + if (this->is_trac_active() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(10, this->is_trac_active(), output); + } + + // bool is_trac_enabled = 11; + if (this->is_trac_enabled() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(11, this->is_trac_enabled(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.Esp) +} + +::google::protobuf::uint8* Esp::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.Esp) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_esp_acc_error = 1; + if (this->is_esp_acc_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_esp_acc_error(), target); + } + + // bool is_esp_on = 2; + if (this->is_esp_on() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_esp_on(), target); + } + + // bool is_esp_active = 3; + if (this->is_esp_active() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(3, this->is_esp_active(), target); + } + + // bool is_abs_error = 4; + if (this->is_abs_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(4, this->is_abs_error(), target); + } + + // bool is_abs_active = 5; + if (this->is_abs_active() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(5, this->is_abs_active(), target); + } + + // bool is_tcsvdc_fail = 6; + if (this->is_tcsvdc_fail() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(6, this->is_tcsvdc_fail(), target); + } + + // bool is_abs_enabled = 7; + if (this->is_abs_enabled() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(7, this->is_abs_enabled(), target); + } + + // bool is_stab_active = 8; + if (this->is_stab_active() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(8, this->is_stab_active(), target); + } + + // bool is_stab_enabled = 9; + if (this->is_stab_enabled() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(9, this->is_stab_enabled(), target); + } + + // bool is_trac_active = 10; + if (this->is_trac_active() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(10, this->is_trac_active(), target); + } + + // bool is_trac_enabled = 11; + if (this->is_trac_enabled() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(11, this->is_trac_enabled(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.Esp) + return target; +} + +size_t Esp::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.Esp) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // bool is_esp_acc_error = 1; + if (this->is_esp_acc_error() != 0) { + total_size += 1 + 1; + } + + // bool is_esp_on = 2; + if (this->is_esp_on() != 0) { + total_size += 1 + 1; + } + + // bool is_esp_active = 3; + if (this->is_esp_active() != 0) { + total_size += 1 + 1; + } + + // bool is_abs_error = 4; + if (this->is_abs_error() != 0) { + total_size += 1 + 1; + } + + // bool is_abs_active = 5; + if (this->is_abs_active() != 0) { + total_size += 1 + 1; + } + + // bool is_tcsvdc_fail = 6; + if (this->is_tcsvdc_fail() != 0) { + total_size += 1 + 1; + } + + // bool is_abs_enabled = 7; + if (this->is_abs_enabled() != 0) { + total_size += 1 + 1; + } + + // bool is_stab_active = 8; + if (this->is_stab_active() != 0) { + total_size += 1 + 1; + } + + // bool is_stab_enabled = 9; + if (this->is_stab_enabled() != 0) { + total_size += 1 + 1; + } + + // bool is_trac_active = 10; + if (this->is_trac_active() != 0) { + total_size += 1 + 1; + } + + // bool is_trac_enabled = 11; + if (this->is_trac_enabled() != 0) { + total_size += 1 + 1; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Esp::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.Esp) + GOOGLE_DCHECK_NE(&from, this); + const Esp* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.Esp) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.Esp) + MergeFrom(*source); + } +} + +void Esp::MergeFrom(const Esp& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.Esp) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.is_esp_acc_error() != 0) { + set_is_esp_acc_error(from.is_esp_acc_error()); + } + if (from.is_esp_on() != 0) { + set_is_esp_on(from.is_esp_on()); + } + if (from.is_esp_active() != 0) { + set_is_esp_active(from.is_esp_active()); + } + if (from.is_abs_error() != 0) { + set_is_abs_error(from.is_abs_error()); + } + if (from.is_abs_active() != 0) { + set_is_abs_active(from.is_abs_active()); + } + if (from.is_tcsvdc_fail() != 0) { + set_is_tcsvdc_fail(from.is_tcsvdc_fail()); + } + if (from.is_abs_enabled() != 0) { + set_is_abs_enabled(from.is_abs_enabled()); + } + if (from.is_stab_active() != 0) { + set_is_stab_active(from.is_stab_active()); + } + if (from.is_stab_enabled() != 0) { + set_is_stab_enabled(from.is_stab_enabled()); + } + if (from.is_trac_active() != 0) { + set_is_trac_active(from.is_trac_active()); + } + if (from.is_trac_enabled() != 0) { + set_is_trac_enabled(from.is_trac_enabled()); + } +} + +void Esp::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.Esp) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Esp::CopyFrom(const Esp& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.Esp) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Esp::IsInitialized() const { + return true; +} + +void Esp::Swap(Esp* other) { + if (other == this) return; + InternalSwap(other); +} +void Esp::InternalSwap(Esp* other) { + using std::swap; + swap(is_esp_acc_error_, other->is_esp_acc_error_); + swap(is_esp_on_, other->is_esp_on_); + swap(is_esp_active_, other->is_esp_active_); + swap(is_abs_error_, other->is_abs_error_); + swap(is_abs_active_, other->is_abs_active_); + swap(is_tcsvdc_fail_, other->is_tcsvdc_fail_); + swap(is_abs_enabled_, other->is_abs_enabled_); + swap(is_stab_active_, other->is_stab_active_); + swap(is_stab_enabled_, other->is_stab_enabled_); + swap(is_trac_active_, other->is_trac_active_); + swap(is_trac_enabled_, other->is_trac_enabled_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Esp::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Ems::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Ems::kIsEngineAccAvailableFieldNumber; +const int Ems::kIsEngineAccErrorFieldNumber; +const int Ems::kEngineStateFieldNumber; +const int Ems::kMaxEngineTorqPercentFieldNumber; +const int Ems::kMinEngineTorqPercentFieldNumber; +const int Ems::kBaseEngineTorqConstantFieldNumber; +const int Ems::kIsEngineSpeedErrorFieldNumber; +const int Ems::kEngineSpeedFieldNumber; +const int Ems::kEngineTorqueFieldNumber; +const int Ems::kIsOverEngineTorqueFieldNumber; +const int Ems::kEngineRpmFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Ems::Ems() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Ems.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.Ems) +} +Ems::Ems(const Ems& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&max_engine_torq_percent_, &from.max_engine_torq_percent_, + static_cast(reinterpret_cast(&engine_rpm_) - + reinterpret_cast(&max_engine_torq_percent_)) + sizeof(engine_rpm_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.Ems) +} + +void Ems::SharedCtor() { + ::memset(&max_engine_torq_percent_, 0, static_cast( + reinterpret_cast(&engine_rpm_) - + reinterpret_cast(&max_engine_torq_percent_)) + sizeof(engine_rpm_)); +} + +Ems::~Ems() { + // @@protoc_insertion_point(destructor:apollo.canbus.Ems) + SharedDtor(); +} + +void Ems::SharedDtor() { +} + +void Ems::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Ems::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Ems& Ems::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Ems.base); + return *internal_default_instance(); +} + + +void Ems::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.Ems) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&max_engine_torq_percent_, 0, static_cast( + reinterpret_cast(&engine_rpm_) - + reinterpret_cast(&max_engine_torq_percent_)) + sizeof(engine_rpm_)); + _internal_metadata_.Clear(); +} + +bool Ems::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.Ems) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_engine_acc_available = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_engine_acc_available_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_engine_acc_error = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_engine_acc_error_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Ems.Type engine_state = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_engine_state(static_cast< ::apollo::canbus::Ems_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // double max_engine_torq_percent = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &max_engine_torq_percent_))); + } else { + goto handle_unusual; + } + break; + } + + // double min_engine_torq_percent = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &min_engine_torq_percent_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 base_engine_torq_constant = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(48u /* 48 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &base_engine_torq_constant_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_engine_speed_error = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(56u /* 56 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_engine_speed_error_))); + } else { + goto handle_unusual; + } + break; + } + + // double engine_speed = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(65u /* 65 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &engine_speed_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 engine_torque = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(72u /* 72 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &engine_torque_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_over_engine_torque = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(80u /* 80 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_over_engine_torque_))); + } else { + goto handle_unusual; + } + break; + } + + // double engine_rpm = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(89u /* 89 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &engine_rpm_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.Ems) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.Ems) + return false; +#undef DO_ +} + +void Ems::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.Ems) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_engine_acc_available = 1; + if (this->is_engine_acc_available() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_engine_acc_available(), output); + } + + // bool is_engine_acc_error = 2; + if (this->is_engine_acc_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_engine_acc_error(), output); + } + + // .apollo.canbus.Ems.Type engine_state = 3; + if (this->engine_state() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 3, this->engine_state(), output); + } + + // double max_engine_torq_percent = 4; + if (this->max_engine_torq_percent() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->max_engine_torq_percent(), output); + } + + // double min_engine_torq_percent = 5; + if (this->min_engine_torq_percent() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->min_engine_torq_percent(), output); + } + + // int32 base_engine_torq_constant = 6; + if (this->base_engine_torq_constant() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(6, this->base_engine_torq_constant(), output); + } + + // bool is_engine_speed_error = 7; + if (this->is_engine_speed_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(7, this->is_engine_speed_error(), output); + } + + // double engine_speed = 8; + if (this->engine_speed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(8, this->engine_speed(), output); + } + + // int32 engine_torque = 9; + if (this->engine_torque() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(9, this->engine_torque(), output); + } + + // bool is_over_engine_torque = 10; + if (this->is_over_engine_torque() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(10, this->is_over_engine_torque(), output); + } + + // double engine_rpm = 11; + if (this->engine_rpm() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(11, this->engine_rpm(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.Ems) +} + +::google::protobuf::uint8* Ems::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.Ems) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_engine_acc_available = 1; + if (this->is_engine_acc_available() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_engine_acc_available(), target); + } + + // bool is_engine_acc_error = 2; + if (this->is_engine_acc_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_engine_acc_error(), target); + } + + // .apollo.canbus.Ems.Type engine_state = 3; + if (this->engine_state() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 3, this->engine_state(), target); + } + + // double max_engine_torq_percent = 4; + if (this->max_engine_torq_percent() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->max_engine_torq_percent(), target); + } + + // double min_engine_torq_percent = 5; + if (this->min_engine_torq_percent() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->min_engine_torq_percent(), target); + } + + // int32 base_engine_torq_constant = 6; + if (this->base_engine_torq_constant() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(6, this->base_engine_torq_constant(), target); + } + + // bool is_engine_speed_error = 7; + if (this->is_engine_speed_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(7, this->is_engine_speed_error(), target); + } + + // double engine_speed = 8; + if (this->engine_speed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(8, this->engine_speed(), target); + } + + // int32 engine_torque = 9; + if (this->engine_torque() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(9, this->engine_torque(), target); + } + + // bool is_over_engine_torque = 10; + if (this->is_over_engine_torque() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(10, this->is_over_engine_torque(), target); + } + + // double engine_rpm = 11; + if (this->engine_rpm() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(11, this->engine_rpm(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.Ems) + return target; +} + +size_t Ems::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.Ems) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double max_engine_torq_percent = 4; + if (this->max_engine_torq_percent() != 0) { + total_size += 1 + 8; + } + + // .apollo.canbus.Ems.Type engine_state = 3; + if (this->engine_state() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->engine_state()); + } + + // bool is_engine_acc_available = 1; + if (this->is_engine_acc_available() != 0) { + total_size += 1 + 1; + } + + // bool is_engine_acc_error = 2; + if (this->is_engine_acc_error() != 0) { + total_size += 1 + 1; + } + + // bool is_engine_speed_error = 7; + if (this->is_engine_speed_error() != 0) { + total_size += 1 + 1; + } + + // bool is_over_engine_torque = 10; + if (this->is_over_engine_torque() != 0) { + total_size += 1 + 1; + } + + // double min_engine_torq_percent = 5; + if (this->min_engine_torq_percent() != 0) { + total_size += 1 + 8; + } + + // int32 base_engine_torq_constant = 6; + if (this->base_engine_torq_constant() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->base_engine_torq_constant()); + } + + // int32 engine_torque = 9; + if (this->engine_torque() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->engine_torque()); + } + + // double engine_speed = 8; + if (this->engine_speed() != 0) { + total_size += 1 + 8; + } + + // double engine_rpm = 11; + if (this->engine_rpm() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Ems::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.Ems) + GOOGLE_DCHECK_NE(&from, this); + const Ems* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.Ems) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.Ems) + MergeFrom(*source); + } +} + +void Ems::MergeFrom(const Ems& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.Ems) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.max_engine_torq_percent() != 0) { + set_max_engine_torq_percent(from.max_engine_torq_percent()); + } + if (from.engine_state() != 0) { + set_engine_state(from.engine_state()); + } + if (from.is_engine_acc_available() != 0) { + set_is_engine_acc_available(from.is_engine_acc_available()); + } + if (from.is_engine_acc_error() != 0) { + set_is_engine_acc_error(from.is_engine_acc_error()); + } + if (from.is_engine_speed_error() != 0) { + set_is_engine_speed_error(from.is_engine_speed_error()); + } + if (from.is_over_engine_torque() != 0) { + set_is_over_engine_torque(from.is_over_engine_torque()); + } + if (from.min_engine_torq_percent() != 0) { + set_min_engine_torq_percent(from.min_engine_torq_percent()); + } + if (from.base_engine_torq_constant() != 0) { + set_base_engine_torq_constant(from.base_engine_torq_constant()); + } + if (from.engine_torque() != 0) { + set_engine_torque(from.engine_torque()); + } + if (from.engine_speed() != 0) { + set_engine_speed(from.engine_speed()); + } + if (from.engine_rpm() != 0) { + set_engine_rpm(from.engine_rpm()); + } +} + +void Ems::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.Ems) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Ems::CopyFrom(const Ems& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.Ems) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Ems::IsInitialized() const { + return true; +} + +void Ems::Swap(Ems* other) { + if (other == this) return; + InternalSwap(other); +} +void Ems::InternalSwap(Ems* other) { + using std::swap; + swap(max_engine_torq_percent_, other->max_engine_torq_percent_); + swap(engine_state_, other->engine_state_); + swap(is_engine_acc_available_, other->is_engine_acc_available_); + swap(is_engine_acc_error_, other->is_engine_acc_error_); + swap(is_engine_speed_error_, other->is_engine_speed_error_); + swap(is_over_engine_torque_, other->is_over_engine_torque_); + swap(min_engine_torq_percent_, other->min_engine_torq_percent_); + swap(base_engine_torq_constant_, other->base_engine_torq_constant_); + swap(engine_torque_, other->engine_torque_); + swap(engine_speed_, other->engine_speed_); + swap(engine_rpm_, other->engine_rpm_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Ems::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Gear::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Gear::kIsShiftPositionValidFieldNumber; +const int Gear::kGearStateFieldNumber; +const int Gear::kDriverOverrideFieldNumber; +const int Gear::kGearCmdFieldNumber; +const int Gear::kCanbusFaultFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Gear::Gear() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Gear.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.Gear) +} +Gear::Gear(const Gear& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&gear_state_, &from.gear_state_, + static_cast(reinterpret_cast(&gear_cmd_) - + reinterpret_cast(&gear_state_)) + sizeof(gear_cmd_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.Gear) +} + +void Gear::SharedCtor() { + ::memset(&gear_state_, 0, static_cast( + reinterpret_cast(&gear_cmd_) - + reinterpret_cast(&gear_state_)) + sizeof(gear_cmd_)); +} + +Gear::~Gear() { + // @@protoc_insertion_point(destructor:apollo.canbus.Gear) + SharedDtor(); +} + +void Gear::SharedDtor() { +} + +void Gear::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Gear::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Gear& Gear::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Gear.base); + return *internal_default_instance(); +} + + +void Gear::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.Gear) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&gear_state_, 0, static_cast( + reinterpret_cast(&gear_cmd_) - + reinterpret_cast(&gear_state_)) + sizeof(gear_cmd_)); + _internal_metadata_.Clear(); +} + +bool Gear::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.Gear) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_shift_position_valid = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_shift_position_valid_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Chassis.GearPosition gear_state = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_gear_state(static_cast< ::apollo::canbus::Chassis_GearPosition >(value)); + } else { + goto handle_unusual; + } + break; + } + + // bool driver_override = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &driver_override_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Chassis.GearPosition gear_cmd = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_gear_cmd(static_cast< ::apollo::canbus::Chassis_GearPosition >(value)); + } else { + goto handle_unusual; + } + break; + } + + // bool canbus_fault = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(40u /* 40 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &canbus_fault_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.Gear) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.Gear) + return false; +#undef DO_ +} + +void Gear::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.Gear) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_shift_position_valid = 1; + if (this->is_shift_position_valid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_shift_position_valid(), output); + } + + // .apollo.canbus.Chassis.GearPosition gear_state = 2; + if (this->gear_state() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 2, this->gear_state(), output); + } + + // bool driver_override = 3; + if (this->driver_override() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(3, this->driver_override(), output); + } + + // .apollo.canbus.Chassis.GearPosition gear_cmd = 4; + if (this->gear_cmd() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 4, this->gear_cmd(), output); + } + + // bool canbus_fault = 5; + if (this->canbus_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(5, this->canbus_fault(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.Gear) +} + +::google::protobuf::uint8* Gear::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.Gear) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_shift_position_valid = 1; + if (this->is_shift_position_valid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_shift_position_valid(), target); + } + + // .apollo.canbus.Chassis.GearPosition gear_state = 2; + if (this->gear_state() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 2, this->gear_state(), target); + } + + // bool driver_override = 3; + if (this->driver_override() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(3, this->driver_override(), target); + } + + // .apollo.canbus.Chassis.GearPosition gear_cmd = 4; + if (this->gear_cmd() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 4, this->gear_cmd(), target); + } + + // bool canbus_fault = 5; + if (this->canbus_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(5, this->canbus_fault(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.Gear) + return target; +} + +size_t Gear::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.Gear) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.canbus.Chassis.GearPosition gear_state = 2; + if (this->gear_state() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->gear_state()); + } + + // bool is_shift_position_valid = 1; + if (this->is_shift_position_valid() != 0) { + total_size += 1 + 1; + } + + // bool driver_override = 3; + if (this->driver_override() != 0) { + total_size += 1 + 1; + } + + // bool canbus_fault = 5; + if (this->canbus_fault() != 0) { + total_size += 1 + 1; + } + + // .apollo.canbus.Chassis.GearPosition gear_cmd = 4; + if (this->gear_cmd() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->gear_cmd()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Gear::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.Gear) + GOOGLE_DCHECK_NE(&from, this); + const Gear* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.Gear) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.Gear) + MergeFrom(*source); + } +} + +void Gear::MergeFrom(const Gear& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.Gear) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.gear_state() != 0) { + set_gear_state(from.gear_state()); + } + if (from.is_shift_position_valid() != 0) { + set_is_shift_position_valid(from.is_shift_position_valid()); + } + if (from.driver_override() != 0) { + set_driver_override(from.driver_override()); + } + if (from.canbus_fault() != 0) { + set_canbus_fault(from.canbus_fault()); + } + if (from.gear_cmd() != 0) { + set_gear_cmd(from.gear_cmd()); + } +} + +void Gear::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.Gear) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Gear::CopyFrom(const Gear& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.Gear) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Gear::IsInitialized() const { + return true; +} + +void Gear::Swap(Gear* other) { + if (other == this) return; + InternalSwap(other); +} +void Gear::InternalSwap(Gear* other) { + using std::swap; + swap(gear_state_, other->gear_state_); + swap(is_shift_position_valid_, other->is_shift_position_valid_); + swap(driver_override_, other->driver_override_); + swap(canbus_fault_, other->canbus_fault_); + swap(gear_cmd_, other->gear_cmd_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Gear::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Safety::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Safety::kIsDriverCarDoorCloseFieldNumber; +const int Safety::kIsDriverBuckledFieldNumber; +const int Safety::kEmergencyButtonFieldNumber; +const int Safety::kHasErrorFieldNumber; +const int Safety::kIsMotorInvertorFaultFieldNumber; +const int Safety::kIsSystemFaultFieldNumber; +const int Safety::kIsPowerBatteryFaultFieldNumber; +const int Safety::kIsMotorInvertorOverTemperatureFieldNumber; +const int Safety::kIsSmallBatteryChargeDischargeFaultFieldNumber; +const int Safety::kDrivingModeFieldNumber; +const int Safety::kIsPassengerDoorOpenFieldNumber; +const int Safety::kIsRearleftDoorOpenFieldNumber; +const int Safety::kIsRearrightDoorOpenFieldNumber; +const int Safety::kIsHoodOpenFieldNumber; +const int Safety::kIsTrunkOpenFieldNumber; +const int Safety::kIsPassengerDetectedFieldNumber; +const int Safety::kIsPassengerAirbagEnabledFieldNumber; +const int Safety::kIsPassengerBuckledFieldNumber; +const int Safety::kFrontLeftTirePressFieldNumber; +const int Safety::kFrontRightTirePressFieldNumber; +const int Safety::kRearLeftTirePressFieldNumber; +const int Safety::kRearRightTirePressFieldNumber; +const int Safety::kCarDrivingModeFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Safety::Safety() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Safety.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.Safety) +} +Safety::Safety(const Safety& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&emergency_button_, &from.emergency_button_, + static_cast(reinterpret_cast(&car_driving_mode_) - + reinterpret_cast(&emergency_button_)) + sizeof(car_driving_mode_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.Safety) +} + +void Safety::SharedCtor() { + ::memset(&emergency_button_, 0, static_cast( + reinterpret_cast(&car_driving_mode_) - + reinterpret_cast(&emergency_button_)) + sizeof(car_driving_mode_)); +} + +Safety::~Safety() { + // @@protoc_insertion_point(destructor:apollo.canbus.Safety) + SharedDtor(); +} + +void Safety::SharedDtor() { +} + +void Safety::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Safety::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Safety& Safety::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_Safety.base); + return *internal_default_instance(); +} + + +void Safety::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.Safety) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&emergency_button_, 0, static_cast( + reinterpret_cast(&car_driving_mode_) - + reinterpret_cast(&emergency_button_)) + sizeof(car_driving_mode_)); + _internal_metadata_.Clear(); +} + +bool Safety::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.Safety) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_driver_car_door_close = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_driver_car_door_close_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_driver_buckled = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_driver_buckled_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 emergency_button = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &emergency_button_))); + } else { + goto handle_unusual; + } + break; + } + + // bool has_error = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &has_error_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_motor_invertor_fault = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(40u /* 40 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_motor_invertor_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_system_fault = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(48u /* 48 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_system_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_power_battery_fault = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(56u /* 56 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_power_battery_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_motor_invertor_over_temperature = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(64u /* 64 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_motor_invertor_over_temperature_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_small_battery_charge_discharge_fault = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(72u /* 72 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_small_battery_charge_discharge_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 driving_mode = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(80u /* 80 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &driving_mode_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_passenger_door_open = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(88u /* 88 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_passenger_door_open_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_rearleft_door_open = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(96u /* 96 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_rearleft_door_open_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_rearright_door_open = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(104u /* 104 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_rearright_door_open_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_hood_open = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(112u /* 112 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_hood_open_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_trunk_open = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(120u /* 120 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_trunk_open_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_passenger_detected = 16; + case 16: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(128u /* 128 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_passenger_detected_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_passenger_airbag_enabled = 17; + case 17: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(136u /* 136 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_passenger_airbag_enabled_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_passenger_buckled = 18; + case 18: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(144u /* 144 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_passenger_buckled_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 front_left_tire_press = 19; + case 19: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(152u /* 152 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &front_left_tire_press_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 front_right_tire_press = 20; + case 20: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(160u /* 160 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &front_right_tire_press_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 rear_left_tire_press = 21; + case 21: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(168u /* 168 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &rear_left_tire_press_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 rear_right_tire_press = 22; + case 22: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(176u /* 176 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &rear_right_tire_press_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Chassis.DrivingMode car_driving_mode = 23; + case 23: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(184u /* 184 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_car_driving_mode(static_cast< ::apollo::canbus::Chassis_DrivingMode >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.Safety) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.Safety) + return false; +#undef DO_ +} + +void Safety::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.Safety) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_driver_car_door_close = 1; + if (this->is_driver_car_door_close() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_driver_car_door_close(), output); + } + + // bool is_driver_buckled = 2; + if (this->is_driver_buckled() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_driver_buckled(), output); + } + + // int32 emergency_button = 3; + if (this->emergency_button() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(3, this->emergency_button(), output); + } + + // bool has_error = 4; + if (this->has_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(4, this->has_error(), output); + } + + // bool is_motor_invertor_fault = 5; + if (this->is_motor_invertor_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(5, this->is_motor_invertor_fault(), output); + } + + // bool is_system_fault = 6; + if (this->is_system_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(6, this->is_system_fault(), output); + } + + // bool is_power_battery_fault = 7; + if (this->is_power_battery_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(7, this->is_power_battery_fault(), output); + } + + // bool is_motor_invertor_over_temperature = 8; + if (this->is_motor_invertor_over_temperature() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(8, this->is_motor_invertor_over_temperature(), output); + } + + // bool is_small_battery_charge_discharge_fault = 9; + if (this->is_small_battery_charge_discharge_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(9, this->is_small_battery_charge_discharge_fault(), output); + } + + // int32 driving_mode = 10; + if (this->driving_mode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(10, this->driving_mode(), output); + } + + // bool is_passenger_door_open = 11; + if (this->is_passenger_door_open() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(11, this->is_passenger_door_open(), output); + } + + // bool is_rearleft_door_open = 12; + if (this->is_rearleft_door_open() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(12, this->is_rearleft_door_open(), output); + } + + // bool is_rearright_door_open = 13; + if (this->is_rearright_door_open() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(13, this->is_rearright_door_open(), output); + } + + // bool is_hood_open = 14; + if (this->is_hood_open() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(14, this->is_hood_open(), output); + } + + // bool is_trunk_open = 15; + if (this->is_trunk_open() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(15, this->is_trunk_open(), output); + } + + // bool is_passenger_detected = 16; + if (this->is_passenger_detected() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(16, this->is_passenger_detected(), output); + } + + // bool is_passenger_airbag_enabled = 17; + if (this->is_passenger_airbag_enabled() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(17, this->is_passenger_airbag_enabled(), output); + } + + // bool is_passenger_buckled = 18; + if (this->is_passenger_buckled() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(18, this->is_passenger_buckled(), output); + } + + // int32 front_left_tire_press = 19; + if (this->front_left_tire_press() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(19, this->front_left_tire_press(), output); + } + + // int32 front_right_tire_press = 20; + if (this->front_right_tire_press() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(20, this->front_right_tire_press(), output); + } + + // int32 rear_left_tire_press = 21; + if (this->rear_left_tire_press() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(21, this->rear_left_tire_press(), output); + } + + // int32 rear_right_tire_press = 22; + if (this->rear_right_tire_press() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(22, this->rear_right_tire_press(), output); + } + + // .apollo.canbus.Chassis.DrivingMode car_driving_mode = 23; + if (this->car_driving_mode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 23, this->car_driving_mode(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.Safety) +} + +::google::protobuf::uint8* Safety::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.Safety) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_driver_car_door_close = 1; + if (this->is_driver_car_door_close() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_driver_car_door_close(), target); + } + + // bool is_driver_buckled = 2; + if (this->is_driver_buckled() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_driver_buckled(), target); + } + + // int32 emergency_button = 3; + if (this->emergency_button() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(3, this->emergency_button(), target); + } + + // bool has_error = 4; + if (this->has_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(4, this->has_error(), target); + } + + // bool is_motor_invertor_fault = 5; + if (this->is_motor_invertor_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(5, this->is_motor_invertor_fault(), target); + } + + // bool is_system_fault = 6; + if (this->is_system_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(6, this->is_system_fault(), target); + } + + // bool is_power_battery_fault = 7; + if (this->is_power_battery_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(7, this->is_power_battery_fault(), target); + } + + // bool is_motor_invertor_over_temperature = 8; + if (this->is_motor_invertor_over_temperature() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(8, this->is_motor_invertor_over_temperature(), target); + } + + // bool is_small_battery_charge_discharge_fault = 9; + if (this->is_small_battery_charge_discharge_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(9, this->is_small_battery_charge_discharge_fault(), target); + } + + // int32 driving_mode = 10; + if (this->driving_mode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(10, this->driving_mode(), target); + } + + // bool is_passenger_door_open = 11; + if (this->is_passenger_door_open() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(11, this->is_passenger_door_open(), target); + } + + // bool is_rearleft_door_open = 12; + if (this->is_rearleft_door_open() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(12, this->is_rearleft_door_open(), target); + } + + // bool is_rearright_door_open = 13; + if (this->is_rearright_door_open() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(13, this->is_rearright_door_open(), target); + } + + // bool is_hood_open = 14; + if (this->is_hood_open() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(14, this->is_hood_open(), target); + } + + // bool is_trunk_open = 15; + if (this->is_trunk_open() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(15, this->is_trunk_open(), target); + } + + // bool is_passenger_detected = 16; + if (this->is_passenger_detected() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(16, this->is_passenger_detected(), target); + } + + // bool is_passenger_airbag_enabled = 17; + if (this->is_passenger_airbag_enabled() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(17, this->is_passenger_airbag_enabled(), target); + } + + // bool is_passenger_buckled = 18; + if (this->is_passenger_buckled() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(18, this->is_passenger_buckled(), target); + } + + // int32 front_left_tire_press = 19; + if (this->front_left_tire_press() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(19, this->front_left_tire_press(), target); + } + + // int32 front_right_tire_press = 20; + if (this->front_right_tire_press() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(20, this->front_right_tire_press(), target); + } + + // int32 rear_left_tire_press = 21; + if (this->rear_left_tire_press() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(21, this->rear_left_tire_press(), target); + } + + // int32 rear_right_tire_press = 22; + if (this->rear_right_tire_press() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(22, this->rear_right_tire_press(), target); + } + + // .apollo.canbus.Chassis.DrivingMode car_driving_mode = 23; + if (this->car_driving_mode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 23, this->car_driving_mode(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.Safety) + return target; +} + +size_t Safety::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.Safety) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // int32 emergency_button = 3; + if (this->emergency_button() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->emergency_button()); + } + + // bool is_driver_car_door_close = 1; + if (this->is_driver_car_door_close() != 0) { + total_size += 1 + 1; + } + + // bool is_driver_buckled = 2; + if (this->is_driver_buckled() != 0) { + total_size += 1 + 1; + } + + // bool has_error = 4; + if (this->has_error() != 0) { + total_size += 1 + 1; + } + + // bool is_motor_invertor_fault = 5; + if (this->is_motor_invertor_fault() != 0) { + total_size += 1 + 1; + } + + // bool is_system_fault = 6; + if (this->is_system_fault() != 0) { + total_size += 1 + 1; + } + + // bool is_power_battery_fault = 7; + if (this->is_power_battery_fault() != 0) { + total_size += 1 + 1; + } + + // bool is_motor_invertor_over_temperature = 8; + if (this->is_motor_invertor_over_temperature() != 0) { + total_size += 1 + 1; + } + + // bool is_small_battery_charge_discharge_fault = 9; + if (this->is_small_battery_charge_discharge_fault() != 0) { + total_size += 1 + 1; + } + + // int32 driving_mode = 10; + if (this->driving_mode() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->driving_mode()); + } + + // bool is_passenger_door_open = 11; + if (this->is_passenger_door_open() != 0) { + total_size += 1 + 1; + } + + // bool is_rearleft_door_open = 12; + if (this->is_rearleft_door_open() != 0) { + total_size += 1 + 1; + } + + // bool is_rearright_door_open = 13; + if (this->is_rearright_door_open() != 0) { + total_size += 1 + 1; + } + + // bool is_hood_open = 14; + if (this->is_hood_open() != 0) { + total_size += 1 + 1; + } + + // bool is_trunk_open = 15; + if (this->is_trunk_open() != 0) { + total_size += 1 + 1; + } + + // bool is_passenger_detected = 16; + if (this->is_passenger_detected() != 0) { + total_size += 2 + 1; + } + + // bool is_passenger_airbag_enabled = 17; + if (this->is_passenger_airbag_enabled() != 0) { + total_size += 2 + 1; + } + + // bool is_passenger_buckled = 18; + if (this->is_passenger_buckled() != 0) { + total_size += 2 + 1; + } + + // int32 front_left_tire_press = 19; + if (this->front_left_tire_press() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->front_left_tire_press()); + } + + // int32 front_right_tire_press = 20; + if (this->front_right_tire_press() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->front_right_tire_press()); + } + + // int32 rear_left_tire_press = 21; + if (this->rear_left_tire_press() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->rear_left_tire_press()); + } + + // int32 rear_right_tire_press = 22; + if (this->rear_right_tire_press() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->rear_right_tire_press()); + } + + // .apollo.canbus.Chassis.DrivingMode car_driving_mode = 23; + if (this->car_driving_mode() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->car_driving_mode()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Safety::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.Safety) + GOOGLE_DCHECK_NE(&from, this); + const Safety* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.Safety) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.Safety) + MergeFrom(*source); + } +} + +void Safety::MergeFrom(const Safety& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.Safety) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.emergency_button() != 0) { + set_emergency_button(from.emergency_button()); + } + if (from.is_driver_car_door_close() != 0) { + set_is_driver_car_door_close(from.is_driver_car_door_close()); + } + if (from.is_driver_buckled() != 0) { + set_is_driver_buckled(from.is_driver_buckled()); + } + if (from.has_error() != 0) { + set_has_error(from.has_error()); + } + if (from.is_motor_invertor_fault() != 0) { + set_is_motor_invertor_fault(from.is_motor_invertor_fault()); + } + if (from.is_system_fault() != 0) { + set_is_system_fault(from.is_system_fault()); + } + if (from.is_power_battery_fault() != 0) { + set_is_power_battery_fault(from.is_power_battery_fault()); + } + if (from.is_motor_invertor_over_temperature() != 0) { + set_is_motor_invertor_over_temperature(from.is_motor_invertor_over_temperature()); + } + if (from.is_small_battery_charge_discharge_fault() != 0) { + set_is_small_battery_charge_discharge_fault(from.is_small_battery_charge_discharge_fault()); + } + if (from.driving_mode() != 0) { + set_driving_mode(from.driving_mode()); + } + if (from.is_passenger_door_open() != 0) { + set_is_passenger_door_open(from.is_passenger_door_open()); + } + if (from.is_rearleft_door_open() != 0) { + set_is_rearleft_door_open(from.is_rearleft_door_open()); + } + if (from.is_rearright_door_open() != 0) { + set_is_rearright_door_open(from.is_rearright_door_open()); + } + if (from.is_hood_open() != 0) { + set_is_hood_open(from.is_hood_open()); + } + if (from.is_trunk_open() != 0) { + set_is_trunk_open(from.is_trunk_open()); + } + if (from.is_passenger_detected() != 0) { + set_is_passenger_detected(from.is_passenger_detected()); + } + if (from.is_passenger_airbag_enabled() != 0) { + set_is_passenger_airbag_enabled(from.is_passenger_airbag_enabled()); + } + if (from.is_passenger_buckled() != 0) { + set_is_passenger_buckled(from.is_passenger_buckled()); + } + if (from.front_left_tire_press() != 0) { + set_front_left_tire_press(from.front_left_tire_press()); + } + if (from.front_right_tire_press() != 0) { + set_front_right_tire_press(from.front_right_tire_press()); + } + if (from.rear_left_tire_press() != 0) { + set_rear_left_tire_press(from.rear_left_tire_press()); + } + if (from.rear_right_tire_press() != 0) { + set_rear_right_tire_press(from.rear_right_tire_press()); + } + if (from.car_driving_mode() != 0) { + set_car_driving_mode(from.car_driving_mode()); + } +} + +void Safety::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.Safety) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Safety::CopyFrom(const Safety& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.Safety) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Safety::IsInitialized() const { + return true; +} + +void Safety::Swap(Safety* other) { + if (other == this) return; + InternalSwap(other); +} +void Safety::InternalSwap(Safety* other) { + using std::swap; + swap(emergency_button_, other->emergency_button_); + swap(is_driver_car_door_close_, other->is_driver_car_door_close_); + swap(is_driver_buckled_, other->is_driver_buckled_); + swap(has_error_, other->has_error_); + swap(is_motor_invertor_fault_, other->is_motor_invertor_fault_); + swap(is_system_fault_, other->is_system_fault_); + swap(is_power_battery_fault_, other->is_power_battery_fault_); + swap(is_motor_invertor_over_temperature_, other->is_motor_invertor_over_temperature_); + swap(is_small_battery_charge_discharge_fault_, other->is_small_battery_charge_discharge_fault_); + swap(driving_mode_, other->driving_mode_); + swap(is_passenger_door_open_, other->is_passenger_door_open_); + swap(is_rearleft_door_open_, other->is_rearleft_door_open_); + swap(is_rearright_door_open_, other->is_rearright_door_open_); + swap(is_hood_open_, other->is_hood_open_); + swap(is_trunk_open_, other->is_trunk_open_); + swap(is_passenger_detected_, other->is_passenger_detected_); + swap(is_passenger_airbag_enabled_, other->is_passenger_airbag_enabled_); + swap(is_passenger_buckled_, other->is_passenger_buckled_); + swap(front_left_tire_press_, other->front_left_tire_press_); + swap(front_right_tire_press_, other->front_right_tire_press_); + swap(rear_left_tire_press_, other->rear_left_tire_press_); + swap(rear_right_tire_press_, other->rear_right_tire_press_); + swap(car_driving_mode_, other->car_driving_mode_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Safety::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void BasicInfo::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int BasicInfo::kIsAutoModeFieldNumber; +const int BasicInfo::kPowerStateFieldNumber; +const int BasicInfo::kIsAirBagDeployedFieldNumber; +const int BasicInfo::kOdoMeterFieldNumber; +const int BasicInfo::kDriveRangeFieldNumber; +const int BasicInfo::kIsSystemErrorFieldNumber; +const int BasicInfo::kIsHumanInterruptFieldNumber; +const int BasicInfo::kAccOnButtonFieldNumber; +const int BasicInfo::kAccOffButtonFieldNumber; +const int BasicInfo::kAccResButtonFieldNumber; +const int BasicInfo::kAccCancelButtonFieldNumber; +const int BasicInfo::kAccOnOffButtonFieldNumber; +const int BasicInfo::kAccResCancelButtonFieldNumber; +const int BasicInfo::kAccIncSpdButtonFieldNumber; +const int BasicInfo::kAccDecSpdButtonFieldNumber; +const int BasicInfo::kAccIncGapButtonFieldNumber; +const int BasicInfo::kAccDecGapButtonFieldNumber; +const int BasicInfo::kLkaButtonFieldNumber; +const int BasicInfo::kCanbusFaultFieldNumber; +const int BasicInfo::kLatitudeFieldNumber; +const int BasicInfo::kLongitudeFieldNumber; +const int BasicInfo::kGpsValidFieldNumber; +const int BasicInfo::kYearFieldNumber; +const int BasicInfo::kMonthFieldNumber; +const int BasicInfo::kDayFieldNumber; +const int BasicInfo::kHoursFieldNumber; +const int BasicInfo::kMinutesFieldNumber; +const int BasicInfo::kSecondsFieldNumber; +const int BasicInfo::kCompassDirectionFieldNumber; +const int BasicInfo::kPdopFieldNumber; +const int BasicInfo::kIsGpsFaultFieldNumber; +const int BasicInfo::kIsInferredFieldNumber; +const int BasicInfo::kAltitudeFieldNumber; +const int BasicInfo::kHeadingFieldNumber; +const int BasicInfo::kHdopFieldNumber; +const int BasicInfo::kVdopFieldNumber; +const int BasicInfo::kQualityFieldNumber; +const int BasicInfo::kNumSatellitesFieldNumber; +const int BasicInfo::kGpsSpeedFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +BasicInfo::BasicInfo() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_BasicInfo.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.canbus.BasicInfo) +} +BasicInfo::BasicInfo(const BasicInfo& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&power_state_, &from.power_state_, + static_cast(reinterpret_cast(&gps_speed_) - + reinterpret_cast(&power_state_)) + sizeof(gps_speed_)); + // @@protoc_insertion_point(copy_constructor:apollo.canbus.BasicInfo) +} + +void BasicInfo::SharedCtor() { + ::memset(&power_state_, 0, static_cast( + reinterpret_cast(&gps_speed_) - + reinterpret_cast(&power_state_)) + sizeof(gps_speed_)); +} + +BasicInfo::~BasicInfo() { + // @@protoc_insertion_point(destructor:apollo.canbus.BasicInfo) + SharedDtor(); +} + +void BasicInfo::SharedDtor() { +} + +void BasicInfo::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* BasicInfo::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const BasicInfo& BasicInfo::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::scc_info_BasicInfo.base); + return *internal_default_instance(); +} + + +void BasicInfo::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.canbus.BasicInfo) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&power_state_, 0, static_cast( + reinterpret_cast(&gps_speed_) - + reinterpret_cast(&power_state_)) + sizeof(gps_speed_)); + _internal_metadata_.Clear(); +} + +bool BasicInfo::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.canbus.BasicInfo) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_auto_mode = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_auto_mode_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.BasicInfo.Type power_state = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_power_state(static_cast< ::apollo::canbus::BasicInfo_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // bool is_air_bag_deployed = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_air_bag_deployed_))); + } else { + goto handle_unusual; + } + break; + } + + // double odo_meter = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &odo_meter_))); + } else { + goto handle_unusual; + } + break; + } + + // double drive_range = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &drive_range_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_system_error = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(48u /* 48 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_system_error_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_human_interrupt = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(56u /* 56 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_human_interrupt_))); + } else { + goto handle_unusual; + } + break; + } + + // bool acc_on_button = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(64u /* 64 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &acc_on_button_))); + } else { + goto handle_unusual; + } + break; + } + + // bool acc_off_button = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(72u /* 72 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &acc_off_button_))); + } else { + goto handle_unusual; + } + break; + } + + // bool acc_res_button = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(80u /* 80 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &acc_res_button_))); + } else { + goto handle_unusual; + } + break; + } + + // bool acc_cancel_button = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(88u /* 88 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &acc_cancel_button_))); + } else { + goto handle_unusual; + } + break; + } + + // bool acc_on_off_button = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(96u /* 96 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &acc_on_off_button_))); + } else { + goto handle_unusual; + } + break; + } + + // bool acc_res_cancel_button = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(104u /* 104 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &acc_res_cancel_button_))); + } else { + goto handle_unusual; + } + break; + } + + // bool acc_inc_spd_button = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(112u /* 112 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &acc_inc_spd_button_))); + } else { + goto handle_unusual; + } + break; + } + + // bool acc_dec_spd_button = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(120u /* 120 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &acc_dec_spd_button_))); + } else { + goto handle_unusual; + } + break; + } + + // bool acc_inc_gap_button = 16; + case 16: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(128u /* 128 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &acc_inc_gap_button_))); + } else { + goto handle_unusual; + } + break; + } + + // bool acc_dec_gap_button = 17; + case 17: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(136u /* 136 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &acc_dec_gap_button_))); + } else { + goto handle_unusual; + } + break; + } + + // bool lka_button = 18; + case 18: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(144u /* 144 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &lka_button_))); + } else { + goto handle_unusual; + } + break; + } + + // bool canbus_fault = 19; + case 19: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(152u /* 152 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &canbus_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // double latitude = 20; + case 20: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(161u /* 161 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &latitude_))); + } else { + goto handle_unusual; + } + break; + } + + // double longitude = 21; + case 21: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(169u /* 169 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &longitude_))); + } else { + goto handle_unusual; + } + break; + } + + // bool gps_valid = 22; + case 22: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(176u /* 176 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &gps_valid_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 year = 23; + case 23: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(184u /* 184 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &year_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 month = 24; + case 24: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(192u /* 192 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &month_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 day = 25; + case 25: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(200u /* 200 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &day_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 hours = 26; + case 26: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(208u /* 208 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &hours_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 minutes = 27; + case 27: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(216u /* 216 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &minutes_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 seconds = 28; + case 28: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(224u /* 224 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &seconds_))); + } else { + goto handle_unusual; + } + break; + } + + // double compass_direction = 29; + case 29: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(233u /* 233 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &compass_direction_))); + } else { + goto handle_unusual; + } + break; + } + + // double pdop = 30; + case 30: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(241u /* 241 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &pdop_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_gps_fault = 31; + case 31: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(248u /* 248 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_gps_fault_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_inferred = 32; + case 32: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(0u /* 256 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_inferred_))); + } else { + goto handle_unusual; + } + break; + } + + // double altitude = 33; + case 33: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 265 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &altitude_))); + } else { + goto handle_unusual; + } + break; + } + + // double heading = 34; + case 34: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 273 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &heading_))); + } else { + goto handle_unusual; + } + break; + } + + // double hdop = 35; + case 35: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 281 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &hdop_))); + } else { + goto handle_unusual; + } + break; + } + + // double vdop = 36; + case 36: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 289 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &vdop_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.BasicInfo.GpsQuality quality = 37; + case 37: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(40u /* 296 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_quality(static_cast< ::apollo::canbus::BasicInfo_GpsQuality >(value)); + } else { + goto handle_unusual; + } + break; + } + + // int32 num_satellites = 38; + case 38: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(48u /* 304 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &num_satellites_))); + } else { + goto handle_unusual; + } + break; + } + + // double gps_speed = 39; + case 39: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 313 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &gps_speed_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.canbus.BasicInfo) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.canbus.BasicInfo) + return false; +#undef DO_ +} + +void BasicInfo::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.canbus.BasicInfo) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_auto_mode = 1; + if (this->is_auto_mode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_auto_mode(), output); + } + + // .apollo.canbus.BasicInfo.Type power_state = 2; + if (this->power_state() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 2, this->power_state(), output); + } + + // bool is_air_bag_deployed = 3; + if (this->is_air_bag_deployed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(3, this->is_air_bag_deployed(), output); + } + + // double odo_meter = 4; + if (this->odo_meter() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->odo_meter(), output); + } + + // double drive_range = 5; + if (this->drive_range() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->drive_range(), output); + } + + // bool is_system_error = 6; + if (this->is_system_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(6, this->is_system_error(), output); + } + + // bool is_human_interrupt = 7; + if (this->is_human_interrupt() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(7, this->is_human_interrupt(), output); + } + + // bool acc_on_button = 8; + if (this->acc_on_button() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(8, this->acc_on_button(), output); + } + + // bool acc_off_button = 9; + if (this->acc_off_button() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(9, this->acc_off_button(), output); + } + + // bool acc_res_button = 10; + if (this->acc_res_button() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(10, this->acc_res_button(), output); + } + + // bool acc_cancel_button = 11; + if (this->acc_cancel_button() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(11, this->acc_cancel_button(), output); + } + + // bool acc_on_off_button = 12; + if (this->acc_on_off_button() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(12, this->acc_on_off_button(), output); + } + + // bool acc_res_cancel_button = 13; + if (this->acc_res_cancel_button() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(13, this->acc_res_cancel_button(), output); + } + + // bool acc_inc_spd_button = 14; + if (this->acc_inc_spd_button() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(14, this->acc_inc_spd_button(), output); + } + + // bool acc_dec_spd_button = 15; + if (this->acc_dec_spd_button() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(15, this->acc_dec_spd_button(), output); + } + + // bool acc_inc_gap_button = 16; + if (this->acc_inc_gap_button() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(16, this->acc_inc_gap_button(), output); + } + + // bool acc_dec_gap_button = 17; + if (this->acc_dec_gap_button() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(17, this->acc_dec_gap_button(), output); + } + + // bool lka_button = 18; + if (this->lka_button() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(18, this->lka_button(), output); + } + + // bool canbus_fault = 19; + if (this->canbus_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(19, this->canbus_fault(), output); + } + + // double latitude = 20; + if (this->latitude() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(20, this->latitude(), output); + } + + // double longitude = 21; + if (this->longitude() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(21, this->longitude(), output); + } + + // bool gps_valid = 22; + if (this->gps_valid() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(22, this->gps_valid(), output); + } + + // int32 year = 23; + if (this->year() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(23, this->year(), output); + } + + // int32 month = 24; + if (this->month() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(24, this->month(), output); + } + + // int32 day = 25; + if (this->day() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(25, this->day(), output); + } + + // int32 hours = 26; + if (this->hours() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(26, this->hours(), output); + } + + // int32 minutes = 27; + if (this->minutes() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(27, this->minutes(), output); + } + + // int32 seconds = 28; + if (this->seconds() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(28, this->seconds(), output); + } + + // double compass_direction = 29; + if (this->compass_direction() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(29, this->compass_direction(), output); + } + + // double pdop = 30; + if (this->pdop() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(30, this->pdop(), output); + } + + // bool is_gps_fault = 31; + if (this->is_gps_fault() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(31, this->is_gps_fault(), output); + } + + // bool is_inferred = 32; + if (this->is_inferred() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(32, this->is_inferred(), output); + } + + // double altitude = 33; + if (this->altitude() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(33, this->altitude(), output); + } + + // double heading = 34; + if (this->heading() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(34, this->heading(), output); + } + + // double hdop = 35; + if (this->hdop() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(35, this->hdop(), output); + } + + // double vdop = 36; + if (this->vdop() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(36, this->vdop(), output); + } + + // .apollo.canbus.BasicInfo.GpsQuality quality = 37; + if (this->quality() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 37, this->quality(), output); + } + + // int32 num_satellites = 38; + if (this->num_satellites() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(38, this->num_satellites(), output); + } + + // double gps_speed = 39; + if (this->gps_speed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(39, this->gps_speed(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.canbus.BasicInfo) +} + +::google::protobuf::uint8* BasicInfo::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.canbus.BasicInfo) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_auto_mode = 1; + if (this->is_auto_mode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_auto_mode(), target); + } + + // .apollo.canbus.BasicInfo.Type power_state = 2; + if (this->power_state() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 2, this->power_state(), target); + } + + // bool is_air_bag_deployed = 3; + if (this->is_air_bag_deployed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(3, this->is_air_bag_deployed(), target); + } + + // double odo_meter = 4; + if (this->odo_meter() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->odo_meter(), target); + } + + // double drive_range = 5; + if (this->drive_range() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->drive_range(), target); + } + + // bool is_system_error = 6; + if (this->is_system_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(6, this->is_system_error(), target); + } + + // bool is_human_interrupt = 7; + if (this->is_human_interrupt() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(7, this->is_human_interrupt(), target); + } + + // bool acc_on_button = 8; + if (this->acc_on_button() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(8, this->acc_on_button(), target); + } + + // bool acc_off_button = 9; + if (this->acc_off_button() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(9, this->acc_off_button(), target); + } + + // bool acc_res_button = 10; + if (this->acc_res_button() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(10, this->acc_res_button(), target); + } + + // bool acc_cancel_button = 11; + if (this->acc_cancel_button() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(11, this->acc_cancel_button(), target); + } + + // bool acc_on_off_button = 12; + if (this->acc_on_off_button() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(12, this->acc_on_off_button(), target); + } + + // bool acc_res_cancel_button = 13; + if (this->acc_res_cancel_button() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(13, this->acc_res_cancel_button(), target); + } + + // bool acc_inc_spd_button = 14; + if (this->acc_inc_spd_button() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(14, this->acc_inc_spd_button(), target); + } + + // bool acc_dec_spd_button = 15; + if (this->acc_dec_spd_button() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(15, this->acc_dec_spd_button(), target); + } + + // bool acc_inc_gap_button = 16; + if (this->acc_inc_gap_button() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(16, this->acc_inc_gap_button(), target); + } + + // bool acc_dec_gap_button = 17; + if (this->acc_dec_gap_button() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(17, this->acc_dec_gap_button(), target); + } + + // bool lka_button = 18; + if (this->lka_button() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(18, this->lka_button(), target); + } + + // bool canbus_fault = 19; + if (this->canbus_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(19, this->canbus_fault(), target); + } + + // double latitude = 20; + if (this->latitude() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(20, this->latitude(), target); + } + + // double longitude = 21; + if (this->longitude() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(21, this->longitude(), target); + } + + // bool gps_valid = 22; + if (this->gps_valid() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(22, this->gps_valid(), target); + } + + // int32 year = 23; + if (this->year() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(23, this->year(), target); + } + + // int32 month = 24; + if (this->month() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(24, this->month(), target); + } + + // int32 day = 25; + if (this->day() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(25, this->day(), target); + } + + // int32 hours = 26; + if (this->hours() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(26, this->hours(), target); + } + + // int32 minutes = 27; + if (this->minutes() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(27, this->minutes(), target); + } + + // int32 seconds = 28; + if (this->seconds() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(28, this->seconds(), target); + } + + // double compass_direction = 29; + if (this->compass_direction() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(29, this->compass_direction(), target); + } + + // double pdop = 30; + if (this->pdop() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(30, this->pdop(), target); + } + + // bool is_gps_fault = 31; + if (this->is_gps_fault() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(31, this->is_gps_fault(), target); + } + + // bool is_inferred = 32; + if (this->is_inferred() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(32, this->is_inferred(), target); + } + + // double altitude = 33; + if (this->altitude() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(33, this->altitude(), target); + } + + // double heading = 34; + if (this->heading() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(34, this->heading(), target); + } + + // double hdop = 35; + if (this->hdop() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(35, this->hdop(), target); + } + + // double vdop = 36; + if (this->vdop() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(36, this->vdop(), target); + } + + // .apollo.canbus.BasicInfo.GpsQuality quality = 37; + if (this->quality() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 37, this->quality(), target); + } + + // int32 num_satellites = 38; + if (this->num_satellites() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(38, this->num_satellites(), target); + } + + // double gps_speed = 39; + if (this->gps_speed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(39, this->gps_speed(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.canbus.BasicInfo) + return target; +} + +size_t BasicInfo::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.canbus.BasicInfo) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.canbus.BasicInfo.Type power_state = 2; + if (this->power_state() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->power_state()); + } + + // bool is_auto_mode = 1; + if (this->is_auto_mode() != 0) { + total_size += 1 + 1; + } + + // bool is_air_bag_deployed = 3; + if (this->is_air_bag_deployed() != 0) { + total_size += 1 + 1; + } + + // bool is_system_error = 6; + if (this->is_system_error() != 0) { + total_size += 1 + 1; + } + + // bool is_human_interrupt = 7; + if (this->is_human_interrupt() != 0) { + total_size += 1 + 1; + } + + // double odo_meter = 4; + if (this->odo_meter() != 0) { + total_size += 1 + 8; + } + + // double drive_range = 5; + if (this->drive_range() != 0) { + total_size += 1 + 8; + } + + // bool acc_on_button = 8; + if (this->acc_on_button() != 0) { + total_size += 1 + 1; + } + + // bool acc_off_button = 9; + if (this->acc_off_button() != 0) { + total_size += 1 + 1; + } + + // bool acc_res_button = 10; + if (this->acc_res_button() != 0) { + total_size += 1 + 1; + } + + // bool acc_cancel_button = 11; + if (this->acc_cancel_button() != 0) { + total_size += 1 + 1; + } + + // bool acc_on_off_button = 12; + if (this->acc_on_off_button() != 0) { + total_size += 1 + 1; + } + + // bool acc_res_cancel_button = 13; + if (this->acc_res_cancel_button() != 0) { + total_size += 1 + 1; + } + + // bool acc_inc_spd_button = 14; + if (this->acc_inc_spd_button() != 0) { + total_size += 1 + 1; + } + + // bool acc_dec_spd_button = 15; + if (this->acc_dec_spd_button() != 0) { + total_size += 1 + 1; + } + + // bool acc_inc_gap_button = 16; + if (this->acc_inc_gap_button() != 0) { + total_size += 2 + 1; + } + + // bool acc_dec_gap_button = 17; + if (this->acc_dec_gap_button() != 0) { + total_size += 2 + 1; + } + + // bool lka_button = 18; + if (this->lka_button() != 0) { + total_size += 2 + 1; + } + + // bool canbus_fault = 19; + if (this->canbus_fault() != 0) { + total_size += 2 + 1; + } + + // int32 year = 23; + if (this->year() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->year()); + } + + // double latitude = 20; + if (this->latitude() != 0) { + total_size += 2 + 8; + } + + // double longitude = 21; + if (this->longitude() != 0) { + total_size += 2 + 8; + } + + // int32 month = 24; + if (this->month() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->month()); + } + + // int32 day = 25; + if (this->day() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->day()); + } + + // int32 hours = 26; + if (this->hours() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->hours()); + } + + // int32 minutes = 27; + if (this->minutes() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->minutes()); + } + + // int32 seconds = 28; + if (this->seconds() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->seconds()); + } + + // bool gps_valid = 22; + if (this->gps_valid() != 0) { + total_size += 2 + 1; + } + + // bool is_gps_fault = 31; + if (this->is_gps_fault() != 0) { + total_size += 2 + 1; + } + + // bool is_inferred = 32; + if (this->is_inferred() != 0) { + total_size += 2 + 1; + } + + // double compass_direction = 29; + if (this->compass_direction() != 0) { + total_size += 2 + 8; + } + + // double pdop = 30; + if (this->pdop() != 0) { + total_size += 2 + 8; + } + + // double altitude = 33; + if (this->altitude() != 0) { + total_size += 2 + 8; + } + + // double heading = 34; + if (this->heading() != 0) { + total_size += 2 + 8; + } + + // double hdop = 35; + if (this->hdop() != 0) { + total_size += 2 + 8; + } + + // double vdop = 36; + if (this->vdop() != 0) { + total_size += 2 + 8; + } + + // .apollo.canbus.BasicInfo.GpsQuality quality = 37; + if (this->quality() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->quality()); + } + + // int32 num_satellites = 38; + if (this->num_satellites() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->num_satellites()); + } + + // double gps_speed = 39; + if (this->gps_speed() != 0) { + total_size += 2 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void BasicInfo::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.canbus.BasicInfo) + GOOGLE_DCHECK_NE(&from, this); + const BasicInfo* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.canbus.BasicInfo) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.canbus.BasicInfo) + MergeFrom(*source); + } +} + +void BasicInfo::MergeFrom(const BasicInfo& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.canbus.BasicInfo) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.power_state() != 0) { + set_power_state(from.power_state()); + } + if (from.is_auto_mode() != 0) { + set_is_auto_mode(from.is_auto_mode()); + } + if (from.is_air_bag_deployed() != 0) { + set_is_air_bag_deployed(from.is_air_bag_deployed()); + } + if (from.is_system_error() != 0) { + set_is_system_error(from.is_system_error()); + } + if (from.is_human_interrupt() != 0) { + set_is_human_interrupt(from.is_human_interrupt()); + } + if (from.odo_meter() != 0) { + set_odo_meter(from.odo_meter()); + } + if (from.drive_range() != 0) { + set_drive_range(from.drive_range()); + } + if (from.acc_on_button() != 0) { + set_acc_on_button(from.acc_on_button()); + } + if (from.acc_off_button() != 0) { + set_acc_off_button(from.acc_off_button()); + } + if (from.acc_res_button() != 0) { + set_acc_res_button(from.acc_res_button()); + } + if (from.acc_cancel_button() != 0) { + set_acc_cancel_button(from.acc_cancel_button()); + } + if (from.acc_on_off_button() != 0) { + set_acc_on_off_button(from.acc_on_off_button()); + } + if (from.acc_res_cancel_button() != 0) { + set_acc_res_cancel_button(from.acc_res_cancel_button()); + } + if (from.acc_inc_spd_button() != 0) { + set_acc_inc_spd_button(from.acc_inc_spd_button()); + } + if (from.acc_dec_spd_button() != 0) { + set_acc_dec_spd_button(from.acc_dec_spd_button()); + } + if (from.acc_inc_gap_button() != 0) { + set_acc_inc_gap_button(from.acc_inc_gap_button()); + } + if (from.acc_dec_gap_button() != 0) { + set_acc_dec_gap_button(from.acc_dec_gap_button()); + } + if (from.lka_button() != 0) { + set_lka_button(from.lka_button()); + } + if (from.canbus_fault() != 0) { + set_canbus_fault(from.canbus_fault()); + } + if (from.year() != 0) { + set_year(from.year()); + } + if (from.latitude() != 0) { + set_latitude(from.latitude()); + } + if (from.longitude() != 0) { + set_longitude(from.longitude()); + } + if (from.month() != 0) { + set_month(from.month()); + } + if (from.day() != 0) { + set_day(from.day()); + } + if (from.hours() != 0) { + set_hours(from.hours()); + } + if (from.minutes() != 0) { + set_minutes(from.minutes()); + } + if (from.seconds() != 0) { + set_seconds(from.seconds()); + } + if (from.gps_valid() != 0) { + set_gps_valid(from.gps_valid()); + } + if (from.is_gps_fault() != 0) { + set_is_gps_fault(from.is_gps_fault()); + } + if (from.is_inferred() != 0) { + set_is_inferred(from.is_inferred()); + } + if (from.compass_direction() != 0) { + set_compass_direction(from.compass_direction()); + } + if (from.pdop() != 0) { + set_pdop(from.pdop()); + } + if (from.altitude() != 0) { + set_altitude(from.altitude()); + } + if (from.heading() != 0) { + set_heading(from.heading()); + } + if (from.hdop() != 0) { + set_hdop(from.hdop()); + } + if (from.vdop() != 0) { + set_vdop(from.vdop()); + } + if (from.quality() != 0) { + set_quality(from.quality()); + } + if (from.num_satellites() != 0) { + set_num_satellites(from.num_satellites()); + } + if (from.gps_speed() != 0) { + set_gps_speed(from.gps_speed()); + } +} + +void BasicInfo::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.canbus.BasicInfo) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void BasicInfo::CopyFrom(const BasicInfo& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.canbus.BasicInfo) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool BasicInfo::IsInitialized() const { + return true; +} + +void BasicInfo::Swap(BasicInfo* other) { + if (other == this) return; + InternalSwap(other); +} +void BasicInfo::InternalSwap(BasicInfo* other) { + using std::swap; + swap(power_state_, other->power_state_); + swap(is_auto_mode_, other->is_auto_mode_); + swap(is_air_bag_deployed_, other->is_air_bag_deployed_); + swap(is_system_error_, other->is_system_error_); + swap(is_human_interrupt_, other->is_human_interrupt_); + swap(odo_meter_, other->odo_meter_); + swap(drive_range_, other->drive_range_); + swap(acc_on_button_, other->acc_on_button_); + swap(acc_off_button_, other->acc_off_button_); + swap(acc_res_button_, other->acc_res_button_); + swap(acc_cancel_button_, other->acc_cancel_button_); + swap(acc_on_off_button_, other->acc_on_off_button_); + swap(acc_res_cancel_button_, other->acc_res_cancel_button_); + swap(acc_inc_spd_button_, other->acc_inc_spd_button_); + swap(acc_dec_spd_button_, other->acc_dec_spd_button_); + swap(acc_inc_gap_button_, other->acc_inc_gap_button_); + swap(acc_dec_gap_button_, other->acc_dec_gap_button_); + swap(lka_button_, other->lka_button_); + swap(canbus_fault_, other->canbus_fault_); + swap(year_, other->year_); + swap(latitude_, other->latitude_); + swap(longitude_, other->longitude_); + swap(month_, other->month_); + swap(day_, other->day_); + swap(hours_, other->hours_); + swap(minutes_, other->minutes_); + swap(seconds_, other->seconds_); + swap(gps_valid_, other->gps_valid_); + swap(is_gps_fault_, other->is_gps_fault_); + swap(is_inferred_, other->is_inferred_); + swap(compass_direction_, other->compass_direction_); + swap(pdop_, other->pdop_); + swap(altitude_, other->altitude_); + swap(heading_, other->heading_); + swap(hdop_, other->hdop_); + swap(vdop_, other->vdop_); + swap(quality_, other->quality_); + swap(num_satellites_, other->num_satellites_); + swap(gps_speed_, other->gps_speed_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata BasicInfo::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace canbus +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::ChassisDetail* Arena::CreateMaybeMessage< ::apollo::canbus::ChassisDetail >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::ChassisDetail >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::CheckResponseSignal* Arena::CreateMaybeMessage< ::apollo::canbus::CheckResponseSignal >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::CheckResponseSignal >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::Battery* Arena::CreateMaybeMessage< ::apollo::canbus::Battery >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::Battery >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::Light* Arena::CreateMaybeMessage< ::apollo::canbus::Light >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::Light >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::Eps* Arena::CreateMaybeMessage< ::apollo::canbus::Eps >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::Eps >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::VehicleSpd* Arena::CreateMaybeMessage< ::apollo::canbus::VehicleSpd >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::VehicleSpd >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::Deceleration* Arena::CreateMaybeMessage< ::apollo::canbus::Deceleration >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::Deceleration >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::Brake* Arena::CreateMaybeMessage< ::apollo::canbus::Brake >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::Brake >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::Epb* Arena::CreateMaybeMessage< ::apollo::canbus::Epb >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::Epb >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::Gas* Arena::CreateMaybeMessage< ::apollo::canbus::Gas >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::Gas >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::Esp* Arena::CreateMaybeMessage< ::apollo::canbus::Esp >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::Esp >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::Ems* Arena::CreateMaybeMessage< ::apollo::canbus::Ems >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::Ems >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::Gear* Arena::CreateMaybeMessage< ::apollo::canbus::Gear >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::Gear >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::Safety* Arena::CreateMaybeMessage< ::apollo::canbus::Safety >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::Safety >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::canbus::BasicInfo* Arena::CreateMaybeMessage< ::apollo::canbus::BasicInfo >(Arena* arena) { + return Arena::CreateInternal< ::apollo::canbus::BasicInfo >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/canbus/chassis_detail.pb.h b/apollo_msgs/include/apollo_msgs/proto/canbus/chassis_detail.pb.h new file mode 100644 index 0000000..9ada61b --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/canbus/chassis_detail.pb.h @@ -0,0 +1,8221 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/canbus/chassis_detail.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "apollo_msgs/proto/canbus/chassis.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[15]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto +namespace apollo { +namespace canbus { +class BasicInfo; +class BasicInfoDefaultTypeInternal; +extern BasicInfoDefaultTypeInternal _BasicInfo_default_instance_; +class Battery; +class BatteryDefaultTypeInternal; +extern BatteryDefaultTypeInternal _Battery_default_instance_; +class Brake; +class BrakeDefaultTypeInternal; +extern BrakeDefaultTypeInternal _Brake_default_instance_; +class ChassisDetail; +class ChassisDetailDefaultTypeInternal; +extern ChassisDetailDefaultTypeInternal _ChassisDetail_default_instance_; +class CheckResponseSignal; +class CheckResponseSignalDefaultTypeInternal; +extern CheckResponseSignalDefaultTypeInternal _CheckResponseSignal_default_instance_; +class Deceleration; +class DecelerationDefaultTypeInternal; +extern DecelerationDefaultTypeInternal _Deceleration_default_instance_; +class Ems; +class EmsDefaultTypeInternal; +extern EmsDefaultTypeInternal _Ems_default_instance_; +class Epb; +class EpbDefaultTypeInternal; +extern EpbDefaultTypeInternal _Epb_default_instance_; +class Eps; +class EpsDefaultTypeInternal; +extern EpsDefaultTypeInternal _Eps_default_instance_; +class Esp; +class EspDefaultTypeInternal; +extern EspDefaultTypeInternal _Esp_default_instance_; +class Gas; +class GasDefaultTypeInternal; +extern GasDefaultTypeInternal _Gas_default_instance_; +class Gear; +class GearDefaultTypeInternal; +extern GearDefaultTypeInternal _Gear_default_instance_; +class Light; +class LightDefaultTypeInternal; +extern LightDefaultTypeInternal _Light_default_instance_; +class Safety; +class SafetyDefaultTypeInternal; +extern SafetyDefaultTypeInternal _Safety_default_instance_; +class VehicleSpd; +class VehicleSpdDefaultTypeInternal; +extern VehicleSpdDefaultTypeInternal _VehicleSpd_default_instance_; +} // namespace canbus +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::canbus::BasicInfo* Arena::CreateMaybeMessage<::apollo::canbus::BasicInfo>(Arena*); +template<> ::apollo::canbus::Battery* Arena::CreateMaybeMessage<::apollo::canbus::Battery>(Arena*); +template<> ::apollo::canbus::Brake* Arena::CreateMaybeMessage<::apollo::canbus::Brake>(Arena*); +template<> ::apollo::canbus::ChassisDetail* Arena::CreateMaybeMessage<::apollo::canbus::ChassisDetail>(Arena*); +template<> ::apollo::canbus::CheckResponseSignal* Arena::CreateMaybeMessage<::apollo::canbus::CheckResponseSignal>(Arena*); +template<> ::apollo::canbus::Deceleration* Arena::CreateMaybeMessage<::apollo::canbus::Deceleration>(Arena*); +template<> ::apollo::canbus::Ems* Arena::CreateMaybeMessage<::apollo::canbus::Ems>(Arena*); +template<> ::apollo::canbus::Epb* Arena::CreateMaybeMessage<::apollo::canbus::Epb>(Arena*); +template<> ::apollo::canbus::Eps* Arena::CreateMaybeMessage<::apollo::canbus::Eps>(Arena*); +template<> ::apollo::canbus::Esp* Arena::CreateMaybeMessage<::apollo::canbus::Esp>(Arena*); +template<> ::apollo::canbus::Gas* Arena::CreateMaybeMessage<::apollo::canbus::Gas>(Arena*); +template<> ::apollo::canbus::Gear* Arena::CreateMaybeMessage<::apollo::canbus::Gear>(Arena*); +template<> ::apollo::canbus::Light* Arena::CreateMaybeMessage<::apollo::canbus::Light>(Arena*); +template<> ::apollo::canbus::Safety* Arena::CreateMaybeMessage<::apollo::canbus::Safety>(Arena*); +template<> ::apollo::canbus::VehicleSpd* Arena::CreateMaybeMessage<::apollo::canbus::VehicleSpd>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace canbus { + +enum ChassisDetail_Type { + ChassisDetail_Type_QIRUI_EQ_15 = 0, + ChassisDetail_Type_CHANGAN_RUICHENG = 1, + ChassisDetail_Type_ChassisDetail_Type_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + ChassisDetail_Type_ChassisDetail_Type_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool ChassisDetail_Type_IsValid(int value); +const ChassisDetail_Type ChassisDetail_Type_Type_MIN = ChassisDetail_Type_QIRUI_EQ_15; +const ChassisDetail_Type ChassisDetail_Type_Type_MAX = ChassisDetail_Type_CHANGAN_RUICHENG; +const int ChassisDetail_Type_Type_ARRAYSIZE = ChassisDetail_Type_Type_MAX + 1; + +const ::google::protobuf::EnumDescriptor* ChassisDetail_Type_descriptor(); +inline const ::std::string& ChassisDetail_Type_Name(ChassisDetail_Type value) { + return ::google::protobuf::internal::NameOfEnum( + ChassisDetail_Type_descriptor(), value); +} +inline bool ChassisDetail_Type_Parse( + const ::std::string& name, ChassisDetail_Type* value) { + return ::google::protobuf::internal::ParseNamedEnum( + ChassisDetail_Type_descriptor(), name, value); +} +enum Light_TurnLightType { + Light_TurnLightType_TURN_LIGHT_OFF = 0, + Light_TurnLightType_TURN_LEFT_ON = 1, + Light_TurnLightType_TURN_RIGHT_ON = 2, + Light_TurnLightType_TURN_LIGHT_ON = 3, + Light_TurnLightType_Light_TurnLightType_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Light_TurnLightType_Light_TurnLightType_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Light_TurnLightType_IsValid(int value); +const Light_TurnLightType Light_TurnLightType_TurnLightType_MIN = Light_TurnLightType_TURN_LIGHT_OFF; +const Light_TurnLightType Light_TurnLightType_TurnLightType_MAX = Light_TurnLightType_TURN_LIGHT_ON; +const int Light_TurnLightType_TurnLightType_ARRAYSIZE = Light_TurnLightType_TurnLightType_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Light_TurnLightType_descriptor(); +inline const ::std::string& Light_TurnLightType_Name(Light_TurnLightType value) { + return ::google::protobuf::internal::NameOfEnum( + Light_TurnLightType_descriptor(), value); +} +inline bool Light_TurnLightType_Parse( + const ::std::string& name, Light_TurnLightType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Light_TurnLightType_descriptor(), name, value); +} +enum Light_LampType { + Light_LampType_BEAM_OFF = 0, + Light_LampType_HIGH_BEAM_ON = 1, + Light_LampType_LOW_BEAM_ON = 2, + Light_LampType_Light_LampType_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Light_LampType_Light_LampType_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Light_LampType_IsValid(int value); +const Light_LampType Light_LampType_LampType_MIN = Light_LampType_BEAM_OFF; +const Light_LampType Light_LampType_LampType_MAX = Light_LampType_LOW_BEAM_ON; +const int Light_LampType_LampType_ARRAYSIZE = Light_LampType_LampType_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Light_LampType_descriptor(); +inline const ::std::string& Light_LampType_Name(Light_LampType value) { + return ::google::protobuf::internal::NameOfEnum( + Light_LampType_descriptor(), value); +} +inline bool Light_LampType_Parse( + const ::std::string& name, Light_LampType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Light_LampType_descriptor(), name, value); +} +enum Light_LincolnLampType { + Light_LincolnLampType_BEAM_NULL = 0, + Light_LincolnLampType_BEAM_FLASH_TO_PASS = 1, + Light_LincolnLampType_BEAM_HIGH = 2, + Light_LincolnLampType_BEAM_INVALID = 3, + Light_LincolnLampType_Light_LincolnLampType_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Light_LincolnLampType_Light_LincolnLampType_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Light_LincolnLampType_IsValid(int value); +const Light_LincolnLampType Light_LincolnLampType_LincolnLampType_MIN = Light_LincolnLampType_BEAM_NULL; +const Light_LincolnLampType Light_LincolnLampType_LincolnLampType_MAX = Light_LincolnLampType_BEAM_INVALID; +const int Light_LincolnLampType_LincolnLampType_ARRAYSIZE = Light_LincolnLampType_LincolnLampType_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Light_LincolnLampType_descriptor(); +inline const ::std::string& Light_LincolnLampType_Name(Light_LincolnLampType value) { + return ::google::protobuf::internal::NameOfEnum( + Light_LincolnLampType_descriptor(), value); +} +inline bool Light_LincolnLampType_Parse( + const ::std::string& name, Light_LincolnLampType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Light_LincolnLampType_descriptor(), name, value); +} +enum Light_LincolnWiperType { + Light_LincolnWiperType_WIPER_OFF = 0, + Light_LincolnWiperType_WIPER_AUTO_OFF = 1, + Light_LincolnWiperType_WIPER_OFF_MOVING = 2, + Light_LincolnWiperType_WIPER_MANUAL_OFF = 3, + Light_LincolnWiperType_WIPER_MANUAL_ON = 4, + Light_LincolnWiperType_WIPER_MANUAL_LOW = 5, + Light_LincolnWiperType_WIPER_MANUAL_HIGH = 6, + Light_LincolnWiperType_WIPER_MIST_FLICK = 7, + Light_LincolnWiperType_WIPER_WASH = 8, + Light_LincolnWiperType_WIPER_AUTO_LOW = 9, + Light_LincolnWiperType_WIPER_AUTO_HIGH = 10, + Light_LincolnWiperType_WIPER_COURTESY_WIPE = 11, + Light_LincolnWiperType_WIPER_AUTO_ADJUST = 12, + Light_LincolnWiperType_WIPER_RESERVED = 13, + Light_LincolnWiperType_WIPER_STALLED = 14, + Light_LincolnWiperType_WIPER_NO_DATA = 15, + Light_LincolnWiperType_Light_LincolnWiperType_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Light_LincolnWiperType_Light_LincolnWiperType_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Light_LincolnWiperType_IsValid(int value); +const Light_LincolnWiperType Light_LincolnWiperType_LincolnWiperType_MIN = Light_LincolnWiperType_WIPER_OFF; +const Light_LincolnWiperType Light_LincolnWiperType_LincolnWiperType_MAX = Light_LincolnWiperType_WIPER_NO_DATA; +const int Light_LincolnWiperType_LincolnWiperType_ARRAYSIZE = Light_LincolnWiperType_LincolnWiperType_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Light_LincolnWiperType_descriptor(); +inline const ::std::string& Light_LincolnWiperType_Name(Light_LincolnWiperType value) { + return ::google::protobuf::internal::NameOfEnum( + Light_LincolnWiperType_descriptor(), value); +} +inline bool Light_LincolnWiperType_Parse( + const ::std::string& name, Light_LincolnWiperType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Light_LincolnWiperType_descriptor(), name, value); +} +enum Light_LincolnAmbientType { + Light_LincolnAmbientType_AMBIENT_DARK = 0, + Light_LincolnAmbientType_AMBIENT_LIGHT = 1, + Light_LincolnAmbientType_AMBIENT_TWILIGHT = 2, + Light_LincolnAmbientType_AMBIENT_TUNNEL_ON = 3, + Light_LincolnAmbientType_AMBIENT_TUNNEL_OFF = 4, + Light_LincolnAmbientType_AMBIENT_INVALID = 5, + Light_LincolnAmbientType_AMBIENT_NO_DATA = 7, + Light_LincolnAmbientType_Light_LincolnAmbientType_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Light_LincolnAmbientType_Light_LincolnAmbientType_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Light_LincolnAmbientType_IsValid(int value); +const Light_LincolnAmbientType Light_LincolnAmbientType_LincolnAmbientType_MIN = Light_LincolnAmbientType_AMBIENT_DARK; +const Light_LincolnAmbientType Light_LincolnAmbientType_LincolnAmbientType_MAX = Light_LincolnAmbientType_AMBIENT_NO_DATA; +const int Light_LincolnAmbientType_LincolnAmbientType_ARRAYSIZE = Light_LincolnAmbientType_LincolnAmbientType_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Light_LincolnAmbientType_descriptor(); +inline const ::std::string& Light_LincolnAmbientType_Name(Light_LincolnAmbientType value) { + return ::google::protobuf::internal::NameOfEnum( + Light_LincolnAmbientType_descriptor(), value); +} +inline bool Light_LincolnAmbientType_Parse( + const ::std::string& name, Light_LincolnAmbientType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Light_LincolnAmbientType_descriptor(), name, value); +} +enum Eps_Type { + Eps_Type_NOT_AVAILABLE = 0, + Eps_Type_READY = 1, + Eps_Type_ACTIVE = 2, + Eps_Type_INVALID = 3, + Eps_Type_Eps_Type_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Eps_Type_Eps_Type_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Eps_Type_IsValid(int value); +const Eps_Type Eps_Type_Type_MIN = Eps_Type_NOT_AVAILABLE; +const Eps_Type Eps_Type_Type_MAX = Eps_Type_INVALID; +const int Eps_Type_Type_ARRAYSIZE = Eps_Type_Type_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Eps_Type_descriptor(); +inline const ::std::string& Eps_Type_Name(Eps_Type value) { + return ::google::protobuf::internal::NameOfEnum( + Eps_Type_descriptor(), value); +} +inline bool Eps_Type_Parse( + const ::std::string& name, Eps_Type* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Eps_Type_descriptor(), name, value); +} +enum VehicleSpd_Type { + VehicleSpd_Type_FORWARD = 0, + VehicleSpd_Type_BACKWARD = 1, + VehicleSpd_Type_STANDSTILL = 2, + VehicleSpd_Type_INVALID = 3, + VehicleSpd_Type_VehicleSpd_Type_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + VehicleSpd_Type_VehicleSpd_Type_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool VehicleSpd_Type_IsValid(int value); +const VehicleSpd_Type VehicleSpd_Type_Type_MIN = VehicleSpd_Type_FORWARD; +const VehicleSpd_Type VehicleSpd_Type_Type_MAX = VehicleSpd_Type_INVALID; +const int VehicleSpd_Type_Type_ARRAYSIZE = VehicleSpd_Type_Type_MAX + 1; + +const ::google::protobuf::EnumDescriptor* VehicleSpd_Type_descriptor(); +inline const ::std::string& VehicleSpd_Type_Name(VehicleSpd_Type value) { + return ::google::protobuf::internal::NameOfEnum( + VehicleSpd_Type_descriptor(), value); +} +inline bool VehicleSpd_Type_Parse( + const ::std::string& name, VehicleSpd_Type* value) { + return ::google::protobuf::internal::ParseNamedEnum( + VehicleSpd_Type_descriptor(), name, value); +} +enum Brake_HSAStatusType { + Brake_HSAStatusType_HSA_INACTIVE = 0, + Brake_HSAStatusType_HSA_FINDING_GRADIENT = 1, + Brake_HSAStatusType_HSA_ACTIVE_PRESSED = 2, + Brake_HSAStatusType_HSA_ACTIVE_RELEASED = 3, + Brake_HSAStatusType_HSA_FAST_RELEASE = 4, + Brake_HSAStatusType_HSA_SLOW_RELEASE = 5, + Brake_HSAStatusType_HSA_FAILED = 6, + Brake_HSAStatusType_HSA_UNDEFINED = 7, + Brake_HSAStatusType_Brake_HSAStatusType_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Brake_HSAStatusType_Brake_HSAStatusType_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Brake_HSAStatusType_IsValid(int value); +const Brake_HSAStatusType Brake_HSAStatusType_HSAStatusType_MIN = Brake_HSAStatusType_HSA_INACTIVE; +const Brake_HSAStatusType Brake_HSAStatusType_HSAStatusType_MAX = Brake_HSAStatusType_HSA_UNDEFINED; +const int Brake_HSAStatusType_HSAStatusType_ARRAYSIZE = Brake_HSAStatusType_HSAStatusType_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Brake_HSAStatusType_descriptor(); +inline const ::std::string& Brake_HSAStatusType_Name(Brake_HSAStatusType value) { + return ::google::protobuf::internal::NameOfEnum( + Brake_HSAStatusType_descriptor(), value); +} +inline bool Brake_HSAStatusType_Parse( + const ::std::string& name, Brake_HSAStatusType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Brake_HSAStatusType_descriptor(), name, value); +} +enum Brake_HSAModeType { + Brake_HSAModeType_HSA_OFF = 0, + Brake_HSAModeType_HSA_AUTO = 1, + Brake_HSAModeType_HSA_MANUAL = 2, + Brake_HSAModeType_HSA_MODE_UNDEFINED = 3, + Brake_HSAModeType_Brake_HSAModeType_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Brake_HSAModeType_Brake_HSAModeType_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Brake_HSAModeType_IsValid(int value); +const Brake_HSAModeType Brake_HSAModeType_HSAModeType_MIN = Brake_HSAModeType_HSA_OFF; +const Brake_HSAModeType Brake_HSAModeType_HSAModeType_MAX = Brake_HSAModeType_HSA_MODE_UNDEFINED; +const int Brake_HSAModeType_HSAModeType_ARRAYSIZE = Brake_HSAModeType_HSAModeType_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Brake_HSAModeType_descriptor(); +inline const ::std::string& Brake_HSAModeType_Name(Brake_HSAModeType value) { + return ::google::protobuf::internal::NameOfEnum( + Brake_HSAModeType_descriptor(), value); +} +inline bool Brake_HSAModeType_Parse( + const ::std::string& name, Brake_HSAModeType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Brake_HSAModeType_descriptor(), name, value); +} +enum Epb_PBrakeType { + Epb_PBrakeType_PBRAKE_OFF = 0, + Epb_PBrakeType_PBRAKE_TRANSITION = 1, + Epb_PBrakeType_PBRAKE_ON = 2, + Epb_PBrakeType_PBRAKE_FAULT = 3, + Epb_PBrakeType_Epb_PBrakeType_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Epb_PBrakeType_Epb_PBrakeType_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Epb_PBrakeType_IsValid(int value); +const Epb_PBrakeType Epb_PBrakeType_PBrakeType_MIN = Epb_PBrakeType_PBRAKE_OFF; +const Epb_PBrakeType Epb_PBrakeType_PBrakeType_MAX = Epb_PBrakeType_PBRAKE_FAULT; +const int Epb_PBrakeType_PBrakeType_ARRAYSIZE = Epb_PBrakeType_PBrakeType_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Epb_PBrakeType_descriptor(); +inline const ::std::string& Epb_PBrakeType_Name(Epb_PBrakeType value) { + return ::google::protobuf::internal::NameOfEnum( + Epb_PBrakeType_descriptor(), value); +} +inline bool Epb_PBrakeType_Parse( + const ::std::string& name, Epb_PBrakeType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Epb_PBrakeType_descriptor(), name, value); +} +enum Ems_Type { + Ems_Type_STOP = 0, + Ems_Type_CRANK = 1, + Ems_Type_RUNNING = 2, + Ems_Type_INVALID = 3, + Ems_Type_Ems_Type_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Ems_Type_Ems_Type_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Ems_Type_IsValid(int value); +const Ems_Type Ems_Type_Type_MIN = Ems_Type_STOP; +const Ems_Type Ems_Type_Type_MAX = Ems_Type_INVALID; +const int Ems_Type_Type_ARRAYSIZE = Ems_Type_Type_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Ems_Type_descriptor(); +inline const ::std::string& Ems_Type_Name(Ems_Type value) { + return ::google::protobuf::internal::NameOfEnum( + Ems_Type_descriptor(), value); +} +inline bool Ems_Type_Parse( + const ::std::string& name, Ems_Type* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Ems_Type_descriptor(), name, value); +} +enum BasicInfo_Type { + BasicInfo_Type_OFF = 0, + BasicInfo_Type_ACC = 1, + BasicInfo_Type_ON = 2, + BasicInfo_Type_START = 3, + BasicInfo_Type_INVALID = 4, + BasicInfo_Type_BasicInfo_Type_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + BasicInfo_Type_BasicInfo_Type_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool BasicInfo_Type_IsValid(int value); +const BasicInfo_Type BasicInfo_Type_Type_MIN = BasicInfo_Type_OFF; +const BasicInfo_Type BasicInfo_Type_Type_MAX = BasicInfo_Type_INVALID; +const int BasicInfo_Type_Type_ARRAYSIZE = BasicInfo_Type_Type_MAX + 1; + +const ::google::protobuf::EnumDescriptor* BasicInfo_Type_descriptor(); +inline const ::std::string& BasicInfo_Type_Name(BasicInfo_Type value) { + return ::google::protobuf::internal::NameOfEnum( + BasicInfo_Type_descriptor(), value); +} +inline bool BasicInfo_Type_Parse( + const ::std::string& name, BasicInfo_Type* value) { + return ::google::protobuf::internal::ParseNamedEnum( + BasicInfo_Type_descriptor(), name, value); +} +enum BasicInfo_GpsQuality { + BasicInfo_GpsQuality_FIX_NO = 0, + BasicInfo_GpsQuality_FIX_2D = 1, + BasicInfo_GpsQuality_FIX_3D = 2, + BasicInfo_GpsQuality_FIX_INVALID = 3, + BasicInfo_GpsQuality_BasicInfo_GpsQuality_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + BasicInfo_GpsQuality_BasicInfo_GpsQuality_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool BasicInfo_GpsQuality_IsValid(int value); +const BasicInfo_GpsQuality BasicInfo_GpsQuality_GpsQuality_MIN = BasicInfo_GpsQuality_FIX_NO; +const BasicInfo_GpsQuality BasicInfo_GpsQuality_GpsQuality_MAX = BasicInfo_GpsQuality_FIX_INVALID; +const int BasicInfo_GpsQuality_GpsQuality_ARRAYSIZE = BasicInfo_GpsQuality_GpsQuality_MAX + 1; + +const ::google::protobuf::EnumDescriptor* BasicInfo_GpsQuality_descriptor(); +inline const ::std::string& BasicInfo_GpsQuality_Name(BasicInfo_GpsQuality value) { + return ::google::protobuf::internal::NameOfEnum( + BasicInfo_GpsQuality_descriptor(), value); +} +inline bool BasicInfo_GpsQuality_Parse( + const ::std::string& name, BasicInfo_GpsQuality* value) { + return ::google::protobuf::internal::ParseNamedEnum( + BasicInfo_GpsQuality_descriptor(), name, value); +} +// =================================================================== + +class ChassisDetail : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.ChassisDetail) */ { + public: + ChassisDetail(); + virtual ~ChassisDetail(); + + ChassisDetail(const ChassisDetail& from); + + inline ChassisDetail& operator=(const ChassisDetail& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ChassisDetail(ChassisDetail&& from) noexcept + : ChassisDetail() { + *this = ::std::move(from); + } + + inline ChassisDetail& operator=(ChassisDetail&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ChassisDetail& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ChassisDetail* internal_default_instance() { + return reinterpret_cast( + &_ChassisDetail_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(ChassisDetail* other); + friend void swap(ChassisDetail& a, ChassisDetail& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ChassisDetail* New() const final { + return CreateMaybeMessage(NULL); + } + + ChassisDetail* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ChassisDetail& from); + void MergeFrom(const ChassisDetail& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ChassisDetail* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef ChassisDetail_Type Type; + static const Type QIRUI_EQ_15 = + ChassisDetail_Type_QIRUI_EQ_15; + static const Type CHANGAN_RUICHENG = + ChassisDetail_Type_CHANGAN_RUICHENG; + static inline bool Type_IsValid(int value) { + return ChassisDetail_Type_IsValid(value); + } + static const Type Type_MIN = + ChassisDetail_Type_Type_MIN; + static const Type Type_MAX = + ChassisDetail_Type_Type_MAX; + static const int Type_ARRAYSIZE = + ChassisDetail_Type_Type_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Type_descriptor() { + return ChassisDetail_Type_descriptor(); + } + static inline const ::std::string& Type_Name(Type value) { + return ChassisDetail_Type_Name(value); + } + static inline bool Type_Parse(const ::std::string& name, + Type* value) { + return ChassisDetail_Type_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // .apollo.canbus.BasicInfo basic = 2; + bool has_basic() const; + void clear_basic(); + static const int kBasicFieldNumber = 2; + private: + const ::apollo::canbus::BasicInfo& _internal_basic() const; + public: + const ::apollo::canbus::BasicInfo& basic() const; + ::apollo::canbus::BasicInfo* release_basic(); + ::apollo::canbus::BasicInfo* mutable_basic(); + void set_allocated_basic(::apollo::canbus::BasicInfo* basic); + + // .apollo.canbus.Safety safety = 3; + bool has_safety() const; + void clear_safety(); + static const int kSafetyFieldNumber = 3; + private: + const ::apollo::canbus::Safety& _internal_safety() const; + public: + const ::apollo::canbus::Safety& safety() const; + ::apollo::canbus::Safety* release_safety(); + ::apollo::canbus::Safety* mutable_safety(); + void set_allocated_safety(::apollo::canbus::Safety* safety); + + // .apollo.canbus.Gear gear = 4; + bool has_gear() const; + void clear_gear(); + static const int kGearFieldNumber = 4; + private: + const ::apollo::canbus::Gear& _internal_gear() const; + public: + const ::apollo::canbus::Gear& gear() const; + ::apollo::canbus::Gear* release_gear(); + ::apollo::canbus::Gear* mutable_gear(); + void set_allocated_gear(::apollo::canbus::Gear* gear); + + // .apollo.canbus.Ems ems = 5; + bool has_ems() const; + void clear_ems(); + static const int kEmsFieldNumber = 5; + private: + const ::apollo::canbus::Ems& _internal_ems() const; + public: + const ::apollo::canbus::Ems& ems() const; + ::apollo::canbus::Ems* release_ems(); + ::apollo::canbus::Ems* mutable_ems(); + void set_allocated_ems(::apollo::canbus::Ems* ems); + + // .apollo.canbus.Esp esp = 6; + bool has_esp() const; + void clear_esp(); + static const int kEspFieldNumber = 6; + private: + const ::apollo::canbus::Esp& _internal_esp() const; + public: + const ::apollo::canbus::Esp& esp() const; + ::apollo::canbus::Esp* release_esp(); + ::apollo::canbus::Esp* mutable_esp(); + void set_allocated_esp(::apollo::canbus::Esp* esp); + + // .apollo.canbus.Gas gas = 7; + bool has_gas() const; + void clear_gas(); + static const int kGasFieldNumber = 7; + private: + const ::apollo::canbus::Gas& _internal_gas() const; + public: + const ::apollo::canbus::Gas& gas() const; + ::apollo::canbus::Gas* release_gas(); + ::apollo::canbus::Gas* mutable_gas(); + void set_allocated_gas(::apollo::canbus::Gas* gas); + + // .apollo.canbus.Epb epb = 8; + bool has_epb() const; + void clear_epb(); + static const int kEpbFieldNumber = 8; + private: + const ::apollo::canbus::Epb& _internal_epb() const; + public: + const ::apollo::canbus::Epb& epb() const; + ::apollo::canbus::Epb* release_epb(); + ::apollo::canbus::Epb* mutable_epb(); + void set_allocated_epb(::apollo::canbus::Epb* epb); + + // .apollo.canbus.Brake brake = 9; + bool has_brake() const; + void clear_brake(); + static const int kBrakeFieldNumber = 9; + private: + const ::apollo::canbus::Brake& _internal_brake() const; + public: + const ::apollo::canbus::Brake& brake() const; + ::apollo::canbus::Brake* release_brake(); + ::apollo::canbus::Brake* mutable_brake(); + void set_allocated_brake(::apollo::canbus::Brake* brake); + + // .apollo.canbus.Deceleration deceleration = 10; + bool has_deceleration() const; + void clear_deceleration(); + static const int kDecelerationFieldNumber = 10; + private: + const ::apollo::canbus::Deceleration& _internal_deceleration() const; + public: + const ::apollo::canbus::Deceleration& deceleration() const; + ::apollo::canbus::Deceleration* release_deceleration(); + ::apollo::canbus::Deceleration* mutable_deceleration(); + void set_allocated_deceleration(::apollo::canbus::Deceleration* deceleration); + + // .apollo.canbus.VehicleSpd vehicle_spd = 11; + bool has_vehicle_spd() const; + void clear_vehicle_spd(); + static const int kVehicleSpdFieldNumber = 11; + private: + const ::apollo::canbus::VehicleSpd& _internal_vehicle_spd() const; + public: + const ::apollo::canbus::VehicleSpd& vehicle_spd() const; + ::apollo::canbus::VehicleSpd* release_vehicle_spd(); + ::apollo::canbus::VehicleSpd* mutable_vehicle_spd(); + void set_allocated_vehicle_spd(::apollo::canbus::VehicleSpd* vehicle_spd); + + // .apollo.canbus.Eps eps = 12; + bool has_eps() const; + void clear_eps(); + static const int kEpsFieldNumber = 12; + private: + const ::apollo::canbus::Eps& _internal_eps() const; + public: + const ::apollo::canbus::Eps& eps() const; + ::apollo::canbus::Eps* release_eps(); + ::apollo::canbus::Eps* mutable_eps(); + void set_allocated_eps(::apollo::canbus::Eps* eps); + + // .apollo.canbus.Light light = 13; + bool has_light() const; + void clear_light(); + static const int kLightFieldNumber = 13; + private: + const ::apollo::canbus::Light& _internal_light() const; + public: + const ::apollo::canbus::Light& light() const; + ::apollo::canbus::Light* release_light(); + ::apollo::canbus::Light* mutable_light(); + void set_allocated_light(::apollo::canbus::Light* light); + + // .apollo.canbus.Battery battery = 14; + bool has_battery() const; + void clear_battery(); + static const int kBatteryFieldNumber = 14; + private: + const ::apollo::canbus::Battery& _internal_battery() const; + public: + const ::apollo::canbus::Battery& battery() const; + ::apollo::canbus::Battery* release_battery(); + ::apollo::canbus::Battery* mutable_battery(); + void set_allocated_battery(::apollo::canbus::Battery* battery); + + // .apollo.canbus.CheckResponseSignal check_response = 15; + bool has_check_response() const; + void clear_check_response(); + static const int kCheckResponseFieldNumber = 15; + private: + const ::apollo::canbus::CheckResponseSignal& _internal_check_response() const; + public: + const ::apollo::canbus::CheckResponseSignal& check_response() const; + ::apollo::canbus::CheckResponseSignal* release_check_response(); + ::apollo::canbus::CheckResponseSignal* mutable_check_response(); + void set_allocated_check_response(::apollo::canbus::CheckResponseSignal* check_response); + + // .apollo.canbus.ChassisDetail.Type car_type = 1; + void clear_car_type(); + static const int kCarTypeFieldNumber = 1; + ::apollo::canbus::ChassisDetail_Type car_type() const; + void set_car_type(::apollo::canbus::ChassisDetail_Type value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.ChassisDetail) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::canbus::BasicInfo* basic_; + ::apollo::canbus::Safety* safety_; + ::apollo::canbus::Gear* gear_; + ::apollo::canbus::Ems* ems_; + ::apollo::canbus::Esp* esp_; + ::apollo::canbus::Gas* gas_; + ::apollo::canbus::Epb* epb_; + ::apollo::canbus::Brake* brake_; + ::apollo::canbus::Deceleration* deceleration_; + ::apollo::canbus::VehicleSpd* vehicle_spd_; + ::apollo::canbus::Eps* eps_; + ::apollo::canbus::Light* light_; + ::apollo::canbus::Battery* battery_; + ::apollo::canbus::CheckResponseSignal* check_response_; + int car_type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class CheckResponseSignal : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.CheckResponseSignal) */ { + public: + CheckResponseSignal(); + virtual ~CheckResponseSignal(); + + CheckResponseSignal(const CheckResponseSignal& from); + + inline CheckResponseSignal& operator=(const CheckResponseSignal& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + CheckResponseSignal(CheckResponseSignal&& from) noexcept + : CheckResponseSignal() { + *this = ::std::move(from); + } + + inline CheckResponseSignal& operator=(CheckResponseSignal&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const CheckResponseSignal& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const CheckResponseSignal* internal_default_instance() { + return reinterpret_cast( + &_CheckResponseSignal_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(CheckResponseSignal* other); + friend void swap(CheckResponseSignal& a, CheckResponseSignal& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline CheckResponseSignal* New() const final { + return CreateMaybeMessage(NULL); + } + + CheckResponseSignal* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const CheckResponseSignal& from); + void MergeFrom(const CheckResponseSignal& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(CheckResponseSignal* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // bool is_eps_online = 1; + void clear_is_eps_online(); + static const int kIsEpsOnlineFieldNumber = 1; + bool is_eps_online() const; + void set_is_eps_online(bool value); + + // bool is_epb_online = 2; + void clear_is_epb_online(); + static const int kIsEpbOnlineFieldNumber = 2; + bool is_epb_online() const; + void set_is_epb_online(bool value); + + // bool is_esp_online = 3; + void clear_is_esp_online(); + static const int kIsEspOnlineFieldNumber = 3; + bool is_esp_online() const; + void set_is_esp_online(bool value); + + // bool is_vtog_online = 4; + void clear_is_vtog_online(); + static const int kIsVtogOnlineFieldNumber = 4; + bool is_vtog_online() const; + void set_is_vtog_online(bool value); + + // bool is_scu_online = 5; + void clear_is_scu_online(); + static const int kIsScuOnlineFieldNumber = 5; + bool is_scu_online() const; + void set_is_scu_online(bool value); + + // bool is_switch_online = 6; + void clear_is_switch_online(); + static const int kIsSwitchOnlineFieldNumber = 6; + bool is_switch_online() const; + void set_is_switch_online(bool value); + + // bool is_vcu_online = 7; + void clear_is_vcu_online(); + static const int kIsVcuOnlineFieldNumber = 7; + bool is_vcu_online() const; + void set_is_vcu_online(bool value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.CheckResponseSignal) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + bool is_eps_online_; + bool is_epb_online_; + bool is_esp_online_; + bool is_vtog_online_; + bool is_scu_online_; + bool is_switch_online_; + bool is_vcu_online_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Battery : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.Battery) */ { + public: + Battery(); + virtual ~Battery(); + + Battery(const Battery& from); + + inline Battery& operator=(const Battery& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Battery(Battery&& from) noexcept + : Battery() { + *this = ::std::move(from); + } + + inline Battery& operator=(Battery&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Battery& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Battery* internal_default_instance() { + return reinterpret_cast( + &_Battery_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + void Swap(Battery* other); + friend void swap(Battery& a, Battery& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Battery* New() const final { + return CreateMaybeMessage(NULL); + } + + Battery* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Battery& from); + void MergeFrom(const Battery& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Battery* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double battery_percent = 1; + void clear_battery_percent(); + static const int kBatteryPercentFieldNumber = 1; + double battery_percent() const; + void set_battery_percent(double value); + + // double fuel_level = 2; + void clear_fuel_level(); + static const int kFuelLevelFieldNumber = 2; + double fuel_level() const; + void set_fuel_level(double value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.Battery) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double battery_percent_; + double fuel_level_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Light : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.Light) */ { + public: + Light(); + virtual ~Light(); + + Light(const Light& from); + + inline Light& operator=(const Light& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Light(Light&& from) noexcept + : Light() { + *this = ::std::move(from); + } + + inline Light& operator=(Light&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Light& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Light* internal_default_instance() { + return reinterpret_cast( + &_Light_default_instance_); + } + static constexpr int kIndexInFileMessages = + 3; + + void Swap(Light* other); + friend void swap(Light& a, Light& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Light* New() const final { + return CreateMaybeMessage(NULL); + } + + Light* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Light& from); + void MergeFrom(const Light& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Light* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef Light_TurnLightType TurnLightType; + static const TurnLightType TURN_LIGHT_OFF = + Light_TurnLightType_TURN_LIGHT_OFF; + static const TurnLightType TURN_LEFT_ON = + Light_TurnLightType_TURN_LEFT_ON; + static const TurnLightType TURN_RIGHT_ON = + Light_TurnLightType_TURN_RIGHT_ON; + static const TurnLightType TURN_LIGHT_ON = + Light_TurnLightType_TURN_LIGHT_ON; + static inline bool TurnLightType_IsValid(int value) { + return Light_TurnLightType_IsValid(value); + } + static const TurnLightType TurnLightType_MIN = + Light_TurnLightType_TurnLightType_MIN; + static const TurnLightType TurnLightType_MAX = + Light_TurnLightType_TurnLightType_MAX; + static const int TurnLightType_ARRAYSIZE = + Light_TurnLightType_TurnLightType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + TurnLightType_descriptor() { + return Light_TurnLightType_descriptor(); + } + static inline const ::std::string& TurnLightType_Name(TurnLightType value) { + return Light_TurnLightType_Name(value); + } + static inline bool TurnLightType_Parse(const ::std::string& name, + TurnLightType* value) { + return Light_TurnLightType_Parse(name, value); + } + + typedef Light_LampType LampType; + static const LampType BEAM_OFF = + Light_LampType_BEAM_OFF; + static const LampType HIGH_BEAM_ON = + Light_LampType_HIGH_BEAM_ON; + static const LampType LOW_BEAM_ON = + Light_LampType_LOW_BEAM_ON; + static inline bool LampType_IsValid(int value) { + return Light_LampType_IsValid(value); + } + static const LampType LampType_MIN = + Light_LampType_LampType_MIN; + static const LampType LampType_MAX = + Light_LampType_LampType_MAX; + static const int LampType_ARRAYSIZE = + Light_LampType_LampType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + LampType_descriptor() { + return Light_LampType_descriptor(); + } + static inline const ::std::string& LampType_Name(LampType value) { + return Light_LampType_Name(value); + } + static inline bool LampType_Parse(const ::std::string& name, + LampType* value) { + return Light_LampType_Parse(name, value); + } + + typedef Light_LincolnLampType LincolnLampType; + static const LincolnLampType BEAM_NULL = + Light_LincolnLampType_BEAM_NULL; + static const LincolnLampType BEAM_FLASH_TO_PASS = + Light_LincolnLampType_BEAM_FLASH_TO_PASS; + static const LincolnLampType BEAM_HIGH = + Light_LincolnLampType_BEAM_HIGH; + static const LincolnLampType BEAM_INVALID = + Light_LincolnLampType_BEAM_INVALID; + static inline bool LincolnLampType_IsValid(int value) { + return Light_LincolnLampType_IsValid(value); + } + static const LincolnLampType LincolnLampType_MIN = + Light_LincolnLampType_LincolnLampType_MIN; + static const LincolnLampType LincolnLampType_MAX = + Light_LincolnLampType_LincolnLampType_MAX; + static const int LincolnLampType_ARRAYSIZE = + Light_LincolnLampType_LincolnLampType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + LincolnLampType_descriptor() { + return Light_LincolnLampType_descriptor(); + } + static inline const ::std::string& LincolnLampType_Name(LincolnLampType value) { + return Light_LincolnLampType_Name(value); + } + static inline bool LincolnLampType_Parse(const ::std::string& name, + LincolnLampType* value) { + return Light_LincolnLampType_Parse(name, value); + } + + typedef Light_LincolnWiperType LincolnWiperType; + static const LincolnWiperType WIPER_OFF = + Light_LincolnWiperType_WIPER_OFF; + static const LincolnWiperType WIPER_AUTO_OFF = + Light_LincolnWiperType_WIPER_AUTO_OFF; + static const LincolnWiperType WIPER_OFF_MOVING = + Light_LincolnWiperType_WIPER_OFF_MOVING; + static const LincolnWiperType WIPER_MANUAL_OFF = + Light_LincolnWiperType_WIPER_MANUAL_OFF; + static const LincolnWiperType WIPER_MANUAL_ON = + Light_LincolnWiperType_WIPER_MANUAL_ON; + static const LincolnWiperType WIPER_MANUAL_LOW = + Light_LincolnWiperType_WIPER_MANUAL_LOW; + static const LincolnWiperType WIPER_MANUAL_HIGH = + Light_LincolnWiperType_WIPER_MANUAL_HIGH; + static const LincolnWiperType WIPER_MIST_FLICK = + Light_LincolnWiperType_WIPER_MIST_FLICK; + static const LincolnWiperType WIPER_WASH = + Light_LincolnWiperType_WIPER_WASH; + static const LincolnWiperType WIPER_AUTO_LOW = + Light_LincolnWiperType_WIPER_AUTO_LOW; + static const LincolnWiperType WIPER_AUTO_HIGH = + Light_LincolnWiperType_WIPER_AUTO_HIGH; + static const LincolnWiperType WIPER_COURTESY_WIPE = + Light_LincolnWiperType_WIPER_COURTESY_WIPE; + static const LincolnWiperType WIPER_AUTO_ADJUST = + Light_LincolnWiperType_WIPER_AUTO_ADJUST; + static const LincolnWiperType WIPER_RESERVED = + Light_LincolnWiperType_WIPER_RESERVED; + static const LincolnWiperType WIPER_STALLED = + Light_LincolnWiperType_WIPER_STALLED; + static const LincolnWiperType WIPER_NO_DATA = + Light_LincolnWiperType_WIPER_NO_DATA; + static inline bool LincolnWiperType_IsValid(int value) { + return Light_LincolnWiperType_IsValid(value); + } + static const LincolnWiperType LincolnWiperType_MIN = + Light_LincolnWiperType_LincolnWiperType_MIN; + static const LincolnWiperType LincolnWiperType_MAX = + Light_LincolnWiperType_LincolnWiperType_MAX; + static const int LincolnWiperType_ARRAYSIZE = + Light_LincolnWiperType_LincolnWiperType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + LincolnWiperType_descriptor() { + return Light_LincolnWiperType_descriptor(); + } + static inline const ::std::string& LincolnWiperType_Name(LincolnWiperType value) { + return Light_LincolnWiperType_Name(value); + } + static inline bool LincolnWiperType_Parse(const ::std::string& name, + LincolnWiperType* value) { + return Light_LincolnWiperType_Parse(name, value); + } + + typedef Light_LincolnAmbientType LincolnAmbientType; + static const LincolnAmbientType AMBIENT_DARK = + Light_LincolnAmbientType_AMBIENT_DARK; + static const LincolnAmbientType AMBIENT_LIGHT = + Light_LincolnAmbientType_AMBIENT_LIGHT; + static const LincolnAmbientType AMBIENT_TWILIGHT = + Light_LincolnAmbientType_AMBIENT_TWILIGHT; + static const LincolnAmbientType AMBIENT_TUNNEL_ON = + Light_LincolnAmbientType_AMBIENT_TUNNEL_ON; + static const LincolnAmbientType AMBIENT_TUNNEL_OFF = + Light_LincolnAmbientType_AMBIENT_TUNNEL_OFF; + static const LincolnAmbientType AMBIENT_INVALID = + Light_LincolnAmbientType_AMBIENT_INVALID; + static const LincolnAmbientType AMBIENT_NO_DATA = + Light_LincolnAmbientType_AMBIENT_NO_DATA; + static inline bool LincolnAmbientType_IsValid(int value) { + return Light_LincolnAmbientType_IsValid(value); + } + static const LincolnAmbientType LincolnAmbientType_MIN = + Light_LincolnAmbientType_LincolnAmbientType_MIN; + static const LincolnAmbientType LincolnAmbientType_MAX = + Light_LincolnAmbientType_LincolnAmbientType_MAX; + static const int LincolnAmbientType_ARRAYSIZE = + Light_LincolnAmbientType_LincolnAmbientType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + LincolnAmbientType_descriptor() { + return Light_LincolnAmbientType_descriptor(); + } + static inline const ::std::string& LincolnAmbientType_Name(LincolnAmbientType value) { + return Light_LincolnAmbientType_Name(value); + } + static inline bool LincolnAmbientType_Parse(const ::std::string& name, + LincolnAmbientType* value) { + return Light_LincolnAmbientType_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // .apollo.canbus.Light.TurnLightType turn_light_type = 1; + void clear_turn_light_type(); + static const int kTurnLightTypeFieldNumber = 1; + ::apollo::canbus::Light_TurnLightType turn_light_type() const; + void set_turn_light_type(::apollo::canbus::Light_TurnLightType value); + + // .apollo.canbus.Light.LampType lamp_type = 2; + void clear_lamp_type(); + static const int kLampTypeFieldNumber = 2; + ::apollo::canbus::Light_LampType lamp_type() const; + void set_lamp_type(::apollo::canbus::Light_LampType value); + + // bool is_brake_lamp_on = 3; + void clear_is_brake_lamp_on(); + static const int kIsBrakeLampOnFieldNumber = 3; + bool is_brake_lamp_on() const; + void set_is_brake_lamp_on(bool value); + + // bool is_auto_light = 4; + void clear_is_auto_light(); + static const int kIsAutoLightFieldNumber = 4; + bool is_auto_light() const; + void set_is_auto_light(bool value); + + // bool is_horn_on = 7; + void clear_is_horn_on(); + static const int kIsHornOnFieldNumber = 7; + bool is_horn_on() const; + void set_is_horn_on(bool value); + + // int32 wiper_gear = 5; + void clear_wiper_gear(); + static const int kWiperGearFieldNumber = 5; + ::google::protobuf::int32 wiper_gear() const; + void set_wiper_gear(::google::protobuf::int32 value); + + // int32 lotion_gear = 6; + void clear_lotion_gear(); + static const int kLotionGearFieldNumber = 6; + ::google::protobuf::int32 lotion_gear() const; + void set_lotion_gear(::google::protobuf::int32 value); + + // .apollo.canbus.Light.LincolnLampType lincoln_lamp_type = 8; + void clear_lincoln_lamp_type(); + static const int kLincolnLampTypeFieldNumber = 8; + ::apollo::canbus::Light_LincolnLampType lincoln_lamp_type() const; + void set_lincoln_lamp_type(::apollo::canbus::Light_LincolnLampType value); + + // .apollo.canbus.Light.LincolnWiperType lincoln_wiper = 9; + void clear_lincoln_wiper(); + static const int kLincolnWiperFieldNumber = 9; + ::apollo::canbus::Light_LincolnWiperType lincoln_wiper() const; + void set_lincoln_wiper(::apollo::canbus::Light_LincolnWiperType value); + + // .apollo.canbus.Light.LincolnAmbientType lincoln_ambient = 10; + void clear_lincoln_ambient(); + static const int kLincolnAmbientFieldNumber = 10; + ::apollo::canbus::Light_LincolnAmbientType lincoln_ambient() const; + void set_lincoln_ambient(::apollo::canbus::Light_LincolnAmbientType value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.Light) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + int turn_light_type_; + int lamp_type_; + bool is_brake_lamp_on_; + bool is_auto_light_; + bool is_horn_on_; + ::google::protobuf::int32 wiper_gear_; + ::google::protobuf::int32 lotion_gear_; + int lincoln_lamp_type_; + int lincoln_wiper_; + int lincoln_ambient_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Eps : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.Eps) */ { + public: + Eps(); + virtual ~Eps(); + + Eps(const Eps& from); + + inline Eps& operator=(const Eps& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Eps(Eps&& from) noexcept + : Eps() { + *this = ::std::move(from); + } + + inline Eps& operator=(Eps&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Eps& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Eps* internal_default_instance() { + return reinterpret_cast( + &_Eps_default_instance_); + } + static constexpr int kIndexInFileMessages = + 4; + + void Swap(Eps* other); + friend void swap(Eps& a, Eps& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Eps* New() const final { + return CreateMaybeMessage(NULL); + } + + Eps* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Eps& from); + void MergeFrom(const Eps& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Eps* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef Eps_Type Type; + static const Type NOT_AVAILABLE = + Eps_Type_NOT_AVAILABLE; + static const Type READY = + Eps_Type_READY; + static const Type ACTIVE = + Eps_Type_ACTIVE; + static const Type INVALID = + Eps_Type_INVALID; + static inline bool Type_IsValid(int value) { + return Eps_Type_IsValid(value); + } + static const Type Type_MIN = + Eps_Type_Type_MIN; + static const Type Type_MAX = + Eps_Type_Type_MAX; + static const int Type_ARRAYSIZE = + Eps_Type_Type_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Type_descriptor() { + return Eps_Type_descriptor(); + } + static inline const ::std::string& Type_Name(Type value) { + return Eps_Type_Name(value); + } + static inline bool Type_Parse(const ::std::string& name, + Type* value) { + return Eps_Type_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // double eps_driver_hand_torq = 3; + void clear_eps_driver_hand_torq(); + static const int kEpsDriverHandTorqFieldNumber = 3; + double eps_driver_hand_torq() const; + void set_eps_driver_hand_torq(double value); + + // .apollo.canbus.Eps.Type eps_control_state = 2; + void clear_eps_control_state(); + static const int kEpsControlStateFieldNumber = 2; + ::apollo::canbus::Eps_Type eps_control_state() const; + void set_eps_control_state(::apollo::canbus::Eps_Type value); + + // bool is_eps_fail = 1; + void clear_is_eps_fail(); + static const int kIsEpsFailFieldNumber = 1; + bool is_eps_fail() const; + void set_is_eps_fail(bool value); + + // bool is_steering_angle_valid = 4; + void clear_is_steering_angle_valid(); + static const int kIsSteeringAngleValidFieldNumber = 4; + bool is_steering_angle_valid() const; + void set_is_steering_angle_valid(bool value); + + // bool is_trimming_status = 7; + void clear_is_trimming_status(); + static const int kIsTrimmingStatusFieldNumber = 7; + bool is_trimming_status() const; + void set_is_trimming_status(bool value); + + // bool is_calibration_status = 8; + void clear_is_calibration_status(); + static const int kIsCalibrationStatusFieldNumber = 8; + bool is_calibration_status() const; + void set_is_calibration_status(bool value); + + // double steering_angle = 5; + void clear_steering_angle(); + static const int kSteeringAngleFieldNumber = 5; + double steering_angle() const; + void set_steering_angle(double value); + + // double steering_angle_spd = 6; + void clear_steering_angle_spd(); + static const int kSteeringAngleSpdFieldNumber = 6; + double steering_angle_spd() const; + void set_steering_angle_spd(double value); + + // int32 allow_enter_autonomous_mode = 10; + void clear_allow_enter_autonomous_mode(); + static const int kAllowEnterAutonomousModeFieldNumber = 10; + ::google::protobuf::int32 allow_enter_autonomous_mode() const; + void set_allow_enter_autonomous_mode(::google::protobuf::int32 value); + + // int32 current_driving_mode = 11; + void clear_current_driving_mode(); + static const int kCurrentDrivingModeFieldNumber = 11; + ::google::protobuf::int32 current_driving_mode() const; + void set_current_driving_mode(::google::protobuf::int32 value); + + // double steering_angle_cmd = 12; + void clear_steering_angle_cmd(); + static const int kSteeringAngleCmdFieldNumber = 12; + double steering_angle_cmd() const; + void set_steering_angle_cmd(double value); + + // double vehicle_speed = 13; + void clear_vehicle_speed(); + static const int kVehicleSpeedFieldNumber = 13; + double vehicle_speed() const; + void set_vehicle_speed(double value); + + // double epas_torque = 14; + void clear_epas_torque(); + static const int kEpasTorqueFieldNumber = 14; + double epas_torque() const; + void set_epas_torque(double value); + + // bool is_failure_status = 9; + void clear_is_failure_status(); + static const int kIsFailureStatusFieldNumber = 9; + bool is_failure_status() const; + void set_is_failure_status(bool value); + + // bool steering_enabled = 15; + void clear_steering_enabled(); + static const int kSteeringEnabledFieldNumber = 15; + bool steering_enabled() const; + void set_steering_enabled(bool value); + + // bool driver_override = 16; + void clear_driver_override(); + static const int kDriverOverrideFieldNumber = 16; + bool driver_override() const; + void set_driver_override(bool value); + + // bool driver_activity = 17; + void clear_driver_activity(); + static const int kDriverActivityFieldNumber = 17; + bool driver_activity() const; + void set_driver_activity(bool value); + + // bool watchdog_fault = 18; + void clear_watchdog_fault(); + static const int kWatchdogFaultFieldNumber = 18; + bool watchdog_fault() const; + void set_watchdog_fault(bool value); + + // bool channel_1_fault = 19; + void clear_channel_1_fault(); + static const int kChannel1FaultFieldNumber = 19; + bool channel_1_fault() const; + void set_channel_1_fault(bool value); + + // bool channel_2_fault = 20; + void clear_channel_2_fault(); + static const int kChannel2FaultFieldNumber = 20; + bool channel_2_fault() const; + void set_channel_2_fault(bool value); + + // bool calibration_fault = 21; + void clear_calibration_fault(); + static const int kCalibrationFaultFieldNumber = 21; + bool calibration_fault() const; + void set_calibration_fault(bool value); + + // double timestamp_65 = 23; + void clear_timestamp_65(); + static const int kTimestamp65FieldNumber = 23; + double timestamp_65() const; + void set_timestamp_65(double value); + + // bool connector_fault = 22; + void clear_connector_fault(); + static const int kConnectorFaultFieldNumber = 22; + bool connector_fault() const; + void set_connector_fault(bool value); + + // int32 major_version = 24; + void clear_major_version(); + static const int kMajorVersionFieldNumber = 24; + ::google::protobuf::int32 major_version() const; + void set_major_version(::google::protobuf::int32 value); + + // int32 minor_version = 25; + void clear_minor_version(); + static const int kMinorVersionFieldNumber = 25; + ::google::protobuf::int32 minor_version() const; + void set_minor_version(::google::protobuf::int32 value); + + // int32 build_number = 26; + void clear_build_number(); + static const int kBuildNumberFieldNumber = 26; + ::google::protobuf::int32 build_number() const; + void set_build_number(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.Eps) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double eps_driver_hand_torq_; + int eps_control_state_; + bool is_eps_fail_; + bool is_steering_angle_valid_; + bool is_trimming_status_; + bool is_calibration_status_; + double steering_angle_; + double steering_angle_spd_; + ::google::protobuf::int32 allow_enter_autonomous_mode_; + ::google::protobuf::int32 current_driving_mode_; + double steering_angle_cmd_; + double vehicle_speed_; + double epas_torque_; + bool is_failure_status_; + bool steering_enabled_; + bool driver_override_; + bool driver_activity_; + bool watchdog_fault_; + bool channel_1_fault_; + bool channel_2_fault_; + bool calibration_fault_; + double timestamp_65_; + bool connector_fault_; + ::google::protobuf::int32 major_version_; + ::google::protobuf::int32 minor_version_; + ::google::protobuf::int32 build_number_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class VehicleSpd : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.VehicleSpd) */ { + public: + VehicleSpd(); + virtual ~VehicleSpd(); + + VehicleSpd(const VehicleSpd& from); + + inline VehicleSpd& operator=(const VehicleSpd& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + VehicleSpd(VehicleSpd&& from) noexcept + : VehicleSpd() { + *this = ::std::move(from); + } + + inline VehicleSpd& operator=(VehicleSpd&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const VehicleSpd& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const VehicleSpd* internal_default_instance() { + return reinterpret_cast( + &_VehicleSpd_default_instance_); + } + static constexpr int kIndexInFileMessages = + 5; + + void Swap(VehicleSpd* other); + friend void swap(VehicleSpd& a, VehicleSpd& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline VehicleSpd* New() const final { + return CreateMaybeMessage(NULL); + } + + VehicleSpd* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const VehicleSpd& from); + void MergeFrom(const VehicleSpd& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(VehicleSpd* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef VehicleSpd_Type Type; + static const Type FORWARD = + VehicleSpd_Type_FORWARD; + static const Type BACKWARD = + VehicleSpd_Type_BACKWARD; + static const Type STANDSTILL = + VehicleSpd_Type_STANDSTILL; + static const Type INVALID = + VehicleSpd_Type_INVALID; + static inline bool Type_IsValid(int value) { + return VehicleSpd_Type_IsValid(value); + } + static const Type Type_MIN = + VehicleSpd_Type_Type_MIN; + static const Type Type_MAX = + VehicleSpd_Type_Type_MAX; + static const int Type_ARRAYSIZE = + VehicleSpd_Type_Type_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Type_descriptor() { + return VehicleSpd_Type_descriptor(); + } + static inline const ::std::string& Type_Name(Type value) { + return VehicleSpd_Type_Name(value); + } + static inline bool Type_Parse(const ::std::string& name, + Type* value) { + return VehicleSpd_Type_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // double vehicle_spd = 3; + void clear_vehicle_spd(); + static const int kVehicleSpdFieldNumber = 3; + double vehicle_spd() const; + void set_vehicle_spd(double value); + + // bool is_vehicle_standstill = 1; + void clear_is_vehicle_standstill(); + static const int kIsVehicleStandstillFieldNumber = 1; + bool is_vehicle_standstill() const; + void set_is_vehicle_standstill(bool value); + + // bool is_vehicle_spd_valid = 2; + void clear_is_vehicle_spd_valid(); + static const int kIsVehicleSpdValidFieldNumber = 2; + bool is_vehicle_spd_valid() const; + void set_is_vehicle_spd_valid(bool value); + + // bool is_wheel_spd_rr_valid = 4; + void clear_is_wheel_spd_rr_valid(); + static const int kIsWheelSpdRrValidFieldNumber = 4; + bool is_wheel_spd_rr_valid() const; + void set_is_wheel_spd_rr_valid(bool value); + + // bool is_wheel_spd_rl_valid = 7; + void clear_is_wheel_spd_rl_valid(); + static const int kIsWheelSpdRlValidFieldNumber = 7; + bool is_wheel_spd_rl_valid() const; + void set_is_wheel_spd_rl_valid(bool value); + + // .apollo.canbus.VehicleSpd.Type wheel_direction_rr = 5; + void clear_wheel_direction_rr(); + static const int kWheelDirectionRrFieldNumber = 5; + ::apollo::canbus::VehicleSpd_Type wheel_direction_rr() const; + void set_wheel_direction_rr(::apollo::canbus::VehicleSpd_Type value); + + // double wheel_spd_rr = 6; + void clear_wheel_spd_rr(); + static const int kWheelSpdRrFieldNumber = 6; + double wheel_spd_rr() const; + void set_wheel_spd_rr(double value); + + // double wheel_spd_rl = 9; + void clear_wheel_spd_rl(); + static const int kWheelSpdRlFieldNumber = 9; + double wheel_spd_rl() const; + void set_wheel_spd_rl(double value); + + // .apollo.canbus.VehicleSpd.Type wheel_direction_rl = 8; + void clear_wheel_direction_rl(); + static const int kWheelDirectionRlFieldNumber = 8; + ::apollo::canbus::VehicleSpd_Type wheel_direction_rl() const; + void set_wheel_direction_rl(::apollo::canbus::VehicleSpd_Type value); + + // .apollo.canbus.VehicleSpd.Type wheel_direction_fr = 11; + void clear_wheel_direction_fr(); + static const int kWheelDirectionFrFieldNumber = 11; + ::apollo::canbus::VehicleSpd_Type wheel_direction_fr() const; + void set_wheel_direction_fr(::apollo::canbus::VehicleSpd_Type value); + + // double wheel_spd_fr = 12; + void clear_wheel_spd_fr(); + static const int kWheelSpdFrFieldNumber = 12; + double wheel_spd_fr() const; + void set_wheel_spd_fr(double value); + + // .apollo.canbus.VehicleSpd.Type wheel_direction_fl = 14; + void clear_wheel_direction_fl(); + static const int kWheelDirectionFlFieldNumber = 14; + ::apollo::canbus::VehicleSpd_Type wheel_direction_fl() const; + void set_wheel_direction_fl(::apollo::canbus::VehicleSpd_Type value); + + // bool is_wheel_spd_fr_valid = 10; + void clear_is_wheel_spd_fr_valid(); + static const int kIsWheelSpdFrValidFieldNumber = 10; + bool is_wheel_spd_fr_valid() const; + void set_is_wheel_spd_fr_valid(bool value); + + // bool is_wheel_spd_fl_valid = 13; + void clear_is_wheel_spd_fl_valid(); + static const int kIsWheelSpdFlValidFieldNumber = 13; + bool is_wheel_spd_fl_valid() const; + void set_is_wheel_spd_fl_valid(bool value); + + // bool is_yaw_rate_valid = 16; + void clear_is_yaw_rate_valid(); + static const int kIsYawRateValidFieldNumber = 16; + bool is_yaw_rate_valid() const; + void set_is_yaw_rate_valid(bool value); + + // bool is_ax_valid = 19; + void clear_is_ax_valid(); + static const int kIsAxValidFieldNumber = 19; + bool is_ax_valid() const; + void set_is_ax_valid(bool value); + + // double wheel_spd_fl = 15; + void clear_wheel_spd_fl(); + static const int kWheelSpdFlFieldNumber = 15; + double wheel_spd_fl() const; + void set_wheel_spd_fl(double value); + + // double yaw_rate = 17; + void clear_yaw_rate(); + static const int kYawRateFieldNumber = 17; + double yaw_rate() const; + void set_yaw_rate(double value); + + // double yaw_rate_offset = 18; + void clear_yaw_rate_offset(); + static const int kYawRateOffsetFieldNumber = 18; + double yaw_rate_offset() const; + void set_yaw_rate_offset(double value); + + // double ax = 20; + void clear_ax(); + static const int kAxFieldNumber = 20; + double ax() const; + void set_ax(double value); + + // double ax_offset = 21; + void clear_ax_offset(); + static const int kAxOffsetFieldNumber = 21; + double ax_offset() const; + void set_ax_offset(double value); + + // double ay = 23; + void clear_ay(); + static const int kAyFieldNumber = 23; + double ay() const; + void set_ay(double value); + + // double ay_offset = 24; + void clear_ay_offset(); + static const int kAyOffsetFieldNumber = 24; + double ay_offset() const; + void set_ay_offset(double value); + + // double lat_acc = 25; + void clear_lat_acc(); + static const int kLatAccFieldNumber = 25; + double lat_acc() const; + void set_lat_acc(double value); + + // double long_acc = 26; + void clear_long_acc(); + static const int kLongAccFieldNumber = 26; + double long_acc() const; + void set_long_acc(double value); + + // double vert_acc = 27; + void clear_vert_acc(); + static const int kVertAccFieldNumber = 27; + double vert_acc() const; + void set_vert_acc(double value); + + // double roll_rate = 28; + void clear_roll_rate(); + static const int kRollRateFieldNumber = 28; + double roll_rate() const; + void set_roll_rate(double value); + + // double acc_est = 29; + void clear_acc_est(); + static const int kAccEstFieldNumber = 29; + double acc_est() const; + void set_acc_est(double value); + + // double timestamp_sec = 30; + void clear_timestamp_sec(); + static const int kTimestampSecFieldNumber = 30; + double timestamp_sec() const; + void set_timestamp_sec(double value); + + // bool is_ay_valid = 22; + void clear_is_ay_valid(); + static const int kIsAyValidFieldNumber = 22; + bool is_ay_valid() const; + void set_is_ay_valid(bool value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.VehicleSpd) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double vehicle_spd_; + bool is_vehicle_standstill_; + bool is_vehicle_spd_valid_; + bool is_wheel_spd_rr_valid_; + bool is_wheel_spd_rl_valid_; + int wheel_direction_rr_; + double wheel_spd_rr_; + double wheel_spd_rl_; + int wheel_direction_rl_; + int wheel_direction_fr_; + double wheel_spd_fr_; + int wheel_direction_fl_; + bool is_wheel_spd_fr_valid_; + bool is_wheel_spd_fl_valid_; + bool is_yaw_rate_valid_; + bool is_ax_valid_; + double wheel_spd_fl_; + double yaw_rate_; + double yaw_rate_offset_; + double ax_; + double ax_offset_; + double ay_; + double ay_offset_; + double lat_acc_; + double long_acc_; + double vert_acc_; + double roll_rate_; + double acc_est_; + double timestamp_sec_; + bool is_ay_valid_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Deceleration : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.Deceleration) */ { + public: + Deceleration(); + virtual ~Deceleration(); + + Deceleration(const Deceleration& from); + + inline Deceleration& operator=(const Deceleration& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Deceleration(Deceleration&& from) noexcept + : Deceleration() { + *this = ::std::move(from); + } + + inline Deceleration& operator=(Deceleration&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Deceleration& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Deceleration* internal_default_instance() { + return reinterpret_cast( + &_Deceleration_default_instance_); + } + static constexpr int kIndexInFileMessages = + 6; + + void Swap(Deceleration* other); + friend void swap(Deceleration& a, Deceleration& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Deceleration* New() const final { + return CreateMaybeMessage(NULL); + } + + Deceleration* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Deceleration& from); + void MergeFrom(const Deceleration& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Deceleration* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double deceleration = 3; + void clear_deceleration(); + static const int kDecelerationFieldNumber = 3; + double deceleration() const; + void set_deceleration(double value); + + // double is_evb_fail = 4; + void clear_is_evb_fail(); + static const int kIsEvbFailFieldNumber = 4; + double is_evb_fail() const; + void set_is_evb_fail(double value); + + // double evb_pressure = 5; + void clear_evb_pressure(); + static const int kEvbPressureFieldNumber = 5; + double evb_pressure() const; + void set_evb_pressure(double value); + + // double brake_pressure = 6; + void clear_brake_pressure(); + static const int kBrakePressureFieldNumber = 6; + double brake_pressure() const; + void set_brake_pressure(double value); + + // double brake_pressure_spd = 7; + void clear_brake_pressure_spd(); + static const int kBrakePressureSpdFieldNumber = 7; + double brake_pressure_spd() const; + void set_brake_pressure_spd(double value); + + // bool is_deceleration_available = 1; + void clear_is_deceleration_available(); + static const int kIsDecelerationAvailableFieldNumber = 1; + bool is_deceleration_available() const; + void set_is_deceleration_available(bool value); + + // bool is_deceleration_active = 2; + void clear_is_deceleration_active(); + static const int kIsDecelerationActiveFieldNumber = 2; + bool is_deceleration_active() const; + void set_is_deceleration_active(bool value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.Deceleration) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double deceleration_; + double is_evb_fail_; + double evb_pressure_; + double brake_pressure_; + double brake_pressure_spd_; + bool is_deceleration_available_; + bool is_deceleration_active_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Brake : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.Brake) */ { + public: + Brake(); + virtual ~Brake(); + + Brake(const Brake& from); + + inline Brake& operator=(const Brake& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Brake(Brake&& from) noexcept + : Brake() { + *this = ::std::move(from); + } + + inline Brake& operator=(Brake&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Brake& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Brake* internal_default_instance() { + return reinterpret_cast( + &_Brake_default_instance_); + } + static constexpr int kIndexInFileMessages = + 7; + + void Swap(Brake* other); + friend void swap(Brake& a, Brake& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Brake* New() const final { + return CreateMaybeMessage(NULL); + } + + Brake* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Brake& from); + void MergeFrom(const Brake& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Brake* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef Brake_HSAStatusType HSAStatusType; + static const HSAStatusType HSA_INACTIVE = + Brake_HSAStatusType_HSA_INACTIVE; + static const HSAStatusType HSA_FINDING_GRADIENT = + Brake_HSAStatusType_HSA_FINDING_GRADIENT; + static const HSAStatusType HSA_ACTIVE_PRESSED = + Brake_HSAStatusType_HSA_ACTIVE_PRESSED; + static const HSAStatusType HSA_ACTIVE_RELEASED = + Brake_HSAStatusType_HSA_ACTIVE_RELEASED; + static const HSAStatusType HSA_FAST_RELEASE = + Brake_HSAStatusType_HSA_FAST_RELEASE; + static const HSAStatusType HSA_SLOW_RELEASE = + Brake_HSAStatusType_HSA_SLOW_RELEASE; + static const HSAStatusType HSA_FAILED = + Brake_HSAStatusType_HSA_FAILED; + static const HSAStatusType HSA_UNDEFINED = + Brake_HSAStatusType_HSA_UNDEFINED; + static inline bool HSAStatusType_IsValid(int value) { + return Brake_HSAStatusType_IsValid(value); + } + static const HSAStatusType HSAStatusType_MIN = + Brake_HSAStatusType_HSAStatusType_MIN; + static const HSAStatusType HSAStatusType_MAX = + Brake_HSAStatusType_HSAStatusType_MAX; + static const int HSAStatusType_ARRAYSIZE = + Brake_HSAStatusType_HSAStatusType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + HSAStatusType_descriptor() { + return Brake_HSAStatusType_descriptor(); + } + static inline const ::std::string& HSAStatusType_Name(HSAStatusType value) { + return Brake_HSAStatusType_Name(value); + } + static inline bool HSAStatusType_Parse(const ::std::string& name, + HSAStatusType* value) { + return Brake_HSAStatusType_Parse(name, value); + } + + typedef Brake_HSAModeType HSAModeType; + static const HSAModeType HSA_OFF = + Brake_HSAModeType_HSA_OFF; + static const HSAModeType HSA_AUTO = + Brake_HSAModeType_HSA_AUTO; + static const HSAModeType HSA_MANUAL = + Brake_HSAModeType_HSA_MANUAL; + static const HSAModeType HSA_MODE_UNDEFINED = + Brake_HSAModeType_HSA_MODE_UNDEFINED; + static inline bool HSAModeType_IsValid(int value) { + return Brake_HSAModeType_IsValid(value); + } + static const HSAModeType HSAModeType_MIN = + Brake_HSAModeType_HSAModeType_MIN; + static const HSAModeType HSAModeType_MAX = + Brake_HSAModeType_HSAModeType_MAX; + static const int HSAModeType_ARRAYSIZE = + Brake_HSAModeType_HSAModeType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + HSAModeType_descriptor() { + return Brake_HSAModeType_descriptor(); + } + static inline const ::std::string& HSAModeType_Name(HSAModeType value) { + return Brake_HSAModeType_Name(value); + } + static inline bool HSAModeType_Parse(const ::std::string& name, + HSAModeType* value) { + return Brake_HSAModeType_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // double brake_pedal_position = 5; + void clear_brake_pedal_position(); + static const int kBrakePedalPositionFieldNumber = 5; + double brake_pedal_position() const; + void set_brake_pedal_position(double value); + + // bool is_brake_pedal_pressed = 1; + void clear_is_brake_pedal_pressed(); + static const int kIsBrakePedalPressedFieldNumber = 1; + bool is_brake_pedal_pressed() const; + void set_is_brake_pedal_pressed(bool value); + + // bool is_brake_force_exist = 2; + void clear_is_brake_force_exist(); + static const int kIsBrakeForceExistFieldNumber = 2; + bool is_brake_force_exist() const; + void set_is_brake_force_exist(bool value); + + // bool is_brake_over_heat = 3; + void clear_is_brake_over_heat(); + static const int kIsBrakeOverHeatFieldNumber = 3; + bool is_brake_over_heat() const; + void set_is_brake_over_heat(bool value); + + // bool is_hand_brake_on = 4; + void clear_is_hand_brake_on(); + static const int kIsHandBrakeOnFieldNumber = 4; + bool is_hand_brake_on() const; + void set_is_hand_brake_on(bool value); + + // bool is_brake_valid = 6; + void clear_is_brake_valid(); + static const int kIsBrakeValidFieldNumber = 6; + bool is_brake_valid() const; + void set_is_brake_valid(bool value); + + // bool boo_input = 10; + void clear_boo_input(); + static const int kBooInputFieldNumber = 10; + bool boo_input() const; + void set_boo_input(bool value); + + // bool boo_cmd = 11; + void clear_boo_cmd(); + static const int kBooCmdFieldNumber = 11; + bool boo_cmd() const; + void set_boo_cmd(bool value); + + // bool boo_output = 12; + void clear_boo_output(); + static const int kBooOutputFieldNumber = 12; + bool boo_output() const; + void set_boo_output(bool value); + + // double brake_input = 7; + void clear_brake_input(); + static const int kBrakeInputFieldNumber = 7; + double brake_input() const; + void set_brake_input(double value); + + // double brake_cmd = 8; + void clear_brake_cmd(); + static const int kBrakeCmdFieldNumber = 8; + double brake_cmd() const; + void set_brake_cmd(double value); + + // double brake_output = 9; + void clear_brake_output(); + static const int kBrakeOutputFieldNumber = 9; + double brake_output() const; + void set_brake_output(double value); + + // int32 watchdog_source = 14; + void clear_watchdog_source(); + static const int kWatchdogSourceFieldNumber = 14; + ::google::protobuf::int32 watchdog_source() const; + void set_watchdog_source(::google::protobuf::int32 value); + + // bool watchdog_applying_brakes = 13; + void clear_watchdog_applying_brakes(); + static const int kWatchdogApplyingBrakesFieldNumber = 13; + bool watchdog_applying_brakes() const; + void set_watchdog_applying_brakes(bool value); + + // bool brake_enabled = 15; + void clear_brake_enabled(); + static const int kBrakeEnabledFieldNumber = 15; + bool brake_enabled() const; + void set_brake_enabled(bool value); + + // bool driver_override = 16; + void clear_driver_override(); + static const int kDriverOverrideFieldNumber = 16; + bool driver_override() const; + void set_driver_override(bool value); + + // bool driver_activity = 17; + void clear_driver_activity(); + static const int kDriverActivityFieldNumber = 17; + bool driver_activity() const; + void set_driver_activity(bool value); + + // bool watchdog_fault = 18; + void clear_watchdog_fault(); + static const int kWatchdogFaultFieldNumber = 18; + bool watchdog_fault() const; + void set_watchdog_fault(bool value); + + // bool channel_1_fault = 19; + void clear_channel_1_fault(); + static const int kChannel1FaultFieldNumber = 19; + bool channel_1_fault() const; + void set_channel_1_fault(bool value); + + // bool channel_2_fault = 20; + void clear_channel_2_fault(); + static const int kChannel2FaultFieldNumber = 20; + bool channel_2_fault() const; + void set_channel_2_fault(bool value); + + // bool boo_fault = 21; + void clear_boo_fault(); + static const int kBooFaultFieldNumber = 21; + bool boo_fault() const; + void set_boo_fault(bool value); + + // bool connector_fault = 22; + void clear_connector_fault(); + static const int kConnectorFaultFieldNumber = 22; + bool connector_fault() const; + void set_connector_fault(bool value); + + // int32 brake_torque_req = 23; + void clear_brake_torque_req(); + static const int kBrakeTorqueReqFieldNumber = 23; + ::google::protobuf::int32 brake_torque_req() const; + void set_brake_torque_req(::google::protobuf::int32 value); + + // .apollo.canbus.Brake.HSAStatusType hsa_status = 24; + void clear_hsa_status(); + static const int kHsaStatusFieldNumber = 24; + ::apollo::canbus::Brake_HSAStatusType hsa_status() const; + void set_hsa_status(::apollo::canbus::Brake_HSAStatusType value); + + // int32 brake_torque_act = 25; + void clear_brake_torque_act(); + static const int kBrakeTorqueActFieldNumber = 25; + ::google::protobuf::int32 brake_torque_act() const; + void set_brake_torque_act(::google::protobuf::int32 value); + + // .apollo.canbus.Brake.HSAModeType hsa_mode = 26; + void clear_hsa_mode(); + static const int kHsaModeFieldNumber = 26; + ::apollo::canbus::Brake_HSAModeType hsa_mode() const; + void set_hsa_mode(::apollo::canbus::Brake_HSAModeType value); + + // int32 wheel_torque_act = 27; + void clear_wheel_torque_act(); + static const int kWheelTorqueActFieldNumber = 27; + ::google::protobuf::int32 wheel_torque_act() const; + void set_wheel_torque_act(::google::protobuf::int32 value); + + // int32 major_version = 28; + void clear_major_version(); + static const int kMajorVersionFieldNumber = 28; + ::google::protobuf::int32 major_version() const; + void set_major_version(::google::protobuf::int32 value); + + // int32 minor_version = 29; + void clear_minor_version(); + static const int kMinorVersionFieldNumber = 29; + ::google::protobuf::int32 minor_version() const; + void set_minor_version(::google::protobuf::int32 value); + + // int32 build_number = 30; + void clear_build_number(); + static const int kBuildNumberFieldNumber = 30; + ::google::protobuf::int32 build_number() const; + void set_build_number(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.Brake) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double brake_pedal_position_; + bool is_brake_pedal_pressed_; + bool is_brake_force_exist_; + bool is_brake_over_heat_; + bool is_hand_brake_on_; + bool is_brake_valid_; + bool boo_input_; + bool boo_cmd_; + bool boo_output_; + double brake_input_; + double brake_cmd_; + double brake_output_; + ::google::protobuf::int32 watchdog_source_; + bool watchdog_applying_brakes_; + bool brake_enabled_; + bool driver_override_; + bool driver_activity_; + bool watchdog_fault_; + bool channel_1_fault_; + bool channel_2_fault_; + bool boo_fault_; + bool connector_fault_; + ::google::protobuf::int32 brake_torque_req_; + int hsa_status_; + ::google::protobuf::int32 brake_torque_act_; + int hsa_mode_; + ::google::protobuf::int32 wheel_torque_act_; + ::google::protobuf::int32 major_version_; + ::google::protobuf::int32 minor_version_; + ::google::protobuf::int32 build_number_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Epb : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.Epb) */ { + public: + Epb(); + virtual ~Epb(); + + Epb(const Epb& from); + + inline Epb& operator=(const Epb& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Epb(Epb&& from) noexcept + : Epb() { + *this = ::std::move(from); + } + + inline Epb& operator=(Epb&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Epb& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Epb* internal_default_instance() { + return reinterpret_cast( + &_Epb_default_instance_); + } + static constexpr int kIndexInFileMessages = + 8; + + void Swap(Epb* other); + friend void swap(Epb& a, Epb& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Epb* New() const final { + return CreateMaybeMessage(NULL); + } + + Epb* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Epb& from); + void MergeFrom(const Epb& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Epb* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef Epb_PBrakeType PBrakeType; + static const PBrakeType PBRAKE_OFF = + Epb_PBrakeType_PBRAKE_OFF; + static const PBrakeType PBRAKE_TRANSITION = + Epb_PBrakeType_PBRAKE_TRANSITION; + static const PBrakeType PBRAKE_ON = + Epb_PBrakeType_PBRAKE_ON; + static const PBrakeType PBRAKE_FAULT = + Epb_PBrakeType_PBRAKE_FAULT; + static inline bool PBrakeType_IsValid(int value) { + return Epb_PBrakeType_IsValid(value); + } + static const PBrakeType PBrakeType_MIN = + Epb_PBrakeType_PBrakeType_MIN; + static const PBrakeType PBrakeType_MAX = + Epb_PBrakeType_PBrakeType_MAX; + static const int PBrakeType_ARRAYSIZE = + Epb_PBrakeType_PBrakeType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + PBrakeType_descriptor() { + return Epb_PBrakeType_descriptor(); + } + static inline const ::std::string& PBrakeType_Name(PBrakeType value) { + return Epb_PBrakeType_Name(value); + } + static inline bool PBrakeType_Parse(const ::std::string& name, + PBrakeType* value) { + return Epb_PBrakeType_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // bool is_epb_error = 1; + void clear_is_epb_error(); + static const int kIsEpbErrorFieldNumber = 1; + bool is_epb_error() const; + void set_is_epb_error(bool value); + + // bool is_epb_released = 2; + void clear_is_epb_released(); + static const int kIsEpbReleasedFieldNumber = 2; + bool is_epb_released() const; + void set_is_epb_released(bool value); + + // int32 epb_status = 3; + void clear_epb_status(); + static const int kEpbStatusFieldNumber = 3; + ::google::protobuf::int32 epb_status() const; + void set_epb_status(::google::protobuf::int32 value); + + // .apollo.canbus.Epb.PBrakeType parking_brake_status = 4; + void clear_parking_brake_status(); + static const int kParkingBrakeStatusFieldNumber = 4; + ::apollo::canbus::Epb_PBrakeType parking_brake_status() const; + void set_parking_brake_status(::apollo::canbus::Epb_PBrakeType value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.Epb) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + bool is_epb_error_; + bool is_epb_released_; + ::google::protobuf::int32 epb_status_; + int parking_brake_status_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Gas : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.Gas) */ { + public: + Gas(); + virtual ~Gas(); + + Gas(const Gas& from); + + inline Gas& operator=(const Gas& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Gas(Gas&& from) noexcept + : Gas() { + *this = ::std::move(from); + } + + inline Gas& operator=(Gas&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Gas& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Gas* internal_default_instance() { + return reinterpret_cast( + &_Gas_default_instance_); + } + static constexpr int kIndexInFileMessages = + 9; + + void Swap(Gas* other); + friend void swap(Gas& a, Gas& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Gas* New() const final { + return CreateMaybeMessage(NULL); + } + + Gas* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Gas& from); + void MergeFrom(const Gas& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Gas* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double gas_pedal_position = 3; + void clear_gas_pedal_position(); + static const int kGasPedalPositionFieldNumber = 3; + double gas_pedal_position() const; + void set_gas_pedal_position(double value); + + // bool is_gas_pedal_error = 1; + void clear_is_gas_pedal_error(); + static const int kIsGasPedalErrorFieldNumber = 1; + bool is_gas_pedal_error() const; + void set_is_gas_pedal_error(bool value); + + // bool is_gas_pedal_pressed_more = 2; + void clear_is_gas_pedal_pressed_more(); + static const int kIsGasPedalPressedMoreFieldNumber = 2; + bool is_gas_pedal_pressed_more() const; + void set_is_gas_pedal_pressed_more(bool value); + + // bool is_gas_valid = 4; + void clear_is_gas_valid(); + static const int kIsGasValidFieldNumber = 4; + bool is_gas_valid() const; + void set_is_gas_valid(bool value); + + // bool throttle_enabled = 9; + void clear_throttle_enabled(); + static const int kThrottleEnabledFieldNumber = 9; + bool throttle_enabled() const; + void set_throttle_enabled(bool value); + + // int32 watchdog_source = 8; + void clear_watchdog_source(); + static const int kWatchdogSourceFieldNumber = 8; + ::google::protobuf::int32 watchdog_source() const; + void set_watchdog_source(::google::protobuf::int32 value); + + // double throttle_input = 5; + void clear_throttle_input(); + static const int kThrottleInputFieldNumber = 5; + double throttle_input() const; + void set_throttle_input(double value); + + // double throttle_cmd = 6; + void clear_throttle_cmd(); + static const int kThrottleCmdFieldNumber = 6; + double throttle_cmd() const; + void set_throttle_cmd(double value); + + // double throttle_output = 7; + void clear_throttle_output(); + static const int kThrottleOutputFieldNumber = 7; + double throttle_output() const; + void set_throttle_output(double value); + + // bool driver_override = 10; + void clear_driver_override(); + static const int kDriverOverrideFieldNumber = 10; + bool driver_override() const; + void set_driver_override(bool value); + + // bool driver_activity = 11; + void clear_driver_activity(); + static const int kDriverActivityFieldNumber = 11; + bool driver_activity() const; + void set_driver_activity(bool value); + + // bool watchdog_fault = 12; + void clear_watchdog_fault(); + static const int kWatchdogFaultFieldNumber = 12; + bool watchdog_fault() const; + void set_watchdog_fault(bool value); + + // bool channel_1_fault = 13; + void clear_channel_1_fault(); + static const int kChannel1FaultFieldNumber = 13; + bool channel_1_fault() const; + void set_channel_1_fault(bool value); + + // bool channel_2_fault = 14; + void clear_channel_2_fault(); + static const int kChannel2FaultFieldNumber = 14; + bool channel_2_fault() const; + void set_channel_2_fault(bool value); + + // bool connector_fault = 15; + void clear_connector_fault(); + static const int kConnectorFaultFieldNumber = 15; + bool connector_fault() const; + void set_connector_fault(bool value); + + // double accelerator_pedal = 16; + void clear_accelerator_pedal(); + static const int kAcceleratorPedalFieldNumber = 16; + double accelerator_pedal() const; + void set_accelerator_pedal(double value); + + // double accelerator_pedal_rate = 17; + void clear_accelerator_pedal_rate(); + static const int kAcceleratorPedalRateFieldNumber = 17; + double accelerator_pedal_rate() const; + void set_accelerator_pedal_rate(double value); + + // int32 major_version = 18; + void clear_major_version(); + static const int kMajorVersionFieldNumber = 18; + ::google::protobuf::int32 major_version() const; + void set_major_version(::google::protobuf::int32 value); + + // int32 minor_version = 19; + void clear_minor_version(); + static const int kMinorVersionFieldNumber = 19; + ::google::protobuf::int32 minor_version() const; + void set_minor_version(::google::protobuf::int32 value); + + // int32 build_number = 20; + void clear_build_number(); + static const int kBuildNumberFieldNumber = 20; + ::google::protobuf::int32 build_number() const; + void set_build_number(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.Gas) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double gas_pedal_position_; + bool is_gas_pedal_error_; + bool is_gas_pedal_pressed_more_; + bool is_gas_valid_; + bool throttle_enabled_; + ::google::protobuf::int32 watchdog_source_; + double throttle_input_; + double throttle_cmd_; + double throttle_output_; + bool driver_override_; + bool driver_activity_; + bool watchdog_fault_; + bool channel_1_fault_; + bool channel_2_fault_; + bool connector_fault_; + double accelerator_pedal_; + double accelerator_pedal_rate_; + ::google::protobuf::int32 major_version_; + ::google::protobuf::int32 minor_version_; + ::google::protobuf::int32 build_number_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Esp : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.Esp) */ { + public: + Esp(); + virtual ~Esp(); + + Esp(const Esp& from); + + inline Esp& operator=(const Esp& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Esp(Esp&& from) noexcept + : Esp() { + *this = ::std::move(from); + } + + inline Esp& operator=(Esp&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Esp& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Esp* internal_default_instance() { + return reinterpret_cast( + &_Esp_default_instance_); + } + static constexpr int kIndexInFileMessages = + 10; + + void Swap(Esp* other); + friend void swap(Esp& a, Esp& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Esp* New() const final { + return CreateMaybeMessage(NULL); + } + + Esp* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Esp& from); + void MergeFrom(const Esp& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Esp* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // bool is_esp_acc_error = 1; + void clear_is_esp_acc_error(); + static const int kIsEspAccErrorFieldNumber = 1; + bool is_esp_acc_error() const; + void set_is_esp_acc_error(bool value); + + // bool is_esp_on = 2; + void clear_is_esp_on(); + static const int kIsEspOnFieldNumber = 2; + bool is_esp_on() const; + void set_is_esp_on(bool value); + + // bool is_esp_active = 3; + void clear_is_esp_active(); + static const int kIsEspActiveFieldNumber = 3; + bool is_esp_active() const; + void set_is_esp_active(bool value); + + // bool is_abs_error = 4; + void clear_is_abs_error(); + static const int kIsAbsErrorFieldNumber = 4; + bool is_abs_error() const; + void set_is_abs_error(bool value); + + // bool is_abs_active = 5; + void clear_is_abs_active(); + static const int kIsAbsActiveFieldNumber = 5; + bool is_abs_active() const; + void set_is_abs_active(bool value); + + // bool is_tcsvdc_fail = 6; + void clear_is_tcsvdc_fail(); + static const int kIsTcsvdcFailFieldNumber = 6; + bool is_tcsvdc_fail() const; + void set_is_tcsvdc_fail(bool value); + + // bool is_abs_enabled = 7; + void clear_is_abs_enabled(); + static const int kIsAbsEnabledFieldNumber = 7; + bool is_abs_enabled() const; + void set_is_abs_enabled(bool value); + + // bool is_stab_active = 8; + void clear_is_stab_active(); + static const int kIsStabActiveFieldNumber = 8; + bool is_stab_active() const; + void set_is_stab_active(bool value); + + // bool is_stab_enabled = 9; + void clear_is_stab_enabled(); + static const int kIsStabEnabledFieldNumber = 9; + bool is_stab_enabled() const; + void set_is_stab_enabled(bool value); + + // bool is_trac_active = 10; + void clear_is_trac_active(); + static const int kIsTracActiveFieldNumber = 10; + bool is_trac_active() const; + void set_is_trac_active(bool value); + + // bool is_trac_enabled = 11; + void clear_is_trac_enabled(); + static const int kIsTracEnabledFieldNumber = 11; + bool is_trac_enabled() const; + void set_is_trac_enabled(bool value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.Esp) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + bool is_esp_acc_error_; + bool is_esp_on_; + bool is_esp_active_; + bool is_abs_error_; + bool is_abs_active_; + bool is_tcsvdc_fail_; + bool is_abs_enabled_; + bool is_stab_active_; + bool is_stab_enabled_; + bool is_trac_active_; + bool is_trac_enabled_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Ems : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.Ems) */ { + public: + Ems(); + virtual ~Ems(); + + Ems(const Ems& from); + + inline Ems& operator=(const Ems& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Ems(Ems&& from) noexcept + : Ems() { + *this = ::std::move(from); + } + + inline Ems& operator=(Ems&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Ems& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Ems* internal_default_instance() { + return reinterpret_cast( + &_Ems_default_instance_); + } + static constexpr int kIndexInFileMessages = + 11; + + void Swap(Ems* other); + friend void swap(Ems& a, Ems& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Ems* New() const final { + return CreateMaybeMessage(NULL); + } + + Ems* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Ems& from); + void MergeFrom(const Ems& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Ems* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef Ems_Type Type; + static const Type STOP = + Ems_Type_STOP; + static const Type CRANK = + Ems_Type_CRANK; + static const Type RUNNING = + Ems_Type_RUNNING; + static const Type INVALID = + Ems_Type_INVALID; + static inline bool Type_IsValid(int value) { + return Ems_Type_IsValid(value); + } + static const Type Type_MIN = + Ems_Type_Type_MIN; + static const Type Type_MAX = + Ems_Type_Type_MAX; + static const int Type_ARRAYSIZE = + Ems_Type_Type_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Type_descriptor() { + return Ems_Type_descriptor(); + } + static inline const ::std::string& Type_Name(Type value) { + return Ems_Type_Name(value); + } + static inline bool Type_Parse(const ::std::string& name, + Type* value) { + return Ems_Type_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // double max_engine_torq_percent = 4; + void clear_max_engine_torq_percent(); + static const int kMaxEngineTorqPercentFieldNumber = 4; + double max_engine_torq_percent() const; + void set_max_engine_torq_percent(double value); + + // .apollo.canbus.Ems.Type engine_state = 3; + void clear_engine_state(); + static const int kEngineStateFieldNumber = 3; + ::apollo::canbus::Ems_Type engine_state() const; + void set_engine_state(::apollo::canbus::Ems_Type value); + + // bool is_engine_acc_available = 1; + void clear_is_engine_acc_available(); + static const int kIsEngineAccAvailableFieldNumber = 1; + bool is_engine_acc_available() const; + void set_is_engine_acc_available(bool value); + + // bool is_engine_acc_error = 2; + void clear_is_engine_acc_error(); + static const int kIsEngineAccErrorFieldNumber = 2; + bool is_engine_acc_error() const; + void set_is_engine_acc_error(bool value); + + // bool is_engine_speed_error = 7; + void clear_is_engine_speed_error(); + static const int kIsEngineSpeedErrorFieldNumber = 7; + bool is_engine_speed_error() const; + void set_is_engine_speed_error(bool value); + + // bool is_over_engine_torque = 10; + void clear_is_over_engine_torque(); + static const int kIsOverEngineTorqueFieldNumber = 10; + bool is_over_engine_torque() const; + void set_is_over_engine_torque(bool value); + + // double min_engine_torq_percent = 5; + void clear_min_engine_torq_percent(); + static const int kMinEngineTorqPercentFieldNumber = 5; + double min_engine_torq_percent() const; + void set_min_engine_torq_percent(double value); + + // int32 base_engine_torq_constant = 6; + void clear_base_engine_torq_constant(); + static const int kBaseEngineTorqConstantFieldNumber = 6; + ::google::protobuf::int32 base_engine_torq_constant() const; + void set_base_engine_torq_constant(::google::protobuf::int32 value); + + // int32 engine_torque = 9; + void clear_engine_torque(); + static const int kEngineTorqueFieldNumber = 9; + ::google::protobuf::int32 engine_torque() const; + void set_engine_torque(::google::protobuf::int32 value); + + // double engine_speed = 8; + void clear_engine_speed(); + static const int kEngineSpeedFieldNumber = 8; + double engine_speed() const; + void set_engine_speed(double value); + + // double engine_rpm = 11; + void clear_engine_rpm(); + static const int kEngineRpmFieldNumber = 11; + double engine_rpm() const; + void set_engine_rpm(double value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.Ems) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double max_engine_torq_percent_; + int engine_state_; + bool is_engine_acc_available_; + bool is_engine_acc_error_; + bool is_engine_speed_error_; + bool is_over_engine_torque_; + double min_engine_torq_percent_; + ::google::protobuf::int32 base_engine_torq_constant_; + ::google::protobuf::int32 engine_torque_; + double engine_speed_; + double engine_rpm_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Gear : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.Gear) */ { + public: + Gear(); + virtual ~Gear(); + + Gear(const Gear& from); + + inline Gear& operator=(const Gear& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Gear(Gear&& from) noexcept + : Gear() { + *this = ::std::move(from); + } + + inline Gear& operator=(Gear&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Gear& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Gear* internal_default_instance() { + return reinterpret_cast( + &_Gear_default_instance_); + } + static constexpr int kIndexInFileMessages = + 12; + + void Swap(Gear* other); + friend void swap(Gear& a, Gear& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Gear* New() const final { + return CreateMaybeMessage(NULL); + } + + Gear* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Gear& from); + void MergeFrom(const Gear& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Gear* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.canbus.Chassis.GearPosition gear_state = 2; + void clear_gear_state(); + static const int kGearStateFieldNumber = 2; + ::apollo::canbus::Chassis_GearPosition gear_state() const; + void set_gear_state(::apollo::canbus::Chassis_GearPosition value); + + // bool is_shift_position_valid = 1; + void clear_is_shift_position_valid(); + static const int kIsShiftPositionValidFieldNumber = 1; + bool is_shift_position_valid() const; + void set_is_shift_position_valid(bool value); + + // bool driver_override = 3; + void clear_driver_override(); + static const int kDriverOverrideFieldNumber = 3; + bool driver_override() const; + void set_driver_override(bool value); + + // bool canbus_fault = 5; + void clear_canbus_fault(); + static const int kCanbusFaultFieldNumber = 5; + bool canbus_fault() const; + void set_canbus_fault(bool value); + + // .apollo.canbus.Chassis.GearPosition gear_cmd = 4; + void clear_gear_cmd(); + static const int kGearCmdFieldNumber = 4; + ::apollo::canbus::Chassis_GearPosition gear_cmd() const; + void set_gear_cmd(::apollo::canbus::Chassis_GearPosition value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.Gear) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + int gear_state_; + bool is_shift_position_valid_; + bool driver_override_; + bool canbus_fault_; + int gear_cmd_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Safety : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.Safety) */ { + public: + Safety(); + virtual ~Safety(); + + Safety(const Safety& from); + + inline Safety& operator=(const Safety& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Safety(Safety&& from) noexcept + : Safety() { + *this = ::std::move(from); + } + + inline Safety& operator=(Safety&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Safety& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Safety* internal_default_instance() { + return reinterpret_cast( + &_Safety_default_instance_); + } + static constexpr int kIndexInFileMessages = + 13; + + void Swap(Safety* other); + friend void swap(Safety& a, Safety& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Safety* New() const final { + return CreateMaybeMessage(NULL); + } + + Safety* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Safety& from); + void MergeFrom(const Safety& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Safety* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // int32 emergency_button = 3; + void clear_emergency_button(); + static const int kEmergencyButtonFieldNumber = 3; + ::google::protobuf::int32 emergency_button() const; + void set_emergency_button(::google::protobuf::int32 value); + + // bool is_driver_car_door_close = 1; + void clear_is_driver_car_door_close(); + static const int kIsDriverCarDoorCloseFieldNumber = 1; + bool is_driver_car_door_close() const; + void set_is_driver_car_door_close(bool value); + + // bool is_driver_buckled = 2; + void clear_is_driver_buckled(); + static const int kIsDriverBuckledFieldNumber = 2; + bool is_driver_buckled() const; + void set_is_driver_buckled(bool value); + + // bool has_error = 4; + void clear_has_error(); + static const int kHasErrorFieldNumber = 4; + bool has_error() const; + void set_has_error(bool value); + + // bool is_motor_invertor_fault = 5; + void clear_is_motor_invertor_fault(); + static const int kIsMotorInvertorFaultFieldNumber = 5; + bool is_motor_invertor_fault() const; + void set_is_motor_invertor_fault(bool value); + + // bool is_system_fault = 6; + void clear_is_system_fault(); + static const int kIsSystemFaultFieldNumber = 6; + bool is_system_fault() const; + void set_is_system_fault(bool value); + + // bool is_power_battery_fault = 7; + void clear_is_power_battery_fault(); + static const int kIsPowerBatteryFaultFieldNumber = 7; + bool is_power_battery_fault() const; + void set_is_power_battery_fault(bool value); + + // bool is_motor_invertor_over_temperature = 8; + void clear_is_motor_invertor_over_temperature(); + static const int kIsMotorInvertorOverTemperatureFieldNumber = 8; + bool is_motor_invertor_over_temperature() const; + void set_is_motor_invertor_over_temperature(bool value); + + // bool is_small_battery_charge_discharge_fault = 9; + void clear_is_small_battery_charge_discharge_fault(); + static const int kIsSmallBatteryChargeDischargeFaultFieldNumber = 9; + bool is_small_battery_charge_discharge_fault() const; + void set_is_small_battery_charge_discharge_fault(bool value); + + // int32 driving_mode = 10; + void clear_driving_mode(); + static const int kDrivingModeFieldNumber = 10; + ::google::protobuf::int32 driving_mode() const; + void set_driving_mode(::google::protobuf::int32 value); + + // bool is_passenger_door_open = 11; + void clear_is_passenger_door_open(); + static const int kIsPassengerDoorOpenFieldNumber = 11; + bool is_passenger_door_open() const; + void set_is_passenger_door_open(bool value); + + // bool is_rearleft_door_open = 12; + void clear_is_rearleft_door_open(); + static const int kIsRearleftDoorOpenFieldNumber = 12; + bool is_rearleft_door_open() const; + void set_is_rearleft_door_open(bool value); + + // bool is_rearright_door_open = 13; + void clear_is_rearright_door_open(); + static const int kIsRearrightDoorOpenFieldNumber = 13; + bool is_rearright_door_open() const; + void set_is_rearright_door_open(bool value); + + // bool is_hood_open = 14; + void clear_is_hood_open(); + static const int kIsHoodOpenFieldNumber = 14; + bool is_hood_open() const; + void set_is_hood_open(bool value); + + // bool is_trunk_open = 15; + void clear_is_trunk_open(); + static const int kIsTrunkOpenFieldNumber = 15; + bool is_trunk_open() const; + void set_is_trunk_open(bool value); + + // bool is_passenger_detected = 16; + void clear_is_passenger_detected(); + static const int kIsPassengerDetectedFieldNumber = 16; + bool is_passenger_detected() const; + void set_is_passenger_detected(bool value); + + // bool is_passenger_airbag_enabled = 17; + void clear_is_passenger_airbag_enabled(); + static const int kIsPassengerAirbagEnabledFieldNumber = 17; + bool is_passenger_airbag_enabled() const; + void set_is_passenger_airbag_enabled(bool value); + + // bool is_passenger_buckled = 18; + void clear_is_passenger_buckled(); + static const int kIsPassengerBuckledFieldNumber = 18; + bool is_passenger_buckled() const; + void set_is_passenger_buckled(bool value); + + // int32 front_left_tire_press = 19; + void clear_front_left_tire_press(); + static const int kFrontLeftTirePressFieldNumber = 19; + ::google::protobuf::int32 front_left_tire_press() const; + void set_front_left_tire_press(::google::protobuf::int32 value); + + // int32 front_right_tire_press = 20; + void clear_front_right_tire_press(); + static const int kFrontRightTirePressFieldNumber = 20; + ::google::protobuf::int32 front_right_tire_press() const; + void set_front_right_tire_press(::google::protobuf::int32 value); + + // int32 rear_left_tire_press = 21; + void clear_rear_left_tire_press(); + static const int kRearLeftTirePressFieldNumber = 21; + ::google::protobuf::int32 rear_left_tire_press() const; + void set_rear_left_tire_press(::google::protobuf::int32 value); + + // int32 rear_right_tire_press = 22; + void clear_rear_right_tire_press(); + static const int kRearRightTirePressFieldNumber = 22; + ::google::protobuf::int32 rear_right_tire_press() const; + void set_rear_right_tire_press(::google::protobuf::int32 value); + + // .apollo.canbus.Chassis.DrivingMode car_driving_mode = 23; + void clear_car_driving_mode(); + static const int kCarDrivingModeFieldNumber = 23; + ::apollo::canbus::Chassis_DrivingMode car_driving_mode() const; + void set_car_driving_mode(::apollo::canbus::Chassis_DrivingMode value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.Safety) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 emergency_button_; + bool is_driver_car_door_close_; + bool is_driver_buckled_; + bool has_error_; + bool is_motor_invertor_fault_; + bool is_system_fault_; + bool is_power_battery_fault_; + bool is_motor_invertor_over_temperature_; + bool is_small_battery_charge_discharge_fault_; + ::google::protobuf::int32 driving_mode_; + bool is_passenger_door_open_; + bool is_rearleft_door_open_; + bool is_rearright_door_open_; + bool is_hood_open_; + bool is_trunk_open_; + bool is_passenger_detected_; + bool is_passenger_airbag_enabled_; + bool is_passenger_buckled_; + ::google::protobuf::int32 front_left_tire_press_; + ::google::protobuf::int32 front_right_tire_press_; + ::google::protobuf::int32 rear_left_tire_press_; + ::google::protobuf::int32 rear_right_tire_press_; + int car_driving_mode_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class BasicInfo : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.canbus.BasicInfo) */ { + public: + BasicInfo(); + virtual ~BasicInfo(); + + BasicInfo(const BasicInfo& from); + + inline BasicInfo& operator=(const BasicInfo& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + BasicInfo(BasicInfo&& from) noexcept + : BasicInfo() { + *this = ::std::move(from); + } + + inline BasicInfo& operator=(BasicInfo&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const BasicInfo& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const BasicInfo* internal_default_instance() { + return reinterpret_cast( + &_BasicInfo_default_instance_); + } + static constexpr int kIndexInFileMessages = + 14; + + void Swap(BasicInfo* other); + friend void swap(BasicInfo& a, BasicInfo& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline BasicInfo* New() const final { + return CreateMaybeMessage(NULL); + } + + BasicInfo* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const BasicInfo& from); + void MergeFrom(const BasicInfo& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(BasicInfo* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef BasicInfo_Type Type; + static const Type OFF = + BasicInfo_Type_OFF; + static const Type ACC = + BasicInfo_Type_ACC; + static const Type ON = + BasicInfo_Type_ON; + static const Type START = + BasicInfo_Type_START; + static const Type INVALID = + BasicInfo_Type_INVALID; + static inline bool Type_IsValid(int value) { + return BasicInfo_Type_IsValid(value); + } + static const Type Type_MIN = + BasicInfo_Type_Type_MIN; + static const Type Type_MAX = + BasicInfo_Type_Type_MAX; + static const int Type_ARRAYSIZE = + BasicInfo_Type_Type_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Type_descriptor() { + return BasicInfo_Type_descriptor(); + } + static inline const ::std::string& Type_Name(Type value) { + return BasicInfo_Type_Name(value); + } + static inline bool Type_Parse(const ::std::string& name, + Type* value) { + return BasicInfo_Type_Parse(name, value); + } + + typedef BasicInfo_GpsQuality GpsQuality; + static const GpsQuality FIX_NO = + BasicInfo_GpsQuality_FIX_NO; + static const GpsQuality FIX_2D = + BasicInfo_GpsQuality_FIX_2D; + static const GpsQuality FIX_3D = + BasicInfo_GpsQuality_FIX_3D; + static const GpsQuality FIX_INVALID = + BasicInfo_GpsQuality_FIX_INVALID; + static inline bool GpsQuality_IsValid(int value) { + return BasicInfo_GpsQuality_IsValid(value); + } + static const GpsQuality GpsQuality_MIN = + BasicInfo_GpsQuality_GpsQuality_MIN; + static const GpsQuality GpsQuality_MAX = + BasicInfo_GpsQuality_GpsQuality_MAX; + static const int GpsQuality_ARRAYSIZE = + BasicInfo_GpsQuality_GpsQuality_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + GpsQuality_descriptor() { + return BasicInfo_GpsQuality_descriptor(); + } + static inline const ::std::string& GpsQuality_Name(GpsQuality value) { + return BasicInfo_GpsQuality_Name(value); + } + static inline bool GpsQuality_Parse(const ::std::string& name, + GpsQuality* value) { + return BasicInfo_GpsQuality_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // .apollo.canbus.BasicInfo.Type power_state = 2; + void clear_power_state(); + static const int kPowerStateFieldNumber = 2; + ::apollo::canbus::BasicInfo_Type power_state() const; + void set_power_state(::apollo::canbus::BasicInfo_Type value); + + // bool is_auto_mode = 1; + void clear_is_auto_mode(); + static const int kIsAutoModeFieldNumber = 1; + bool is_auto_mode() const; + void set_is_auto_mode(bool value); + + // bool is_air_bag_deployed = 3; + void clear_is_air_bag_deployed(); + static const int kIsAirBagDeployedFieldNumber = 3; + bool is_air_bag_deployed() const; + void set_is_air_bag_deployed(bool value); + + // bool is_system_error = 6; + void clear_is_system_error(); + static const int kIsSystemErrorFieldNumber = 6; + bool is_system_error() const; + void set_is_system_error(bool value); + + // bool is_human_interrupt = 7; + void clear_is_human_interrupt(); + static const int kIsHumanInterruptFieldNumber = 7; + bool is_human_interrupt() const; + void set_is_human_interrupt(bool value); + + // double odo_meter = 4; + void clear_odo_meter(); + static const int kOdoMeterFieldNumber = 4; + double odo_meter() const; + void set_odo_meter(double value); + + // double drive_range = 5; + void clear_drive_range(); + static const int kDriveRangeFieldNumber = 5; + double drive_range() const; + void set_drive_range(double value); + + // bool acc_on_button = 8; + void clear_acc_on_button(); + static const int kAccOnButtonFieldNumber = 8; + bool acc_on_button() const; + void set_acc_on_button(bool value); + + // bool acc_off_button = 9; + void clear_acc_off_button(); + static const int kAccOffButtonFieldNumber = 9; + bool acc_off_button() const; + void set_acc_off_button(bool value); + + // bool acc_res_button = 10; + void clear_acc_res_button(); + static const int kAccResButtonFieldNumber = 10; + bool acc_res_button() const; + void set_acc_res_button(bool value); + + // bool acc_cancel_button = 11; + void clear_acc_cancel_button(); + static const int kAccCancelButtonFieldNumber = 11; + bool acc_cancel_button() const; + void set_acc_cancel_button(bool value); + + // bool acc_on_off_button = 12; + void clear_acc_on_off_button(); + static const int kAccOnOffButtonFieldNumber = 12; + bool acc_on_off_button() const; + void set_acc_on_off_button(bool value); + + // bool acc_res_cancel_button = 13; + void clear_acc_res_cancel_button(); + static const int kAccResCancelButtonFieldNumber = 13; + bool acc_res_cancel_button() const; + void set_acc_res_cancel_button(bool value); + + // bool acc_inc_spd_button = 14; + void clear_acc_inc_spd_button(); + static const int kAccIncSpdButtonFieldNumber = 14; + bool acc_inc_spd_button() const; + void set_acc_inc_spd_button(bool value); + + // bool acc_dec_spd_button = 15; + void clear_acc_dec_spd_button(); + static const int kAccDecSpdButtonFieldNumber = 15; + bool acc_dec_spd_button() const; + void set_acc_dec_spd_button(bool value); + + // bool acc_inc_gap_button = 16; + void clear_acc_inc_gap_button(); + static const int kAccIncGapButtonFieldNumber = 16; + bool acc_inc_gap_button() const; + void set_acc_inc_gap_button(bool value); + + // bool acc_dec_gap_button = 17; + void clear_acc_dec_gap_button(); + static const int kAccDecGapButtonFieldNumber = 17; + bool acc_dec_gap_button() const; + void set_acc_dec_gap_button(bool value); + + // bool lka_button = 18; + void clear_lka_button(); + static const int kLkaButtonFieldNumber = 18; + bool lka_button() const; + void set_lka_button(bool value); + + // bool canbus_fault = 19; + void clear_canbus_fault(); + static const int kCanbusFaultFieldNumber = 19; + bool canbus_fault() const; + void set_canbus_fault(bool value); + + // int32 year = 23; + void clear_year(); + static const int kYearFieldNumber = 23; + ::google::protobuf::int32 year() const; + void set_year(::google::protobuf::int32 value); + + // double latitude = 20; + void clear_latitude(); + static const int kLatitudeFieldNumber = 20; + double latitude() const; + void set_latitude(double value); + + // double longitude = 21; + void clear_longitude(); + static const int kLongitudeFieldNumber = 21; + double longitude() const; + void set_longitude(double value); + + // int32 month = 24; + void clear_month(); + static const int kMonthFieldNumber = 24; + ::google::protobuf::int32 month() const; + void set_month(::google::protobuf::int32 value); + + // int32 day = 25; + void clear_day(); + static const int kDayFieldNumber = 25; + ::google::protobuf::int32 day() const; + void set_day(::google::protobuf::int32 value); + + // int32 hours = 26; + void clear_hours(); + static const int kHoursFieldNumber = 26; + ::google::protobuf::int32 hours() const; + void set_hours(::google::protobuf::int32 value); + + // int32 minutes = 27; + void clear_minutes(); + static const int kMinutesFieldNumber = 27; + ::google::protobuf::int32 minutes() const; + void set_minutes(::google::protobuf::int32 value); + + // int32 seconds = 28; + void clear_seconds(); + static const int kSecondsFieldNumber = 28; + ::google::protobuf::int32 seconds() const; + void set_seconds(::google::protobuf::int32 value); + + // bool gps_valid = 22; + void clear_gps_valid(); + static const int kGpsValidFieldNumber = 22; + bool gps_valid() const; + void set_gps_valid(bool value); + + // bool is_gps_fault = 31; + void clear_is_gps_fault(); + static const int kIsGpsFaultFieldNumber = 31; + bool is_gps_fault() const; + void set_is_gps_fault(bool value); + + // bool is_inferred = 32; + void clear_is_inferred(); + static const int kIsInferredFieldNumber = 32; + bool is_inferred() const; + void set_is_inferred(bool value); + + // double compass_direction = 29; + void clear_compass_direction(); + static const int kCompassDirectionFieldNumber = 29; + double compass_direction() const; + void set_compass_direction(double value); + + // double pdop = 30; + void clear_pdop(); + static const int kPdopFieldNumber = 30; + double pdop() const; + void set_pdop(double value); + + // double altitude = 33; + void clear_altitude(); + static const int kAltitudeFieldNumber = 33; + double altitude() const; + void set_altitude(double value); + + // double heading = 34; + void clear_heading(); + static const int kHeadingFieldNumber = 34; + double heading() const; + void set_heading(double value); + + // double hdop = 35; + void clear_hdop(); + static const int kHdopFieldNumber = 35; + double hdop() const; + void set_hdop(double value); + + // double vdop = 36; + void clear_vdop(); + static const int kVdopFieldNumber = 36; + double vdop() const; + void set_vdop(double value); + + // .apollo.canbus.BasicInfo.GpsQuality quality = 37; + void clear_quality(); + static const int kQualityFieldNumber = 37; + ::apollo::canbus::BasicInfo_GpsQuality quality() const; + void set_quality(::apollo::canbus::BasicInfo_GpsQuality value); + + // int32 num_satellites = 38; + void clear_num_satellites(); + static const int kNumSatellitesFieldNumber = 38; + ::google::protobuf::int32 num_satellites() const; + void set_num_satellites(::google::protobuf::int32 value); + + // double gps_speed = 39; + void clear_gps_speed(); + static const int kGpsSpeedFieldNumber = 39; + double gps_speed() const; + void set_gps_speed(double value); + + // @@protoc_insertion_point(class_scope:apollo.canbus.BasicInfo) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + int power_state_; + bool is_auto_mode_; + bool is_air_bag_deployed_; + bool is_system_error_; + bool is_human_interrupt_; + double odo_meter_; + double drive_range_; + bool acc_on_button_; + bool acc_off_button_; + bool acc_res_button_; + bool acc_cancel_button_; + bool acc_on_off_button_; + bool acc_res_cancel_button_; + bool acc_inc_spd_button_; + bool acc_dec_spd_button_; + bool acc_inc_gap_button_; + bool acc_dec_gap_button_; + bool lka_button_; + bool canbus_fault_; + ::google::protobuf::int32 year_; + double latitude_; + double longitude_; + ::google::protobuf::int32 month_; + ::google::protobuf::int32 day_; + ::google::protobuf::int32 hours_; + ::google::protobuf::int32 minutes_; + ::google::protobuf::int32 seconds_; + bool gps_valid_; + bool is_gps_fault_; + bool is_inferred_; + double compass_direction_; + double pdop_; + double altitude_; + double heading_; + double hdop_; + double vdop_; + int quality_; + ::google::protobuf::int32 num_satellites_; + double gps_speed_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// ChassisDetail + +// .apollo.canbus.ChassisDetail.Type car_type = 1; +inline void ChassisDetail::clear_car_type() { + car_type_ = 0; +} +inline ::apollo::canbus::ChassisDetail_Type ChassisDetail::car_type() const { + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.car_type) + return static_cast< ::apollo::canbus::ChassisDetail_Type >(car_type_); +} +inline void ChassisDetail::set_car_type(::apollo::canbus::ChassisDetail_Type value) { + + car_type_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.ChassisDetail.car_type) +} + +// .apollo.canbus.BasicInfo basic = 2; +inline bool ChassisDetail::has_basic() const { + return this != internal_default_instance() && basic_ != NULL; +} +inline void ChassisDetail::clear_basic() { + if (GetArenaNoVirtual() == NULL && basic_ != NULL) { + delete basic_; + } + basic_ = NULL; +} +inline const ::apollo::canbus::BasicInfo& ChassisDetail::_internal_basic() const { + return *basic_; +} +inline const ::apollo::canbus::BasicInfo& ChassisDetail::basic() const { + const ::apollo::canbus::BasicInfo* p = basic_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.basic) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_BasicInfo_default_instance_); +} +inline ::apollo::canbus::BasicInfo* ChassisDetail::release_basic() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.basic) + + ::apollo::canbus::BasicInfo* temp = basic_; + basic_ = NULL; + return temp; +} +inline ::apollo::canbus::BasicInfo* ChassisDetail::mutable_basic() { + + if (basic_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::BasicInfo>(GetArenaNoVirtual()); + basic_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.basic) + return basic_; +} +inline void ChassisDetail::set_allocated_basic(::apollo::canbus::BasicInfo* basic) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete basic_; + } + if (basic) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + basic = ::google::protobuf::internal::GetOwnedMessage( + message_arena, basic, submessage_arena); + } + + } else { + + } + basic_ = basic; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.basic) +} + +// .apollo.canbus.Safety safety = 3; +inline bool ChassisDetail::has_safety() const { + return this != internal_default_instance() && safety_ != NULL; +} +inline void ChassisDetail::clear_safety() { + if (GetArenaNoVirtual() == NULL && safety_ != NULL) { + delete safety_; + } + safety_ = NULL; +} +inline const ::apollo::canbus::Safety& ChassisDetail::_internal_safety() const { + return *safety_; +} +inline const ::apollo::canbus::Safety& ChassisDetail::safety() const { + const ::apollo::canbus::Safety* p = safety_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.safety) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Safety_default_instance_); +} +inline ::apollo::canbus::Safety* ChassisDetail::release_safety() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.safety) + + ::apollo::canbus::Safety* temp = safety_; + safety_ = NULL; + return temp; +} +inline ::apollo::canbus::Safety* ChassisDetail::mutable_safety() { + + if (safety_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Safety>(GetArenaNoVirtual()); + safety_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.safety) + return safety_; +} +inline void ChassisDetail::set_allocated_safety(::apollo::canbus::Safety* safety) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete safety_; + } + if (safety) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + safety = ::google::protobuf::internal::GetOwnedMessage( + message_arena, safety, submessage_arena); + } + + } else { + + } + safety_ = safety; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.safety) +} + +// .apollo.canbus.Gear gear = 4; +inline bool ChassisDetail::has_gear() const { + return this != internal_default_instance() && gear_ != NULL; +} +inline void ChassisDetail::clear_gear() { + if (GetArenaNoVirtual() == NULL && gear_ != NULL) { + delete gear_; + } + gear_ = NULL; +} +inline const ::apollo::canbus::Gear& ChassisDetail::_internal_gear() const { + return *gear_; +} +inline const ::apollo::canbus::Gear& ChassisDetail::gear() const { + const ::apollo::canbus::Gear* p = gear_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.gear) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Gear_default_instance_); +} +inline ::apollo::canbus::Gear* ChassisDetail::release_gear() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.gear) + + ::apollo::canbus::Gear* temp = gear_; + gear_ = NULL; + return temp; +} +inline ::apollo::canbus::Gear* ChassisDetail::mutable_gear() { + + if (gear_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Gear>(GetArenaNoVirtual()); + gear_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.gear) + return gear_; +} +inline void ChassisDetail::set_allocated_gear(::apollo::canbus::Gear* gear) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete gear_; + } + if (gear) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + gear = ::google::protobuf::internal::GetOwnedMessage( + message_arena, gear, submessage_arena); + } + + } else { + + } + gear_ = gear; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.gear) +} + +// .apollo.canbus.Ems ems = 5; +inline bool ChassisDetail::has_ems() const { + return this != internal_default_instance() && ems_ != NULL; +} +inline void ChassisDetail::clear_ems() { + if (GetArenaNoVirtual() == NULL && ems_ != NULL) { + delete ems_; + } + ems_ = NULL; +} +inline const ::apollo::canbus::Ems& ChassisDetail::_internal_ems() const { + return *ems_; +} +inline const ::apollo::canbus::Ems& ChassisDetail::ems() const { + const ::apollo::canbus::Ems* p = ems_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.ems) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Ems_default_instance_); +} +inline ::apollo::canbus::Ems* ChassisDetail::release_ems() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.ems) + + ::apollo::canbus::Ems* temp = ems_; + ems_ = NULL; + return temp; +} +inline ::apollo::canbus::Ems* ChassisDetail::mutable_ems() { + + if (ems_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Ems>(GetArenaNoVirtual()); + ems_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.ems) + return ems_; +} +inline void ChassisDetail::set_allocated_ems(::apollo::canbus::Ems* ems) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete ems_; + } + if (ems) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + ems = ::google::protobuf::internal::GetOwnedMessage( + message_arena, ems, submessage_arena); + } + + } else { + + } + ems_ = ems; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.ems) +} + +// .apollo.canbus.Esp esp = 6; +inline bool ChassisDetail::has_esp() const { + return this != internal_default_instance() && esp_ != NULL; +} +inline void ChassisDetail::clear_esp() { + if (GetArenaNoVirtual() == NULL && esp_ != NULL) { + delete esp_; + } + esp_ = NULL; +} +inline const ::apollo::canbus::Esp& ChassisDetail::_internal_esp() const { + return *esp_; +} +inline const ::apollo::canbus::Esp& ChassisDetail::esp() const { + const ::apollo::canbus::Esp* p = esp_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.esp) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Esp_default_instance_); +} +inline ::apollo::canbus::Esp* ChassisDetail::release_esp() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.esp) + + ::apollo::canbus::Esp* temp = esp_; + esp_ = NULL; + return temp; +} +inline ::apollo::canbus::Esp* ChassisDetail::mutable_esp() { + + if (esp_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Esp>(GetArenaNoVirtual()); + esp_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.esp) + return esp_; +} +inline void ChassisDetail::set_allocated_esp(::apollo::canbus::Esp* esp) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete esp_; + } + if (esp) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + esp = ::google::protobuf::internal::GetOwnedMessage( + message_arena, esp, submessage_arena); + } + + } else { + + } + esp_ = esp; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.esp) +} + +// .apollo.canbus.Gas gas = 7; +inline bool ChassisDetail::has_gas() const { + return this != internal_default_instance() && gas_ != NULL; +} +inline void ChassisDetail::clear_gas() { + if (GetArenaNoVirtual() == NULL && gas_ != NULL) { + delete gas_; + } + gas_ = NULL; +} +inline const ::apollo::canbus::Gas& ChassisDetail::_internal_gas() const { + return *gas_; +} +inline const ::apollo::canbus::Gas& ChassisDetail::gas() const { + const ::apollo::canbus::Gas* p = gas_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.gas) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Gas_default_instance_); +} +inline ::apollo::canbus::Gas* ChassisDetail::release_gas() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.gas) + + ::apollo::canbus::Gas* temp = gas_; + gas_ = NULL; + return temp; +} +inline ::apollo::canbus::Gas* ChassisDetail::mutable_gas() { + + if (gas_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Gas>(GetArenaNoVirtual()); + gas_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.gas) + return gas_; +} +inline void ChassisDetail::set_allocated_gas(::apollo::canbus::Gas* gas) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete gas_; + } + if (gas) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + gas = ::google::protobuf::internal::GetOwnedMessage( + message_arena, gas, submessage_arena); + } + + } else { + + } + gas_ = gas; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.gas) +} + +// .apollo.canbus.Epb epb = 8; +inline bool ChassisDetail::has_epb() const { + return this != internal_default_instance() && epb_ != NULL; +} +inline void ChassisDetail::clear_epb() { + if (GetArenaNoVirtual() == NULL && epb_ != NULL) { + delete epb_; + } + epb_ = NULL; +} +inline const ::apollo::canbus::Epb& ChassisDetail::_internal_epb() const { + return *epb_; +} +inline const ::apollo::canbus::Epb& ChassisDetail::epb() const { + const ::apollo::canbus::Epb* p = epb_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.epb) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Epb_default_instance_); +} +inline ::apollo::canbus::Epb* ChassisDetail::release_epb() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.epb) + + ::apollo::canbus::Epb* temp = epb_; + epb_ = NULL; + return temp; +} +inline ::apollo::canbus::Epb* ChassisDetail::mutable_epb() { + + if (epb_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Epb>(GetArenaNoVirtual()); + epb_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.epb) + return epb_; +} +inline void ChassisDetail::set_allocated_epb(::apollo::canbus::Epb* epb) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete epb_; + } + if (epb) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + epb = ::google::protobuf::internal::GetOwnedMessage( + message_arena, epb, submessage_arena); + } + + } else { + + } + epb_ = epb; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.epb) +} + +// .apollo.canbus.Brake brake = 9; +inline bool ChassisDetail::has_brake() const { + return this != internal_default_instance() && brake_ != NULL; +} +inline void ChassisDetail::clear_brake() { + if (GetArenaNoVirtual() == NULL && brake_ != NULL) { + delete brake_; + } + brake_ = NULL; +} +inline const ::apollo::canbus::Brake& ChassisDetail::_internal_brake() const { + return *brake_; +} +inline const ::apollo::canbus::Brake& ChassisDetail::brake() const { + const ::apollo::canbus::Brake* p = brake_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.brake) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Brake_default_instance_); +} +inline ::apollo::canbus::Brake* ChassisDetail::release_brake() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.brake) + + ::apollo::canbus::Brake* temp = brake_; + brake_ = NULL; + return temp; +} +inline ::apollo::canbus::Brake* ChassisDetail::mutable_brake() { + + if (brake_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Brake>(GetArenaNoVirtual()); + brake_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.brake) + return brake_; +} +inline void ChassisDetail::set_allocated_brake(::apollo::canbus::Brake* brake) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete brake_; + } + if (brake) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + brake = ::google::protobuf::internal::GetOwnedMessage( + message_arena, brake, submessage_arena); + } + + } else { + + } + brake_ = brake; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.brake) +} + +// .apollo.canbus.Deceleration deceleration = 10; +inline bool ChassisDetail::has_deceleration() const { + return this != internal_default_instance() && deceleration_ != NULL; +} +inline void ChassisDetail::clear_deceleration() { + if (GetArenaNoVirtual() == NULL && deceleration_ != NULL) { + delete deceleration_; + } + deceleration_ = NULL; +} +inline const ::apollo::canbus::Deceleration& ChassisDetail::_internal_deceleration() const { + return *deceleration_; +} +inline const ::apollo::canbus::Deceleration& ChassisDetail::deceleration() const { + const ::apollo::canbus::Deceleration* p = deceleration_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.deceleration) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Deceleration_default_instance_); +} +inline ::apollo::canbus::Deceleration* ChassisDetail::release_deceleration() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.deceleration) + + ::apollo::canbus::Deceleration* temp = deceleration_; + deceleration_ = NULL; + return temp; +} +inline ::apollo::canbus::Deceleration* ChassisDetail::mutable_deceleration() { + + if (deceleration_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Deceleration>(GetArenaNoVirtual()); + deceleration_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.deceleration) + return deceleration_; +} +inline void ChassisDetail::set_allocated_deceleration(::apollo::canbus::Deceleration* deceleration) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete deceleration_; + } + if (deceleration) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + deceleration = ::google::protobuf::internal::GetOwnedMessage( + message_arena, deceleration, submessage_arena); + } + + } else { + + } + deceleration_ = deceleration; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.deceleration) +} + +// .apollo.canbus.VehicleSpd vehicle_spd = 11; +inline bool ChassisDetail::has_vehicle_spd() const { + return this != internal_default_instance() && vehicle_spd_ != NULL; +} +inline void ChassisDetail::clear_vehicle_spd() { + if (GetArenaNoVirtual() == NULL && vehicle_spd_ != NULL) { + delete vehicle_spd_; + } + vehicle_spd_ = NULL; +} +inline const ::apollo::canbus::VehicleSpd& ChassisDetail::_internal_vehicle_spd() const { + return *vehicle_spd_; +} +inline const ::apollo::canbus::VehicleSpd& ChassisDetail::vehicle_spd() const { + const ::apollo::canbus::VehicleSpd* p = vehicle_spd_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.vehicle_spd) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_VehicleSpd_default_instance_); +} +inline ::apollo::canbus::VehicleSpd* ChassisDetail::release_vehicle_spd() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.vehicle_spd) + + ::apollo::canbus::VehicleSpd* temp = vehicle_spd_; + vehicle_spd_ = NULL; + return temp; +} +inline ::apollo::canbus::VehicleSpd* ChassisDetail::mutable_vehicle_spd() { + + if (vehicle_spd_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::VehicleSpd>(GetArenaNoVirtual()); + vehicle_spd_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.vehicle_spd) + return vehicle_spd_; +} +inline void ChassisDetail::set_allocated_vehicle_spd(::apollo::canbus::VehicleSpd* vehicle_spd) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete vehicle_spd_; + } + if (vehicle_spd) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + vehicle_spd = ::google::protobuf::internal::GetOwnedMessage( + message_arena, vehicle_spd, submessage_arena); + } + + } else { + + } + vehicle_spd_ = vehicle_spd; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.vehicle_spd) +} + +// .apollo.canbus.Eps eps = 12; +inline bool ChassisDetail::has_eps() const { + return this != internal_default_instance() && eps_ != NULL; +} +inline void ChassisDetail::clear_eps() { + if (GetArenaNoVirtual() == NULL && eps_ != NULL) { + delete eps_; + } + eps_ = NULL; +} +inline const ::apollo::canbus::Eps& ChassisDetail::_internal_eps() const { + return *eps_; +} +inline const ::apollo::canbus::Eps& ChassisDetail::eps() const { + const ::apollo::canbus::Eps* p = eps_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.eps) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Eps_default_instance_); +} +inline ::apollo::canbus::Eps* ChassisDetail::release_eps() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.eps) + + ::apollo::canbus::Eps* temp = eps_; + eps_ = NULL; + return temp; +} +inline ::apollo::canbus::Eps* ChassisDetail::mutable_eps() { + + if (eps_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Eps>(GetArenaNoVirtual()); + eps_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.eps) + return eps_; +} +inline void ChassisDetail::set_allocated_eps(::apollo::canbus::Eps* eps) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete eps_; + } + if (eps) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + eps = ::google::protobuf::internal::GetOwnedMessage( + message_arena, eps, submessage_arena); + } + + } else { + + } + eps_ = eps; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.eps) +} + +// .apollo.canbus.Light light = 13; +inline bool ChassisDetail::has_light() const { + return this != internal_default_instance() && light_ != NULL; +} +inline void ChassisDetail::clear_light() { + if (GetArenaNoVirtual() == NULL && light_ != NULL) { + delete light_; + } + light_ = NULL; +} +inline const ::apollo::canbus::Light& ChassisDetail::_internal_light() const { + return *light_; +} +inline const ::apollo::canbus::Light& ChassisDetail::light() const { + const ::apollo::canbus::Light* p = light_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.light) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Light_default_instance_); +} +inline ::apollo::canbus::Light* ChassisDetail::release_light() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.light) + + ::apollo::canbus::Light* temp = light_; + light_ = NULL; + return temp; +} +inline ::apollo::canbus::Light* ChassisDetail::mutable_light() { + + if (light_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Light>(GetArenaNoVirtual()); + light_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.light) + return light_; +} +inline void ChassisDetail::set_allocated_light(::apollo::canbus::Light* light) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete light_; + } + if (light) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + light = ::google::protobuf::internal::GetOwnedMessage( + message_arena, light, submessage_arena); + } + + } else { + + } + light_ = light; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.light) +} + +// .apollo.canbus.Battery battery = 14; +inline bool ChassisDetail::has_battery() const { + return this != internal_default_instance() && battery_ != NULL; +} +inline void ChassisDetail::clear_battery() { + if (GetArenaNoVirtual() == NULL && battery_ != NULL) { + delete battery_; + } + battery_ = NULL; +} +inline const ::apollo::canbus::Battery& ChassisDetail::_internal_battery() const { + return *battery_; +} +inline const ::apollo::canbus::Battery& ChassisDetail::battery() const { + const ::apollo::canbus::Battery* p = battery_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.battery) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Battery_default_instance_); +} +inline ::apollo::canbus::Battery* ChassisDetail::release_battery() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.battery) + + ::apollo::canbus::Battery* temp = battery_; + battery_ = NULL; + return temp; +} +inline ::apollo::canbus::Battery* ChassisDetail::mutable_battery() { + + if (battery_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Battery>(GetArenaNoVirtual()); + battery_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.battery) + return battery_; +} +inline void ChassisDetail::set_allocated_battery(::apollo::canbus::Battery* battery) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete battery_; + } + if (battery) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + battery = ::google::protobuf::internal::GetOwnedMessage( + message_arena, battery, submessage_arena); + } + + } else { + + } + battery_ = battery; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.battery) +} + +// .apollo.canbus.CheckResponseSignal check_response = 15; +inline bool ChassisDetail::has_check_response() const { + return this != internal_default_instance() && check_response_ != NULL; +} +inline void ChassisDetail::clear_check_response() { + if (GetArenaNoVirtual() == NULL && check_response_ != NULL) { + delete check_response_; + } + check_response_ = NULL; +} +inline const ::apollo::canbus::CheckResponseSignal& ChassisDetail::_internal_check_response() const { + return *check_response_; +} +inline const ::apollo::canbus::CheckResponseSignal& ChassisDetail::check_response() const { + const ::apollo::canbus::CheckResponseSignal* p = check_response_; + // @@protoc_insertion_point(field_get:apollo.canbus.ChassisDetail.check_response) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_CheckResponseSignal_default_instance_); +} +inline ::apollo::canbus::CheckResponseSignal* ChassisDetail::release_check_response() { + // @@protoc_insertion_point(field_release:apollo.canbus.ChassisDetail.check_response) + + ::apollo::canbus::CheckResponseSignal* temp = check_response_; + check_response_ = NULL; + return temp; +} +inline ::apollo::canbus::CheckResponseSignal* ChassisDetail::mutable_check_response() { + + if (check_response_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::CheckResponseSignal>(GetArenaNoVirtual()); + check_response_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.canbus.ChassisDetail.check_response) + return check_response_; +} +inline void ChassisDetail::set_allocated_check_response(::apollo::canbus::CheckResponseSignal* check_response) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete check_response_; + } + if (check_response) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + check_response = ::google::protobuf::internal::GetOwnedMessage( + message_arena, check_response, submessage_arena); + } + + } else { + + } + check_response_ = check_response; + // @@protoc_insertion_point(field_set_allocated:apollo.canbus.ChassisDetail.check_response) +} + +// ------------------------------------------------------------------- + +// CheckResponseSignal + +// bool is_eps_online = 1; +inline void CheckResponseSignal::clear_is_eps_online() { + is_eps_online_ = false; +} +inline bool CheckResponseSignal::is_eps_online() const { + // @@protoc_insertion_point(field_get:apollo.canbus.CheckResponseSignal.is_eps_online) + return is_eps_online_; +} +inline void CheckResponseSignal::set_is_eps_online(bool value) { + + is_eps_online_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.CheckResponseSignal.is_eps_online) +} + +// bool is_epb_online = 2; +inline void CheckResponseSignal::clear_is_epb_online() { + is_epb_online_ = false; +} +inline bool CheckResponseSignal::is_epb_online() const { + // @@protoc_insertion_point(field_get:apollo.canbus.CheckResponseSignal.is_epb_online) + return is_epb_online_; +} +inline void CheckResponseSignal::set_is_epb_online(bool value) { + + is_epb_online_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.CheckResponseSignal.is_epb_online) +} + +// bool is_esp_online = 3; +inline void CheckResponseSignal::clear_is_esp_online() { + is_esp_online_ = false; +} +inline bool CheckResponseSignal::is_esp_online() const { + // @@protoc_insertion_point(field_get:apollo.canbus.CheckResponseSignal.is_esp_online) + return is_esp_online_; +} +inline void CheckResponseSignal::set_is_esp_online(bool value) { + + is_esp_online_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.CheckResponseSignal.is_esp_online) +} + +// bool is_vtog_online = 4; +inline void CheckResponseSignal::clear_is_vtog_online() { + is_vtog_online_ = false; +} +inline bool CheckResponseSignal::is_vtog_online() const { + // @@protoc_insertion_point(field_get:apollo.canbus.CheckResponseSignal.is_vtog_online) + return is_vtog_online_; +} +inline void CheckResponseSignal::set_is_vtog_online(bool value) { + + is_vtog_online_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.CheckResponseSignal.is_vtog_online) +} + +// bool is_scu_online = 5; +inline void CheckResponseSignal::clear_is_scu_online() { + is_scu_online_ = false; +} +inline bool CheckResponseSignal::is_scu_online() const { + // @@protoc_insertion_point(field_get:apollo.canbus.CheckResponseSignal.is_scu_online) + return is_scu_online_; +} +inline void CheckResponseSignal::set_is_scu_online(bool value) { + + is_scu_online_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.CheckResponseSignal.is_scu_online) +} + +// bool is_switch_online = 6; +inline void CheckResponseSignal::clear_is_switch_online() { + is_switch_online_ = false; +} +inline bool CheckResponseSignal::is_switch_online() const { + // @@protoc_insertion_point(field_get:apollo.canbus.CheckResponseSignal.is_switch_online) + return is_switch_online_; +} +inline void CheckResponseSignal::set_is_switch_online(bool value) { + + is_switch_online_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.CheckResponseSignal.is_switch_online) +} + +// bool is_vcu_online = 7; +inline void CheckResponseSignal::clear_is_vcu_online() { + is_vcu_online_ = false; +} +inline bool CheckResponseSignal::is_vcu_online() const { + // @@protoc_insertion_point(field_get:apollo.canbus.CheckResponseSignal.is_vcu_online) + return is_vcu_online_; +} +inline void CheckResponseSignal::set_is_vcu_online(bool value) { + + is_vcu_online_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.CheckResponseSignal.is_vcu_online) +} + +// ------------------------------------------------------------------- + +// Battery + +// double battery_percent = 1; +inline void Battery::clear_battery_percent() { + battery_percent_ = 0; +} +inline double Battery::battery_percent() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Battery.battery_percent) + return battery_percent_; +} +inline void Battery::set_battery_percent(double value) { + + battery_percent_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Battery.battery_percent) +} + +// double fuel_level = 2; +inline void Battery::clear_fuel_level() { + fuel_level_ = 0; +} +inline double Battery::fuel_level() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Battery.fuel_level) + return fuel_level_; +} +inline void Battery::set_fuel_level(double value) { + + fuel_level_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Battery.fuel_level) +} + +// ------------------------------------------------------------------- + +// Light + +// .apollo.canbus.Light.TurnLightType turn_light_type = 1; +inline void Light::clear_turn_light_type() { + turn_light_type_ = 0; +} +inline ::apollo::canbus::Light_TurnLightType Light::turn_light_type() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Light.turn_light_type) + return static_cast< ::apollo::canbus::Light_TurnLightType >(turn_light_type_); +} +inline void Light::set_turn_light_type(::apollo::canbus::Light_TurnLightType value) { + + turn_light_type_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Light.turn_light_type) +} + +// .apollo.canbus.Light.LampType lamp_type = 2; +inline void Light::clear_lamp_type() { + lamp_type_ = 0; +} +inline ::apollo::canbus::Light_LampType Light::lamp_type() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Light.lamp_type) + return static_cast< ::apollo::canbus::Light_LampType >(lamp_type_); +} +inline void Light::set_lamp_type(::apollo::canbus::Light_LampType value) { + + lamp_type_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Light.lamp_type) +} + +// bool is_brake_lamp_on = 3; +inline void Light::clear_is_brake_lamp_on() { + is_brake_lamp_on_ = false; +} +inline bool Light::is_brake_lamp_on() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Light.is_brake_lamp_on) + return is_brake_lamp_on_; +} +inline void Light::set_is_brake_lamp_on(bool value) { + + is_brake_lamp_on_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Light.is_brake_lamp_on) +} + +// bool is_auto_light = 4; +inline void Light::clear_is_auto_light() { + is_auto_light_ = false; +} +inline bool Light::is_auto_light() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Light.is_auto_light) + return is_auto_light_; +} +inline void Light::set_is_auto_light(bool value) { + + is_auto_light_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Light.is_auto_light) +} + +// int32 wiper_gear = 5; +inline void Light::clear_wiper_gear() { + wiper_gear_ = 0; +} +inline ::google::protobuf::int32 Light::wiper_gear() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Light.wiper_gear) + return wiper_gear_; +} +inline void Light::set_wiper_gear(::google::protobuf::int32 value) { + + wiper_gear_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Light.wiper_gear) +} + +// int32 lotion_gear = 6; +inline void Light::clear_lotion_gear() { + lotion_gear_ = 0; +} +inline ::google::protobuf::int32 Light::lotion_gear() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Light.lotion_gear) + return lotion_gear_; +} +inline void Light::set_lotion_gear(::google::protobuf::int32 value) { + + lotion_gear_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Light.lotion_gear) +} + +// bool is_horn_on = 7; +inline void Light::clear_is_horn_on() { + is_horn_on_ = false; +} +inline bool Light::is_horn_on() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Light.is_horn_on) + return is_horn_on_; +} +inline void Light::set_is_horn_on(bool value) { + + is_horn_on_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Light.is_horn_on) +} + +// .apollo.canbus.Light.LincolnLampType lincoln_lamp_type = 8; +inline void Light::clear_lincoln_lamp_type() { + lincoln_lamp_type_ = 0; +} +inline ::apollo::canbus::Light_LincolnLampType Light::lincoln_lamp_type() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Light.lincoln_lamp_type) + return static_cast< ::apollo::canbus::Light_LincolnLampType >(lincoln_lamp_type_); +} +inline void Light::set_lincoln_lamp_type(::apollo::canbus::Light_LincolnLampType value) { + + lincoln_lamp_type_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Light.lincoln_lamp_type) +} + +// .apollo.canbus.Light.LincolnWiperType lincoln_wiper = 9; +inline void Light::clear_lincoln_wiper() { + lincoln_wiper_ = 0; +} +inline ::apollo::canbus::Light_LincolnWiperType Light::lincoln_wiper() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Light.lincoln_wiper) + return static_cast< ::apollo::canbus::Light_LincolnWiperType >(lincoln_wiper_); +} +inline void Light::set_lincoln_wiper(::apollo::canbus::Light_LincolnWiperType value) { + + lincoln_wiper_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Light.lincoln_wiper) +} + +// .apollo.canbus.Light.LincolnAmbientType lincoln_ambient = 10; +inline void Light::clear_lincoln_ambient() { + lincoln_ambient_ = 0; +} +inline ::apollo::canbus::Light_LincolnAmbientType Light::lincoln_ambient() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Light.lincoln_ambient) + return static_cast< ::apollo::canbus::Light_LincolnAmbientType >(lincoln_ambient_); +} +inline void Light::set_lincoln_ambient(::apollo::canbus::Light_LincolnAmbientType value) { + + lincoln_ambient_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Light.lincoln_ambient) +} + +// ------------------------------------------------------------------- + +// Eps + +// bool is_eps_fail = 1; +inline void Eps::clear_is_eps_fail() { + is_eps_fail_ = false; +} +inline bool Eps::is_eps_fail() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.is_eps_fail) + return is_eps_fail_; +} +inline void Eps::set_is_eps_fail(bool value) { + + is_eps_fail_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.is_eps_fail) +} + +// .apollo.canbus.Eps.Type eps_control_state = 2; +inline void Eps::clear_eps_control_state() { + eps_control_state_ = 0; +} +inline ::apollo::canbus::Eps_Type Eps::eps_control_state() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.eps_control_state) + return static_cast< ::apollo::canbus::Eps_Type >(eps_control_state_); +} +inline void Eps::set_eps_control_state(::apollo::canbus::Eps_Type value) { + + eps_control_state_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.eps_control_state) +} + +// double eps_driver_hand_torq = 3; +inline void Eps::clear_eps_driver_hand_torq() { + eps_driver_hand_torq_ = 0; +} +inline double Eps::eps_driver_hand_torq() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.eps_driver_hand_torq) + return eps_driver_hand_torq_; +} +inline void Eps::set_eps_driver_hand_torq(double value) { + + eps_driver_hand_torq_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.eps_driver_hand_torq) +} + +// bool is_steering_angle_valid = 4; +inline void Eps::clear_is_steering_angle_valid() { + is_steering_angle_valid_ = false; +} +inline bool Eps::is_steering_angle_valid() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.is_steering_angle_valid) + return is_steering_angle_valid_; +} +inline void Eps::set_is_steering_angle_valid(bool value) { + + is_steering_angle_valid_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.is_steering_angle_valid) +} + +// double steering_angle = 5; +inline void Eps::clear_steering_angle() { + steering_angle_ = 0; +} +inline double Eps::steering_angle() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.steering_angle) + return steering_angle_; +} +inline void Eps::set_steering_angle(double value) { + + steering_angle_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.steering_angle) +} + +// double steering_angle_spd = 6; +inline void Eps::clear_steering_angle_spd() { + steering_angle_spd_ = 0; +} +inline double Eps::steering_angle_spd() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.steering_angle_spd) + return steering_angle_spd_; +} +inline void Eps::set_steering_angle_spd(double value) { + + steering_angle_spd_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.steering_angle_spd) +} + +// bool is_trimming_status = 7; +inline void Eps::clear_is_trimming_status() { + is_trimming_status_ = false; +} +inline bool Eps::is_trimming_status() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.is_trimming_status) + return is_trimming_status_; +} +inline void Eps::set_is_trimming_status(bool value) { + + is_trimming_status_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.is_trimming_status) +} + +// bool is_calibration_status = 8; +inline void Eps::clear_is_calibration_status() { + is_calibration_status_ = false; +} +inline bool Eps::is_calibration_status() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.is_calibration_status) + return is_calibration_status_; +} +inline void Eps::set_is_calibration_status(bool value) { + + is_calibration_status_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.is_calibration_status) +} + +// bool is_failure_status = 9; +inline void Eps::clear_is_failure_status() { + is_failure_status_ = false; +} +inline bool Eps::is_failure_status() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.is_failure_status) + return is_failure_status_; +} +inline void Eps::set_is_failure_status(bool value) { + + is_failure_status_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.is_failure_status) +} + +// int32 allow_enter_autonomous_mode = 10; +inline void Eps::clear_allow_enter_autonomous_mode() { + allow_enter_autonomous_mode_ = 0; +} +inline ::google::protobuf::int32 Eps::allow_enter_autonomous_mode() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.allow_enter_autonomous_mode) + return allow_enter_autonomous_mode_; +} +inline void Eps::set_allow_enter_autonomous_mode(::google::protobuf::int32 value) { + + allow_enter_autonomous_mode_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.allow_enter_autonomous_mode) +} + +// int32 current_driving_mode = 11; +inline void Eps::clear_current_driving_mode() { + current_driving_mode_ = 0; +} +inline ::google::protobuf::int32 Eps::current_driving_mode() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.current_driving_mode) + return current_driving_mode_; +} +inline void Eps::set_current_driving_mode(::google::protobuf::int32 value) { + + current_driving_mode_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.current_driving_mode) +} + +// double steering_angle_cmd = 12; +inline void Eps::clear_steering_angle_cmd() { + steering_angle_cmd_ = 0; +} +inline double Eps::steering_angle_cmd() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.steering_angle_cmd) + return steering_angle_cmd_; +} +inline void Eps::set_steering_angle_cmd(double value) { + + steering_angle_cmd_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.steering_angle_cmd) +} + +// double vehicle_speed = 13; +inline void Eps::clear_vehicle_speed() { + vehicle_speed_ = 0; +} +inline double Eps::vehicle_speed() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.vehicle_speed) + return vehicle_speed_; +} +inline void Eps::set_vehicle_speed(double value) { + + vehicle_speed_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.vehicle_speed) +} + +// double epas_torque = 14; +inline void Eps::clear_epas_torque() { + epas_torque_ = 0; +} +inline double Eps::epas_torque() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.epas_torque) + return epas_torque_; +} +inline void Eps::set_epas_torque(double value) { + + epas_torque_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.epas_torque) +} + +// bool steering_enabled = 15; +inline void Eps::clear_steering_enabled() { + steering_enabled_ = false; +} +inline bool Eps::steering_enabled() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.steering_enabled) + return steering_enabled_; +} +inline void Eps::set_steering_enabled(bool value) { + + steering_enabled_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.steering_enabled) +} + +// bool driver_override = 16; +inline void Eps::clear_driver_override() { + driver_override_ = false; +} +inline bool Eps::driver_override() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.driver_override) + return driver_override_; +} +inline void Eps::set_driver_override(bool value) { + + driver_override_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.driver_override) +} + +// bool driver_activity = 17; +inline void Eps::clear_driver_activity() { + driver_activity_ = false; +} +inline bool Eps::driver_activity() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.driver_activity) + return driver_activity_; +} +inline void Eps::set_driver_activity(bool value) { + + driver_activity_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.driver_activity) +} + +// bool watchdog_fault = 18; +inline void Eps::clear_watchdog_fault() { + watchdog_fault_ = false; +} +inline bool Eps::watchdog_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.watchdog_fault) + return watchdog_fault_; +} +inline void Eps::set_watchdog_fault(bool value) { + + watchdog_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.watchdog_fault) +} + +// bool channel_1_fault = 19; +inline void Eps::clear_channel_1_fault() { + channel_1_fault_ = false; +} +inline bool Eps::channel_1_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.channel_1_fault) + return channel_1_fault_; +} +inline void Eps::set_channel_1_fault(bool value) { + + channel_1_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.channel_1_fault) +} + +// bool channel_2_fault = 20; +inline void Eps::clear_channel_2_fault() { + channel_2_fault_ = false; +} +inline bool Eps::channel_2_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.channel_2_fault) + return channel_2_fault_; +} +inline void Eps::set_channel_2_fault(bool value) { + + channel_2_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.channel_2_fault) +} + +// bool calibration_fault = 21; +inline void Eps::clear_calibration_fault() { + calibration_fault_ = false; +} +inline bool Eps::calibration_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.calibration_fault) + return calibration_fault_; +} +inline void Eps::set_calibration_fault(bool value) { + + calibration_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.calibration_fault) +} + +// bool connector_fault = 22; +inline void Eps::clear_connector_fault() { + connector_fault_ = false; +} +inline bool Eps::connector_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.connector_fault) + return connector_fault_; +} +inline void Eps::set_connector_fault(bool value) { + + connector_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.connector_fault) +} + +// double timestamp_65 = 23; +inline void Eps::clear_timestamp_65() { + timestamp_65_ = 0; +} +inline double Eps::timestamp_65() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.timestamp_65) + return timestamp_65_; +} +inline void Eps::set_timestamp_65(double value) { + + timestamp_65_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.timestamp_65) +} + +// int32 major_version = 24; +inline void Eps::clear_major_version() { + major_version_ = 0; +} +inline ::google::protobuf::int32 Eps::major_version() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.major_version) + return major_version_; +} +inline void Eps::set_major_version(::google::protobuf::int32 value) { + + major_version_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.major_version) +} + +// int32 minor_version = 25; +inline void Eps::clear_minor_version() { + minor_version_ = 0; +} +inline ::google::protobuf::int32 Eps::minor_version() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.minor_version) + return minor_version_; +} +inline void Eps::set_minor_version(::google::protobuf::int32 value) { + + minor_version_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.minor_version) +} + +// int32 build_number = 26; +inline void Eps::clear_build_number() { + build_number_ = 0; +} +inline ::google::protobuf::int32 Eps::build_number() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Eps.build_number) + return build_number_; +} +inline void Eps::set_build_number(::google::protobuf::int32 value) { + + build_number_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Eps.build_number) +} + +// ------------------------------------------------------------------- + +// VehicleSpd + +// bool is_vehicle_standstill = 1; +inline void VehicleSpd::clear_is_vehicle_standstill() { + is_vehicle_standstill_ = false; +} +inline bool VehicleSpd::is_vehicle_standstill() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.is_vehicle_standstill) + return is_vehicle_standstill_; +} +inline void VehicleSpd::set_is_vehicle_standstill(bool value) { + + is_vehicle_standstill_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.is_vehicle_standstill) +} + +// bool is_vehicle_spd_valid = 2; +inline void VehicleSpd::clear_is_vehicle_spd_valid() { + is_vehicle_spd_valid_ = false; +} +inline bool VehicleSpd::is_vehicle_spd_valid() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.is_vehicle_spd_valid) + return is_vehicle_spd_valid_; +} +inline void VehicleSpd::set_is_vehicle_spd_valid(bool value) { + + is_vehicle_spd_valid_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.is_vehicle_spd_valid) +} + +// double vehicle_spd = 3; +inline void VehicleSpd::clear_vehicle_spd() { + vehicle_spd_ = 0; +} +inline double VehicleSpd::vehicle_spd() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.vehicle_spd) + return vehicle_spd_; +} +inline void VehicleSpd::set_vehicle_spd(double value) { + + vehicle_spd_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.vehicle_spd) +} + +// bool is_wheel_spd_rr_valid = 4; +inline void VehicleSpd::clear_is_wheel_spd_rr_valid() { + is_wheel_spd_rr_valid_ = false; +} +inline bool VehicleSpd::is_wheel_spd_rr_valid() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.is_wheel_spd_rr_valid) + return is_wheel_spd_rr_valid_; +} +inline void VehicleSpd::set_is_wheel_spd_rr_valid(bool value) { + + is_wheel_spd_rr_valid_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.is_wheel_spd_rr_valid) +} + +// .apollo.canbus.VehicleSpd.Type wheel_direction_rr = 5; +inline void VehicleSpd::clear_wheel_direction_rr() { + wheel_direction_rr_ = 0; +} +inline ::apollo::canbus::VehicleSpd_Type VehicleSpd::wheel_direction_rr() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.wheel_direction_rr) + return static_cast< ::apollo::canbus::VehicleSpd_Type >(wheel_direction_rr_); +} +inline void VehicleSpd::set_wheel_direction_rr(::apollo::canbus::VehicleSpd_Type value) { + + wheel_direction_rr_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.wheel_direction_rr) +} + +// double wheel_spd_rr = 6; +inline void VehicleSpd::clear_wheel_spd_rr() { + wheel_spd_rr_ = 0; +} +inline double VehicleSpd::wheel_spd_rr() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.wheel_spd_rr) + return wheel_spd_rr_; +} +inline void VehicleSpd::set_wheel_spd_rr(double value) { + + wheel_spd_rr_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.wheel_spd_rr) +} + +// bool is_wheel_spd_rl_valid = 7; +inline void VehicleSpd::clear_is_wheel_spd_rl_valid() { + is_wheel_spd_rl_valid_ = false; +} +inline bool VehicleSpd::is_wheel_spd_rl_valid() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.is_wheel_spd_rl_valid) + return is_wheel_spd_rl_valid_; +} +inline void VehicleSpd::set_is_wheel_spd_rl_valid(bool value) { + + is_wheel_spd_rl_valid_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.is_wheel_spd_rl_valid) +} + +// .apollo.canbus.VehicleSpd.Type wheel_direction_rl = 8; +inline void VehicleSpd::clear_wheel_direction_rl() { + wheel_direction_rl_ = 0; +} +inline ::apollo::canbus::VehicleSpd_Type VehicleSpd::wheel_direction_rl() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.wheel_direction_rl) + return static_cast< ::apollo::canbus::VehicleSpd_Type >(wheel_direction_rl_); +} +inline void VehicleSpd::set_wheel_direction_rl(::apollo::canbus::VehicleSpd_Type value) { + + wheel_direction_rl_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.wheel_direction_rl) +} + +// double wheel_spd_rl = 9; +inline void VehicleSpd::clear_wheel_spd_rl() { + wheel_spd_rl_ = 0; +} +inline double VehicleSpd::wheel_spd_rl() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.wheel_spd_rl) + return wheel_spd_rl_; +} +inline void VehicleSpd::set_wheel_spd_rl(double value) { + + wheel_spd_rl_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.wheel_spd_rl) +} + +// bool is_wheel_spd_fr_valid = 10; +inline void VehicleSpd::clear_is_wheel_spd_fr_valid() { + is_wheel_spd_fr_valid_ = false; +} +inline bool VehicleSpd::is_wheel_spd_fr_valid() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.is_wheel_spd_fr_valid) + return is_wheel_spd_fr_valid_; +} +inline void VehicleSpd::set_is_wheel_spd_fr_valid(bool value) { + + is_wheel_spd_fr_valid_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.is_wheel_spd_fr_valid) +} + +// .apollo.canbus.VehicleSpd.Type wheel_direction_fr = 11; +inline void VehicleSpd::clear_wheel_direction_fr() { + wheel_direction_fr_ = 0; +} +inline ::apollo::canbus::VehicleSpd_Type VehicleSpd::wheel_direction_fr() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.wheel_direction_fr) + return static_cast< ::apollo::canbus::VehicleSpd_Type >(wheel_direction_fr_); +} +inline void VehicleSpd::set_wheel_direction_fr(::apollo::canbus::VehicleSpd_Type value) { + + wheel_direction_fr_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.wheel_direction_fr) +} + +// double wheel_spd_fr = 12; +inline void VehicleSpd::clear_wheel_spd_fr() { + wheel_spd_fr_ = 0; +} +inline double VehicleSpd::wheel_spd_fr() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.wheel_spd_fr) + return wheel_spd_fr_; +} +inline void VehicleSpd::set_wheel_spd_fr(double value) { + + wheel_spd_fr_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.wheel_spd_fr) +} + +// bool is_wheel_spd_fl_valid = 13; +inline void VehicleSpd::clear_is_wheel_spd_fl_valid() { + is_wheel_spd_fl_valid_ = false; +} +inline bool VehicleSpd::is_wheel_spd_fl_valid() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.is_wheel_spd_fl_valid) + return is_wheel_spd_fl_valid_; +} +inline void VehicleSpd::set_is_wheel_spd_fl_valid(bool value) { + + is_wheel_spd_fl_valid_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.is_wheel_spd_fl_valid) +} + +// .apollo.canbus.VehicleSpd.Type wheel_direction_fl = 14; +inline void VehicleSpd::clear_wheel_direction_fl() { + wheel_direction_fl_ = 0; +} +inline ::apollo::canbus::VehicleSpd_Type VehicleSpd::wheel_direction_fl() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.wheel_direction_fl) + return static_cast< ::apollo::canbus::VehicleSpd_Type >(wheel_direction_fl_); +} +inline void VehicleSpd::set_wheel_direction_fl(::apollo::canbus::VehicleSpd_Type value) { + + wheel_direction_fl_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.wheel_direction_fl) +} + +// double wheel_spd_fl = 15; +inline void VehicleSpd::clear_wheel_spd_fl() { + wheel_spd_fl_ = 0; +} +inline double VehicleSpd::wheel_spd_fl() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.wheel_spd_fl) + return wheel_spd_fl_; +} +inline void VehicleSpd::set_wheel_spd_fl(double value) { + + wheel_spd_fl_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.wheel_spd_fl) +} + +// bool is_yaw_rate_valid = 16; +inline void VehicleSpd::clear_is_yaw_rate_valid() { + is_yaw_rate_valid_ = false; +} +inline bool VehicleSpd::is_yaw_rate_valid() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.is_yaw_rate_valid) + return is_yaw_rate_valid_; +} +inline void VehicleSpd::set_is_yaw_rate_valid(bool value) { + + is_yaw_rate_valid_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.is_yaw_rate_valid) +} + +// double yaw_rate = 17; +inline void VehicleSpd::clear_yaw_rate() { + yaw_rate_ = 0; +} +inline double VehicleSpd::yaw_rate() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.yaw_rate) + return yaw_rate_; +} +inline void VehicleSpd::set_yaw_rate(double value) { + + yaw_rate_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.yaw_rate) +} + +// double yaw_rate_offset = 18; +inline void VehicleSpd::clear_yaw_rate_offset() { + yaw_rate_offset_ = 0; +} +inline double VehicleSpd::yaw_rate_offset() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.yaw_rate_offset) + return yaw_rate_offset_; +} +inline void VehicleSpd::set_yaw_rate_offset(double value) { + + yaw_rate_offset_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.yaw_rate_offset) +} + +// bool is_ax_valid = 19; +inline void VehicleSpd::clear_is_ax_valid() { + is_ax_valid_ = false; +} +inline bool VehicleSpd::is_ax_valid() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.is_ax_valid) + return is_ax_valid_; +} +inline void VehicleSpd::set_is_ax_valid(bool value) { + + is_ax_valid_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.is_ax_valid) +} + +// double ax = 20; +inline void VehicleSpd::clear_ax() { + ax_ = 0; +} +inline double VehicleSpd::ax() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.ax) + return ax_; +} +inline void VehicleSpd::set_ax(double value) { + + ax_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.ax) +} + +// double ax_offset = 21; +inline void VehicleSpd::clear_ax_offset() { + ax_offset_ = 0; +} +inline double VehicleSpd::ax_offset() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.ax_offset) + return ax_offset_; +} +inline void VehicleSpd::set_ax_offset(double value) { + + ax_offset_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.ax_offset) +} + +// bool is_ay_valid = 22; +inline void VehicleSpd::clear_is_ay_valid() { + is_ay_valid_ = false; +} +inline bool VehicleSpd::is_ay_valid() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.is_ay_valid) + return is_ay_valid_; +} +inline void VehicleSpd::set_is_ay_valid(bool value) { + + is_ay_valid_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.is_ay_valid) +} + +// double ay = 23; +inline void VehicleSpd::clear_ay() { + ay_ = 0; +} +inline double VehicleSpd::ay() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.ay) + return ay_; +} +inline void VehicleSpd::set_ay(double value) { + + ay_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.ay) +} + +// double ay_offset = 24; +inline void VehicleSpd::clear_ay_offset() { + ay_offset_ = 0; +} +inline double VehicleSpd::ay_offset() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.ay_offset) + return ay_offset_; +} +inline void VehicleSpd::set_ay_offset(double value) { + + ay_offset_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.ay_offset) +} + +// double lat_acc = 25; +inline void VehicleSpd::clear_lat_acc() { + lat_acc_ = 0; +} +inline double VehicleSpd::lat_acc() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.lat_acc) + return lat_acc_; +} +inline void VehicleSpd::set_lat_acc(double value) { + + lat_acc_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.lat_acc) +} + +// double long_acc = 26; +inline void VehicleSpd::clear_long_acc() { + long_acc_ = 0; +} +inline double VehicleSpd::long_acc() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.long_acc) + return long_acc_; +} +inline void VehicleSpd::set_long_acc(double value) { + + long_acc_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.long_acc) +} + +// double vert_acc = 27; +inline void VehicleSpd::clear_vert_acc() { + vert_acc_ = 0; +} +inline double VehicleSpd::vert_acc() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.vert_acc) + return vert_acc_; +} +inline void VehicleSpd::set_vert_acc(double value) { + + vert_acc_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.vert_acc) +} + +// double roll_rate = 28; +inline void VehicleSpd::clear_roll_rate() { + roll_rate_ = 0; +} +inline double VehicleSpd::roll_rate() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.roll_rate) + return roll_rate_; +} +inline void VehicleSpd::set_roll_rate(double value) { + + roll_rate_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.roll_rate) +} + +// double acc_est = 29; +inline void VehicleSpd::clear_acc_est() { + acc_est_ = 0; +} +inline double VehicleSpd::acc_est() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.acc_est) + return acc_est_; +} +inline void VehicleSpd::set_acc_est(double value) { + + acc_est_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.acc_est) +} + +// double timestamp_sec = 30; +inline void VehicleSpd::clear_timestamp_sec() { + timestamp_sec_ = 0; +} +inline double VehicleSpd::timestamp_sec() const { + // @@protoc_insertion_point(field_get:apollo.canbus.VehicleSpd.timestamp_sec) + return timestamp_sec_; +} +inline void VehicleSpd::set_timestamp_sec(double value) { + + timestamp_sec_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.VehicleSpd.timestamp_sec) +} + +// ------------------------------------------------------------------- + +// Deceleration + +// bool is_deceleration_available = 1; +inline void Deceleration::clear_is_deceleration_available() { + is_deceleration_available_ = false; +} +inline bool Deceleration::is_deceleration_available() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Deceleration.is_deceleration_available) + return is_deceleration_available_; +} +inline void Deceleration::set_is_deceleration_available(bool value) { + + is_deceleration_available_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Deceleration.is_deceleration_available) +} + +// bool is_deceleration_active = 2; +inline void Deceleration::clear_is_deceleration_active() { + is_deceleration_active_ = false; +} +inline bool Deceleration::is_deceleration_active() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Deceleration.is_deceleration_active) + return is_deceleration_active_; +} +inline void Deceleration::set_is_deceleration_active(bool value) { + + is_deceleration_active_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Deceleration.is_deceleration_active) +} + +// double deceleration = 3; +inline void Deceleration::clear_deceleration() { + deceleration_ = 0; +} +inline double Deceleration::deceleration() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Deceleration.deceleration) + return deceleration_; +} +inline void Deceleration::set_deceleration(double value) { + + deceleration_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Deceleration.deceleration) +} + +// double is_evb_fail = 4; +inline void Deceleration::clear_is_evb_fail() { + is_evb_fail_ = 0; +} +inline double Deceleration::is_evb_fail() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Deceleration.is_evb_fail) + return is_evb_fail_; +} +inline void Deceleration::set_is_evb_fail(double value) { + + is_evb_fail_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Deceleration.is_evb_fail) +} + +// double evb_pressure = 5; +inline void Deceleration::clear_evb_pressure() { + evb_pressure_ = 0; +} +inline double Deceleration::evb_pressure() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Deceleration.evb_pressure) + return evb_pressure_; +} +inline void Deceleration::set_evb_pressure(double value) { + + evb_pressure_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Deceleration.evb_pressure) +} + +// double brake_pressure = 6; +inline void Deceleration::clear_brake_pressure() { + brake_pressure_ = 0; +} +inline double Deceleration::brake_pressure() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Deceleration.brake_pressure) + return brake_pressure_; +} +inline void Deceleration::set_brake_pressure(double value) { + + brake_pressure_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Deceleration.brake_pressure) +} + +// double brake_pressure_spd = 7; +inline void Deceleration::clear_brake_pressure_spd() { + brake_pressure_spd_ = 0; +} +inline double Deceleration::brake_pressure_spd() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Deceleration.brake_pressure_spd) + return brake_pressure_spd_; +} +inline void Deceleration::set_brake_pressure_spd(double value) { + + brake_pressure_spd_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Deceleration.brake_pressure_spd) +} + +// ------------------------------------------------------------------- + +// Brake + +// bool is_brake_pedal_pressed = 1; +inline void Brake::clear_is_brake_pedal_pressed() { + is_brake_pedal_pressed_ = false; +} +inline bool Brake::is_brake_pedal_pressed() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.is_brake_pedal_pressed) + return is_brake_pedal_pressed_; +} +inline void Brake::set_is_brake_pedal_pressed(bool value) { + + is_brake_pedal_pressed_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.is_brake_pedal_pressed) +} + +// bool is_brake_force_exist = 2; +inline void Brake::clear_is_brake_force_exist() { + is_brake_force_exist_ = false; +} +inline bool Brake::is_brake_force_exist() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.is_brake_force_exist) + return is_brake_force_exist_; +} +inline void Brake::set_is_brake_force_exist(bool value) { + + is_brake_force_exist_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.is_brake_force_exist) +} + +// bool is_brake_over_heat = 3; +inline void Brake::clear_is_brake_over_heat() { + is_brake_over_heat_ = false; +} +inline bool Brake::is_brake_over_heat() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.is_brake_over_heat) + return is_brake_over_heat_; +} +inline void Brake::set_is_brake_over_heat(bool value) { + + is_brake_over_heat_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.is_brake_over_heat) +} + +// bool is_hand_brake_on = 4; +inline void Brake::clear_is_hand_brake_on() { + is_hand_brake_on_ = false; +} +inline bool Brake::is_hand_brake_on() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.is_hand_brake_on) + return is_hand_brake_on_; +} +inline void Brake::set_is_hand_brake_on(bool value) { + + is_hand_brake_on_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.is_hand_brake_on) +} + +// double brake_pedal_position = 5; +inline void Brake::clear_brake_pedal_position() { + brake_pedal_position_ = 0; +} +inline double Brake::brake_pedal_position() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.brake_pedal_position) + return brake_pedal_position_; +} +inline void Brake::set_brake_pedal_position(double value) { + + brake_pedal_position_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.brake_pedal_position) +} + +// bool is_brake_valid = 6; +inline void Brake::clear_is_brake_valid() { + is_brake_valid_ = false; +} +inline bool Brake::is_brake_valid() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.is_brake_valid) + return is_brake_valid_; +} +inline void Brake::set_is_brake_valid(bool value) { + + is_brake_valid_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.is_brake_valid) +} + +// double brake_input = 7; +inline void Brake::clear_brake_input() { + brake_input_ = 0; +} +inline double Brake::brake_input() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.brake_input) + return brake_input_; +} +inline void Brake::set_brake_input(double value) { + + brake_input_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.brake_input) +} + +// double brake_cmd = 8; +inline void Brake::clear_brake_cmd() { + brake_cmd_ = 0; +} +inline double Brake::brake_cmd() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.brake_cmd) + return brake_cmd_; +} +inline void Brake::set_brake_cmd(double value) { + + brake_cmd_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.brake_cmd) +} + +// double brake_output = 9; +inline void Brake::clear_brake_output() { + brake_output_ = 0; +} +inline double Brake::brake_output() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.brake_output) + return brake_output_; +} +inline void Brake::set_brake_output(double value) { + + brake_output_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.brake_output) +} + +// bool boo_input = 10; +inline void Brake::clear_boo_input() { + boo_input_ = false; +} +inline bool Brake::boo_input() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.boo_input) + return boo_input_; +} +inline void Brake::set_boo_input(bool value) { + + boo_input_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.boo_input) +} + +// bool boo_cmd = 11; +inline void Brake::clear_boo_cmd() { + boo_cmd_ = false; +} +inline bool Brake::boo_cmd() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.boo_cmd) + return boo_cmd_; +} +inline void Brake::set_boo_cmd(bool value) { + + boo_cmd_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.boo_cmd) +} + +// bool boo_output = 12; +inline void Brake::clear_boo_output() { + boo_output_ = false; +} +inline bool Brake::boo_output() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.boo_output) + return boo_output_; +} +inline void Brake::set_boo_output(bool value) { + + boo_output_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.boo_output) +} + +// bool watchdog_applying_brakes = 13; +inline void Brake::clear_watchdog_applying_brakes() { + watchdog_applying_brakes_ = false; +} +inline bool Brake::watchdog_applying_brakes() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.watchdog_applying_brakes) + return watchdog_applying_brakes_; +} +inline void Brake::set_watchdog_applying_brakes(bool value) { + + watchdog_applying_brakes_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.watchdog_applying_brakes) +} + +// int32 watchdog_source = 14; +inline void Brake::clear_watchdog_source() { + watchdog_source_ = 0; +} +inline ::google::protobuf::int32 Brake::watchdog_source() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.watchdog_source) + return watchdog_source_; +} +inline void Brake::set_watchdog_source(::google::protobuf::int32 value) { + + watchdog_source_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.watchdog_source) +} + +// bool brake_enabled = 15; +inline void Brake::clear_brake_enabled() { + brake_enabled_ = false; +} +inline bool Brake::brake_enabled() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.brake_enabled) + return brake_enabled_; +} +inline void Brake::set_brake_enabled(bool value) { + + brake_enabled_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.brake_enabled) +} + +// bool driver_override = 16; +inline void Brake::clear_driver_override() { + driver_override_ = false; +} +inline bool Brake::driver_override() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.driver_override) + return driver_override_; +} +inline void Brake::set_driver_override(bool value) { + + driver_override_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.driver_override) +} + +// bool driver_activity = 17; +inline void Brake::clear_driver_activity() { + driver_activity_ = false; +} +inline bool Brake::driver_activity() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.driver_activity) + return driver_activity_; +} +inline void Brake::set_driver_activity(bool value) { + + driver_activity_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.driver_activity) +} + +// bool watchdog_fault = 18; +inline void Brake::clear_watchdog_fault() { + watchdog_fault_ = false; +} +inline bool Brake::watchdog_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.watchdog_fault) + return watchdog_fault_; +} +inline void Brake::set_watchdog_fault(bool value) { + + watchdog_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.watchdog_fault) +} + +// bool channel_1_fault = 19; +inline void Brake::clear_channel_1_fault() { + channel_1_fault_ = false; +} +inline bool Brake::channel_1_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.channel_1_fault) + return channel_1_fault_; +} +inline void Brake::set_channel_1_fault(bool value) { + + channel_1_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.channel_1_fault) +} + +// bool channel_2_fault = 20; +inline void Brake::clear_channel_2_fault() { + channel_2_fault_ = false; +} +inline bool Brake::channel_2_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.channel_2_fault) + return channel_2_fault_; +} +inline void Brake::set_channel_2_fault(bool value) { + + channel_2_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.channel_2_fault) +} + +// bool boo_fault = 21; +inline void Brake::clear_boo_fault() { + boo_fault_ = false; +} +inline bool Brake::boo_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.boo_fault) + return boo_fault_; +} +inline void Brake::set_boo_fault(bool value) { + + boo_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.boo_fault) +} + +// bool connector_fault = 22; +inline void Brake::clear_connector_fault() { + connector_fault_ = false; +} +inline bool Brake::connector_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.connector_fault) + return connector_fault_; +} +inline void Brake::set_connector_fault(bool value) { + + connector_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.connector_fault) +} + +// int32 brake_torque_req = 23; +inline void Brake::clear_brake_torque_req() { + brake_torque_req_ = 0; +} +inline ::google::protobuf::int32 Brake::brake_torque_req() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.brake_torque_req) + return brake_torque_req_; +} +inline void Brake::set_brake_torque_req(::google::protobuf::int32 value) { + + brake_torque_req_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.brake_torque_req) +} + +// .apollo.canbus.Brake.HSAStatusType hsa_status = 24; +inline void Brake::clear_hsa_status() { + hsa_status_ = 0; +} +inline ::apollo::canbus::Brake_HSAStatusType Brake::hsa_status() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.hsa_status) + return static_cast< ::apollo::canbus::Brake_HSAStatusType >(hsa_status_); +} +inline void Brake::set_hsa_status(::apollo::canbus::Brake_HSAStatusType value) { + + hsa_status_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.hsa_status) +} + +// int32 brake_torque_act = 25; +inline void Brake::clear_brake_torque_act() { + brake_torque_act_ = 0; +} +inline ::google::protobuf::int32 Brake::brake_torque_act() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.brake_torque_act) + return brake_torque_act_; +} +inline void Brake::set_brake_torque_act(::google::protobuf::int32 value) { + + brake_torque_act_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.brake_torque_act) +} + +// .apollo.canbus.Brake.HSAModeType hsa_mode = 26; +inline void Brake::clear_hsa_mode() { + hsa_mode_ = 0; +} +inline ::apollo::canbus::Brake_HSAModeType Brake::hsa_mode() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.hsa_mode) + return static_cast< ::apollo::canbus::Brake_HSAModeType >(hsa_mode_); +} +inline void Brake::set_hsa_mode(::apollo::canbus::Brake_HSAModeType value) { + + hsa_mode_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.hsa_mode) +} + +// int32 wheel_torque_act = 27; +inline void Brake::clear_wheel_torque_act() { + wheel_torque_act_ = 0; +} +inline ::google::protobuf::int32 Brake::wheel_torque_act() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.wheel_torque_act) + return wheel_torque_act_; +} +inline void Brake::set_wheel_torque_act(::google::protobuf::int32 value) { + + wheel_torque_act_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.wheel_torque_act) +} + +// int32 major_version = 28; +inline void Brake::clear_major_version() { + major_version_ = 0; +} +inline ::google::protobuf::int32 Brake::major_version() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.major_version) + return major_version_; +} +inline void Brake::set_major_version(::google::protobuf::int32 value) { + + major_version_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.major_version) +} + +// int32 minor_version = 29; +inline void Brake::clear_minor_version() { + minor_version_ = 0; +} +inline ::google::protobuf::int32 Brake::minor_version() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.minor_version) + return minor_version_; +} +inline void Brake::set_minor_version(::google::protobuf::int32 value) { + + minor_version_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.minor_version) +} + +// int32 build_number = 30; +inline void Brake::clear_build_number() { + build_number_ = 0; +} +inline ::google::protobuf::int32 Brake::build_number() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Brake.build_number) + return build_number_; +} +inline void Brake::set_build_number(::google::protobuf::int32 value) { + + build_number_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Brake.build_number) +} + +// ------------------------------------------------------------------- + +// Epb + +// bool is_epb_error = 1; +inline void Epb::clear_is_epb_error() { + is_epb_error_ = false; +} +inline bool Epb::is_epb_error() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Epb.is_epb_error) + return is_epb_error_; +} +inline void Epb::set_is_epb_error(bool value) { + + is_epb_error_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Epb.is_epb_error) +} + +// bool is_epb_released = 2; +inline void Epb::clear_is_epb_released() { + is_epb_released_ = false; +} +inline bool Epb::is_epb_released() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Epb.is_epb_released) + return is_epb_released_; +} +inline void Epb::set_is_epb_released(bool value) { + + is_epb_released_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Epb.is_epb_released) +} + +// int32 epb_status = 3; +inline void Epb::clear_epb_status() { + epb_status_ = 0; +} +inline ::google::protobuf::int32 Epb::epb_status() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Epb.epb_status) + return epb_status_; +} +inline void Epb::set_epb_status(::google::protobuf::int32 value) { + + epb_status_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Epb.epb_status) +} + +// .apollo.canbus.Epb.PBrakeType parking_brake_status = 4; +inline void Epb::clear_parking_brake_status() { + parking_brake_status_ = 0; +} +inline ::apollo::canbus::Epb_PBrakeType Epb::parking_brake_status() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Epb.parking_brake_status) + return static_cast< ::apollo::canbus::Epb_PBrakeType >(parking_brake_status_); +} +inline void Epb::set_parking_brake_status(::apollo::canbus::Epb_PBrakeType value) { + + parking_brake_status_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Epb.parking_brake_status) +} + +// ------------------------------------------------------------------- + +// Gas + +// bool is_gas_pedal_error = 1; +inline void Gas::clear_is_gas_pedal_error() { + is_gas_pedal_error_ = false; +} +inline bool Gas::is_gas_pedal_error() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.is_gas_pedal_error) + return is_gas_pedal_error_; +} +inline void Gas::set_is_gas_pedal_error(bool value) { + + is_gas_pedal_error_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.is_gas_pedal_error) +} + +// bool is_gas_pedal_pressed_more = 2; +inline void Gas::clear_is_gas_pedal_pressed_more() { + is_gas_pedal_pressed_more_ = false; +} +inline bool Gas::is_gas_pedal_pressed_more() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.is_gas_pedal_pressed_more) + return is_gas_pedal_pressed_more_; +} +inline void Gas::set_is_gas_pedal_pressed_more(bool value) { + + is_gas_pedal_pressed_more_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.is_gas_pedal_pressed_more) +} + +// double gas_pedal_position = 3; +inline void Gas::clear_gas_pedal_position() { + gas_pedal_position_ = 0; +} +inline double Gas::gas_pedal_position() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.gas_pedal_position) + return gas_pedal_position_; +} +inline void Gas::set_gas_pedal_position(double value) { + + gas_pedal_position_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.gas_pedal_position) +} + +// bool is_gas_valid = 4; +inline void Gas::clear_is_gas_valid() { + is_gas_valid_ = false; +} +inline bool Gas::is_gas_valid() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.is_gas_valid) + return is_gas_valid_; +} +inline void Gas::set_is_gas_valid(bool value) { + + is_gas_valid_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.is_gas_valid) +} + +// double throttle_input = 5; +inline void Gas::clear_throttle_input() { + throttle_input_ = 0; +} +inline double Gas::throttle_input() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.throttle_input) + return throttle_input_; +} +inline void Gas::set_throttle_input(double value) { + + throttle_input_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.throttle_input) +} + +// double throttle_cmd = 6; +inline void Gas::clear_throttle_cmd() { + throttle_cmd_ = 0; +} +inline double Gas::throttle_cmd() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.throttle_cmd) + return throttle_cmd_; +} +inline void Gas::set_throttle_cmd(double value) { + + throttle_cmd_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.throttle_cmd) +} + +// double throttle_output = 7; +inline void Gas::clear_throttle_output() { + throttle_output_ = 0; +} +inline double Gas::throttle_output() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.throttle_output) + return throttle_output_; +} +inline void Gas::set_throttle_output(double value) { + + throttle_output_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.throttle_output) +} + +// int32 watchdog_source = 8; +inline void Gas::clear_watchdog_source() { + watchdog_source_ = 0; +} +inline ::google::protobuf::int32 Gas::watchdog_source() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.watchdog_source) + return watchdog_source_; +} +inline void Gas::set_watchdog_source(::google::protobuf::int32 value) { + + watchdog_source_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.watchdog_source) +} + +// bool throttle_enabled = 9; +inline void Gas::clear_throttle_enabled() { + throttle_enabled_ = false; +} +inline bool Gas::throttle_enabled() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.throttle_enabled) + return throttle_enabled_; +} +inline void Gas::set_throttle_enabled(bool value) { + + throttle_enabled_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.throttle_enabled) +} + +// bool driver_override = 10; +inline void Gas::clear_driver_override() { + driver_override_ = false; +} +inline bool Gas::driver_override() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.driver_override) + return driver_override_; +} +inline void Gas::set_driver_override(bool value) { + + driver_override_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.driver_override) +} + +// bool driver_activity = 11; +inline void Gas::clear_driver_activity() { + driver_activity_ = false; +} +inline bool Gas::driver_activity() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.driver_activity) + return driver_activity_; +} +inline void Gas::set_driver_activity(bool value) { + + driver_activity_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.driver_activity) +} + +// bool watchdog_fault = 12; +inline void Gas::clear_watchdog_fault() { + watchdog_fault_ = false; +} +inline bool Gas::watchdog_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.watchdog_fault) + return watchdog_fault_; +} +inline void Gas::set_watchdog_fault(bool value) { + + watchdog_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.watchdog_fault) +} + +// bool channel_1_fault = 13; +inline void Gas::clear_channel_1_fault() { + channel_1_fault_ = false; +} +inline bool Gas::channel_1_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.channel_1_fault) + return channel_1_fault_; +} +inline void Gas::set_channel_1_fault(bool value) { + + channel_1_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.channel_1_fault) +} + +// bool channel_2_fault = 14; +inline void Gas::clear_channel_2_fault() { + channel_2_fault_ = false; +} +inline bool Gas::channel_2_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.channel_2_fault) + return channel_2_fault_; +} +inline void Gas::set_channel_2_fault(bool value) { + + channel_2_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.channel_2_fault) +} + +// bool connector_fault = 15; +inline void Gas::clear_connector_fault() { + connector_fault_ = false; +} +inline bool Gas::connector_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.connector_fault) + return connector_fault_; +} +inline void Gas::set_connector_fault(bool value) { + + connector_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.connector_fault) +} + +// double accelerator_pedal = 16; +inline void Gas::clear_accelerator_pedal() { + accelerator_pedal_ = 0; +} +inline double Gas::accelerator_pedal() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.accelerator_pedal) + return accelerator_pedal_; +} +inline void Gas::set_accelerator_pedal(double value) { + + accelerator_pedal_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.accelerator_pedal) +} + +// double accelerator_pedal_rate = 17; +inline void Gas::clear_accelerator_pedal_rate() { + accelerator_pedal_rate_ = 0; +} +inline double Gas::accelerator_pedal_rate() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.accelerator_pedal_rate) + return accelerator_pedal_rate_; +} +inline void Gas::set_accelerator_pedal_rate(double value) { + + accelerator_pedal_rate_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.accelerator_pedal_rate) +} + +// int32 major_version = 18; +inline void Gas::clear_major_version() { + major_version_ = 0; +} +inline ::google::protobuf::int32 Gas::major_version() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.major_version) + return major_version_; +} +inline void Gas::set_major_version(::google::protobuf::int32 value) { + + major_version_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.major_version) +} + +// int32 minor_version = 19; +inline void Gas::clear_minor_version() { + minor_version_ = 0; +} +inline ::google::protobuf::int32 Gas::minor_version() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.minor_version) + return minor_version_; +} +inline void Gas::set_minor_version(::google::protobuf::int32 value) { + + minor_version_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.minor_version) +} + +// int32 build_number = 20; +inline void Gas::clear_build_number() { + build_number_ = 0; +} +inline ::google::protobuf::int32 Gas::build_number() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gas.build_number) + return build_number_; +} +inline void Gas::set_build_number(::google::protobuf::int32 value) { + + build_number_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gas.build_number) +} + +// ------------------------------------------------------------------- + +// Esp + +// bool is_esp_acc_error = 1; +inline void Esp::clear_is_esp_acc_error() { + is_esp_acc_error_ = false; +} +inline bool Esp::is_esp_acc_error() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Esp.is_esp_acc_error) + return is_esp_acc_error_; +} +inline void Esp::set_is_esp_acc_error(bool value) { + + is_esp_acc_error_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Esp.is_esp_acc_error) +} + +// bool is_esp_on = 2; +inline void Esp::clear_is_esp_on() { + is_esp_on_ = false; +} +inline bool Esp::is_esp_on() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Esp.is_esp_on) + return is_esp_on_; +} +inline void Esp::set_is_esp_on(bool value) { + + is_esp_on_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Esp.is_esp_on) +} + +// bool is_esp_active = 3; +inline void Esp::clear_is_esp_active() { + is_esp_active_ = false; +} +inline bool Esp::is_esp_active() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Esp.is_esp_active) + return is_esp_active_; +} +inline void Esp::set_is_esp_active(bool value) { + + is_esp_active_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Esp.is_esp_active) +} + +// bool is_abs_error = 4; +inline void Esp::clear_is_abs_error() { + is_abs_error_ = false; +} +inline bool Esp::is_abs_error() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Esp.is_abs_error) + return is_abs_error_; +} +inline void Esp::set_is_abs_error(bool value) { + + is_abs_error_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Esp.is_abs_error) +} + +// bool is_abs_active = 5; +inline void Esp::clear_is_abs_active() { + is_abs_active_ = false; +} +inline bool Esp::is_abs_active() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Esp.is_abs_active) + return is_abs_active_; +} +inline void Esp::set_is_abs_active(bool value) { + + is_abs_active_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Esp.is_abs_active) +} + +// bool is_tcsvdc_fail = 6; +inline void Esp::clear_is_tcsvdc_fail() { + is_tcsvdc_fail_ = false; +} +inline bool Esp::is_tcsvdc_fail() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Esp.is_tcsvdc_fail) + return is_tcsvdc_fail_; +} +inline void Esp::set_is_tcsvdc_fail(bool value) { + + is_tcsvdc_fail_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Esp.is_tcsvdc_fail) +} + +// bool is_abs_enabled = 7; +inline void Esp::clear_is_abs_enabled() { + is_abs_enabled_ = false; +} +inline bool Esp::is_abs_enabled() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Esp.is_abs_enabled) + return is_abs_enabled_; +} +inline void Esp::set_is_abs_enabled(bool value) { + + is_abs_enabled_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Esp.is_abs_enabled) +} + +// bool is_stab_active = 8; +inline void Esp::clear_is_stab_active() { + is_stab_active_ = false; +} +inline bool Esp::is_stab_active() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Esp.is_stab_active) + return is_stab_active_; +} +inline void Esp::set_is_stab_active(bool value) { + + is_stab_active_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Esp.is_stab_active) +} + +// bool is_stab_enabled = 9; +inline void Esp::clear_is_stab_enabled() { + is_stab_enabled_ = false; +} +inline bool Esp::is_stab_enabled() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Esp.is_stab_enabled) + return is_stab_enabled_; +} +inline void Esp::set_is_stab_enabled(bool value) { + + is_stab_enabled_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Esp.is_stab_enabled) +} + +// bool is_trac_active = 10; +inline void Esp::clear_is_trac_active() { + is_trac_active_ = false; +} +inline bool Esp::is_trac_active() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Esp.is_trac_active) + return is_trac_active_; +} +inline void Esp::set_is_trac_active(bool value) { + + is_trac_active_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Esp.is_trac_active) +} + +// bool is_trac_enabled = 11; +inline void Esp::clear_is_trac_enabled() { + is_trac_enabled_ = false; +} +inline bool Esp::is_trac_enabled() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Esp.is_trac_enabled) + return is_trac_enabled_; +} +inline void Esp::set_is_trac_enabled(bool value) { + + is_trac_enabled_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Esp.is_trac_enabled) +} + +// ------------------------------------------------------------------- + +// Ems + +// bool is_engine_acc_available = 1; +inline void Ems::clear_is_engine_acc_available() { + is_engine_acc_available_ = false; +} +inline bool Ems::is_engine_acc_available() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Ems.is_engine_acc_available) + return is_engine_acc_available_; +} +inline void Ems::set_is_engine_acc_available(bool value) { + + is_engine_acc_available_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Ems.is_engine_acc_available) +} + +// bool is_engine_acc_error = 2; +inline void Ems::clear_is_engine_acc_error() { + is_engine_acc_error_ = false; +} +inline bool Ems::is_engine_acc_error() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Ems.is_engine_acc_error) + return is_engine_acc_error_; +} +inline void Ems::set_is_engine_acc_error(bool value) { + + is_engine_acc_error_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Ems.is_engine_acc_error) +} + +// .apollo.canbus.Ems.Type engine_state = 3; +inline void Ems::clear_engine_state() { + engine_state_ = 0; +} +inline ::apollo::canbus::Ems_Type Ems::engine_state() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Ems.engine_state) + return static_cast< ::apollo::canbus::Ems_Type >(engine_state_); +} +inline void Ems::set_engine_state(::apollo::canbus::Ems_Type value) { + + engine_state_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Ems.engine_state) +} + +// double max_engine_torq_percent = 4; +inline void Ems::clear_max_engine_torq_percent() { + max_engine_torq_percent_ = 0; +} +inline double Ems::max_engine_torq_percent() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Ems.max_engine_torq_percent) + return max_engine_torq_percent_; +} +inline void Ems::set_max_engine_torq_percent(double value) { + + max_engine_torq_percent_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Ems.max_engine_torq_percent) +} + +// double min_engine_torq_percent = 5; +inline void Ems::clear_min_engine_torq_percent() { + min_engine_torq_percent_ = 0; +} +inline double Ems::min_engine_torq_percent() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Ems.min_engine_torq_percent) + return min_engine_torq_percent_; +} +inline void Ems::set_min_engine_torq_percent(double value) { + + min_engine_torq_percent_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Ems.min_engine_torq_percent) +} + +// int32 base_engine_torq_constant = 6; +inline void Ems::clear_base_engine_torq_constant() { + base_engine_torq_constant_ = 0; +} +inline ::google::protobuf::int32 Ems::base_engine_torq_constant() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Ems.base_engine_torq_constant) + return base_engine_torq_constant_; +} +inline void Ems::set_base_engine_torq_constant(::google::protobuf::int32 value) { + + base_engine_torq_constant_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Ems.base_engine_torq_constant) +} + +// bool is_engine_speed_error = 7; +inline void Ems::clear_is_engine_speed_error() { + is_engine_speed_error_ = false; +} +inline bool Ems::is_engine_speed_error() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Ems.is_engine_speed_error) + return is_engine_speed_error_; +} +inline void Ems::set_is_engine_speed_error(bool value) { + + is_engine_speed_error_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Ems.is_engine_speed_error) +} + +// double engine_speed = 8; +inline void Ems::clear_engine_speed() { + engine_speed_ = 0; +} +inline double Ems::engine_speed() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Ems.engine_speed) + return engine_speed_; +} +inline void Ems::set_engine_speed(double value) { + + engine_speed_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Ems.engine_speed) +} + +// int32 engine_torque = 9; +inline void Ems::clear_engine_torque() { + engine_torque_ = 0; +} +inline ::google::protobuf::int32 Ems::engine_torque() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Ems.engine_torque) + return engine_torque_; +} +inline void Ems::set_engine_torque(::google::protobuf::int32 value) { + + engine_torque_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Ems.engine_torque) +} + +// bool is_over_engine_torque = 10; +inline void Ems::clear_is_over_engine_torque() { + is_over_engine_torque_ = false; +} +inline bool Ems::is_over_engine_torque() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Ems.is_over_engine_torque) + return is_over_engine_torque_; +} +inline void Ems::set_is_over_engine_torque(bool value) { + + is_over_engine_torque_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Ems.is_over_engine_torque) +} + +// double engine_rpm = 11; +inline void Ems::clear_engine_rpm() { + engine_rpm_ = 0; +} +inline double Ems::engine_rpm() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Ems.engine_rpm) + return engine_rpm_; +} +inline void Ems::set_engine_rpm(double value) { + + engine_rpm_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Ems.engine_rpm) +} + +// ------------------------------------------------------------------- + +// Gear + +// bool is_shift_position_valid = 1; +inline void Gear::clear_is_shift_position_valid() { + is_shift_position_valid_ = false; +} +inline bool Gear::is_shift_position_valid() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gear.is_shift_position_valid) + return is_shift_position_valid_; +} +inline void Gear::set_is_shift_position_valid(bool value) { + + is_shift_position_valid_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gear.is_shift_position_valid) +} + +// .apollo.canbus.Chassis.GearPosition gear_state = 2; +inline void Gear::clear_gear_state() { + gear_state_ = 0; +} +inline ::apollo::canbus::Chassis_GearPosition Gear::gear_state() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gear.gear_state) + return static_cast< ::apollo::canbus::Chassis_GearPosition >(gear_state_); +} +inline void Gear::set_gear_state(::apollo::canbus::Chassis_GearPosition value) { + + gear_state_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gear.gear_state) +} + +// bool driver_override = 3; +inline void Gear::clear_driver_override() { + driver_override_ = false; +} +inline bool Gear::driver_override() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gear.driver_override) + return driver_override_; +} +inline void Gear::set_driver_override(bool value) { + + driver_override_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gear.driver_override) +} + +// .apollo.canbus.Chassis.GearPosition gear_cmd = 4; +inline void Gear::clear_gear_cmd() { + gear_cmd_ = 0; +} +inline ::apollo::canbus::Chassis_GearPosition Gear::gear_cmd() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gear.gear_cmd) + return static_cast< ::apollo::canbus::Chassis_GearPosition >(gear_cmd_); +} +inline void Gear::set_gear_cmd(::apollo::canbus::Chassis_GearPosition value) { + + gear_cmd_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gear.gear_cmd) +} + +// bool canbus_fault = 5; +inline void Gear::clear_canbus_fault() { + canbus_fault_ = false; +} +inline bool Gear::canbus_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Gear.canbus_fault) + return canbus_fault_; +} +inline void Gear::set_canbus_fault(bool value) { + + canbus_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Gear.canbus_fault) +} + +// ------------------------------------------------------------------- + +// Safety + +// bool is_driver_car_door_close = 1; +inline void Safety::clear_is_driver_car_door_close() { + is_driver_car_door_close_ = false; +} +inline bool Safety::is_driver_car_door_close() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_driver_car_door_close) + return is_driver_car_door_close_; +} +inline void Safety::set_is_driver_car_door_close(bool value) { + + is_driver_car_door_close_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_driver_car_door_close) +} + +// bool is_driver_buckled = 2; +inline void Safety::clear_is_driver_buckled() { + is_driver_buckled_ = false; +} +inline bool Safety::is_driver_buckled() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_driver_buckled) + return is_driver_buckled_; +} +inline void Safety::set_is_driver_buckled(bool value) { + + is_driver_buckled_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_driver_buckled) +} + +// int32 emergency_button = 3; +inline void Safety::clear_emergency_button() { + emergency_button_ = 0; +} +inline ::google::protobuf::int32 Safety::emergency_button() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.emergency_button) + return emergency_button_; +} +inline void Safety::set_emergency_button(::google::protobuf::int32 value) { + + emergency_button_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.emergency_button) +} + +// bool has_error = 4; +inline void Safety::clear_has_error() { + has_error_ = false; +} +inline bool Safety::has_error() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.has_error) + return has_error_; +} +inline void Safety::set_has_error(bool value) { + + has_error_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.has_error) +} + +// bool is_motor_invertor_fault = 5; +inline void Safety::clear_is_motor_invertor_fault() { + is_motor_invertor_fault_ = false; +} +inline bool Safety::is_motor_invertor_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_motor_invertor_fault) + return is_motor_invertor_fault_; +} +inline void Safety::set_is_motor_invertor_fault(bool value) { + + is_motor_invertor_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_motor_invertor_fault) +} + +// bool is_system_fault = 6; +inline void Safety::clear_is_system_fault() { + is_system_fault_ = false; +} +inline bool Safety::is_system_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_system_fault) + return is_system_fault_; +} +inline void Safety::set_is_system_fault(bool value) { + + is_system_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_system_fault) +} + +// bool is_power_battery_fault = 7; +inline void Safety::clear_is_power_battery_fault() { + is_power_battery_fault_ = false; +} +inline bool Safety::is_power_battery_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_power_battery_fault) + return is_power_battery_fault_; +} +inline void Safety::set_is_power_battery_fault(bool value) { + + is_power_battery_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_power_battery_fault) +} + +// bool is_motor_invertor_over_temperature = 8; +inline void Safety::clear_is_motor_invertor_over_temperature() { + is_motor_invertor_over_temperature_ = false; +} +inline bool Safety::is_motor_invertor_over_temperature() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_motor_invertor_over_temperature) + return is_motor_invertor_over_temperature_; +} +inline void Safety::set_is_motor_invertor_over_temperature(bool value) { + + is_motor_invertor_over_temperature_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_motor_invertor_over_temperature) +} + +// bool is_small_battery_charge_discharge_fault = 9; +inline void Safety::clear_is_small_battery_charge_discharge_fault() { + is_small_battery_charge_discharge_fault_ = false; +} +inline bool Safety::is_small_battery_charge_discharge_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_small_battery_charge_discharge_fault) + return is_small_battery_charge_discharge_fault_; +} +inline void Safety::set_is_small_battery_charge_discharge_fault(bool value) { + + is_small_battery_charge_discharge_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_small_battery_charge_discharge_fault) +} + +// int32 driving_mode = 10; +inline void Safety::clear_driving_mode() { + driving_mode_ = 0; +} +inline ::google::protobuf::int32 Safety::driving_mode() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.driving_mode) + return driving_mode_; +} +inline void Safety::set_driving_mode(::google::protobuf::int32 value) { + + driving_mode_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.driving_mode) +} + +// bool is_passenger_door_open = 11; +inline void Safety::clear_is_passenger_door_open() { + is_passenger_door_open_ = false; +} +inline bool Safety::is_passenger_door_open() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_passenger_door_open) + return is_passenger_door_open_; +} +inline void Safety::set_is_passenger_door_open(bool value) { + + is_passenger_door_open_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_passenger_door_open) +} + +// bool is_rearleft_door_open = 12; +inline void Safety::clear_is_rearleft_door_open() { + is_rearleft_door_open_ = false; +} +inline bool Safety::is_rearleft_door_open() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_rearleft_door_open) + return is_rearleft_door_open_; +} +inline void Safety::set_is_rearleft_door_open(bool value) { + + is_rearleft_door_open_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_rearleft_door_open) +} + +// bool is_rearright_door_open = 13; +inline void Safety::clear_is_rearright_door_open() { + is_rearright_door_open_ = false; +} +inline bool Safety::is_rearright_door_open() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_rearright_door_open) + return is_rearright_door_open_; +} +inline void Safety::set_is_rearright_door_open(bool value) { + + is_rearright_door_open_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_rearright_door_open) +} + +// bool is_hood_open = 14; +inline void Safety::clear_is_hood_open() { + is_hood_open_ = false; +} +inline bool Safety::is_hood_open() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_hood_open) + return is_hood_open_; +} +inline void Safety::set_is_hood_open(bool value) { + + is_hood_open_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_hood_open) +} + +// bool is_trunk_open = 15; +inline void Safety::clear_is_trunk_open() { + is_trunk_open_ = false; +} +inline bool Safety::is_trunk_open() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_trunk_open) + return is_trunk_open_; +} +inline void Safety::set_is_trunk_open(bool value) { + + is_trunk_open_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_trunk_open) +} + +// bool is_passenger_detected = 16; +inline void Safety::clear_is_passenger_detected() { + is_passenger_detected_ = false; +} +inline bool Safety::is_passenger_detected() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_passenger_detected) + return is_passenger_detected_; +} +inline void Safety::set_is_passenger_detected(bool value) { + + is_passenger_detected_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_passenger_detected) +} + +// bool is_passenger_airbag_enabled = 17; +inline void Safety::clear_is_passenger_airbag_enabled() { + is_passenger_airbag_enabled_ = false; +} +inline bool Safety::is_passenger_airbag_enabled() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_passenger_airbag_enabled) + return is_passenger_airbag_enabled_; +} +inline void Safety::set_is_passenger_airbag_enabled(bool value) { + + is_passenger_airbag_enabled_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_passenger_airbag_enabled) +} + +// bool is_passenger_buckled = 18; +inline void Safety::clear_is_passenger_buckled() { + is_passenger_buckled_ = false; +} +inline bool Safety::is_passenger_buckled() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.is_passenger_buckled) + return is_passenger_buckled_; +} +inline void Safety::set_is_passenger_buckled(bool value) { + + is_passenger_buckled_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.is_passenger_buckled) +} + +// int32 front_left_tire_press = 19; +inline void Safety::clear_front_left_tire_press() { + front_left_tire_press_ = 0; +} +inline ::google::protobuf::int32 Safety::front_left_tire_press() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.front_left_tire_press) + return front_left_tire_press_; +} +inline void Safety::set_front_left_tire_press(::google::protobuf::int32 value) { + + front_left_tire_press_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.front_left_tire_press) +} + +// int32 front_right_tire_press = 20; +inline void Safety::clear_front_right_tire_press() { + front_right_tire_press_ = 0; +} +inline ::google::protobuf::int32 Safety::front_right_tire_press() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.front_right_tire_press) + return front_right_tire_press_; +} +inline void Safety::set_front_right_tire_press(::google::protobuf::int32 value) { + + front_right_tire_press_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.front_right_tire_press) +} + +// int32 rear_left_tire_press = 21; +inline void Safety::clear_rear_left_tire_press() { + rear_left_tire_press_ = 0; +} +inline ::google::protobuf::int32 Safety::rear_left_tire_press() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.rear_left_tire_press) + return rear_left_tire_press_; +} +inline void Safety::set_rear_left_tire_press(::google::protobuf::int32 value) { + + rear_left_tire_press_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.rear_left_tire_press) +} + +// int32 rear_right_tire_press = 22; +inline void Safety::clear_rear_right_tire_press() { + rear_right_tire_press_ = 0; +} +inline ::google::protobuf::int32 Safety::rear_right_tire_press() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.rear_right_tire_press) + return rear_right_tire_press_; +} +inline void Safety::set_rear_right_tire_press(::google::protobuf::int32 value) { + + rear_right_tire_press_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.rear_right_tire_press) +} + +// .apollo.canbus.Chassis.DrivingMode car_driving_mode = 23; +inline void Safety::clear_car_driving_mode() { + car_driving_mode_ = 0; +} +inline ::apollo::canbus::Chassis_DrivingMode Safety::car_driving_mode() const { + // @@protoc_insertion_point(field_get:apollo.canbus.Safety.car_driving_mode) + return static_cast< ::apollo::canbus::Chassis_DrivingMode >(car_driving_mode_); +} +inline void Safety::set_car_driving_mode(::apollo::canbus::Chassis_DrivingMode value) { + + car_driving_mode_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.Safety.car_driving_mode) +} + +// ------------------------------------------------------------------- + +// BasicInfo + +// bool is_auto_mode = 1; +inline void BasicInfo::clear_is_auto_mode() { + is_auto_mode_ = false; +} +inline bool BasicInfo::is_auto_mode() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.is_auto_mode) + return is_auto_mode_; +} +inline void BasicInfo::set_is_auto_mode(bool value) { + + is_auto_mode_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.is_auto_mode) +} + +// .apollo.canbus.BasicInfo.Type power_state = 2; +inline void BasicInfo::clear_power_state() { + power_state_ = 0; +} +inline ::apollo::canbus::BasicInfo_Type BasicInfo::power_state() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.power_state) + return static_cast< ::apollo::canbus::BasicInfo_Type >(power_state_); +} +inline void BasicInfo::set_power_state(::apollo::canbus::BasicInfo_Type value) { + + power_state_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.power_state) +} + +// bool is_air_bag_deployed = 3; +inline void BasicInfo::clear_is_air_bag_deployed() { + is_air_bag_deployed_ = false; +} +inline bool BasicInfo::is_air_bag_deployed() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.is_air_bag_deployed) + return is_air_bag_deployed_; +} +inline void BasicInfo::set_is_air_bag_deployed(bool value) { + + is_air_bag_deployed_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.is_air_bag_deployed) +} + +// double odo_meter = 4; +inline void BasicInfo::clear_odo_meter() { + odo_meter_ = 0; +} +inline double BasicInfo::odo_meter() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.odo_meter) + return odo_meter_; +} +inline void BasicInfo::set_odo_meter(double value) { + + odo_meter_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.odo_meter) +} + +// double drive_range = 5; +inline void BasicInfo::clear_drive_range() { + drive_range_ = 0; +} +inline double BasicInfo::drive_range() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.drive_range) + return drive_range_; +} +inline void BasicInfo::set_drive_range(double value) { + + drive_range_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.drive_range) +} + +// bool is_system_error = 6; +inline void BasicInfo::clear_is_system_error() { + is_system_error_ = false; +} +inline bool BasicInfo::is_system_error() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.is_system_error) + return is_system_error_; +} +inline void BasicInfo::set_is_system_error(bool value) { + + is_system_error_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.is_system_error) +} + +// bool is_human_interrupt = 7; +inline void BasicInfo::clear_is_human_interrupt() { + is_human_interrupt_ = false; +} +inline bool BasicInfo::is_human_interrupt() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.is_human_interrupt) + return is_human_interrupt_; +} +inline void BasicInfo::set_is_human_interrupt(bool value) { + + is_human_interrupt_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.is_human_interrupt) +} + +// bool acc_on_button = 8; +inline void BasicInfo::clear_acc_on_button() { + acc_on_button_ = false; +} +inline bool BasicInfo::acc_on_button() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.acc_on_button) + return acc_on_button_; +} +inline void BasicInfo::set_acc_on_button(bool value) { + + acc_on_button_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.acc_on_button) +} + +// bool acc_off_button = 9; +inline void BasicInfo::clear_acc_off_button() { + acc_off_button_ = false; +} +inline bool BasicInfo::acc_off_button() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.acc_off_button) + return acc_off_button_; +} +inline void BasicInfo::set_acc_off_button(bool value) { + + acc_off_button_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.acc_off_button) +} + +// bool acc_res_button = 10; +inline void BasicInfo::clear_acc_res_button() { + acc_res_button_ = false; +} +inline bool BasicInfo::acc_res_button() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.acc_res_button) + return acc_res_button_; +} +inline void BasicInfo::set_acc_res_button(bool value) { + + acc_res_button_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.acc_res_button) +} + +// bool acc_cancel_button = 11; +inline void BasicInfo::clear_acc_cancel_button() { + acc_cancel_button_ = false; +} +inline bool BasicInfo::acc_cancel_button() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.acc_cancel_button) + return acc_cancel_button_; +} +inline void BasicInfo::set_acc_cancel_button(bool value) { + + acc_cancel_button_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.acc_cancel_button) +} + +// bool acc_on_off_button = 12; +inline void BasicInfo::clear_acc_on_off_button() { + acc_on_off_button_ = false; +} +inline bool BasicInfo::acc_on_off_button() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.acc_on_off_button) + return acc_on_off_button_; +} +inline void BasicInfo::set_acc_on_off_button(bool value) { + + acc_on_off_button_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.acc_on_off_button) +} + +// bool acc_res_cancel_button = 13; +inline void BasicInfo::clear_acc_res_cancel_button() { + acc_res_cancel_button_ = false; +} +inline bool BasicInfo::acc_res_cancel_button() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.acc_res_cancel_button) + return acc_res_cancel_button_; +} +inline void BasicInfo::set_acc_res_cancel_button(bool value) { + + acc_res_cancel_button_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.acc_res_cancel_button) +} + +// bool acc_inc_spd_button = 14; +inline void BasicInfo::clear_acc_inc_spd_button() { + acc_inc_spd_button_ = false; +} +inline bool BasicInfo::acc_inc_spd_button() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.acc_inc_spd_button) + return acc_inc_spd_button_; +} +inline void BasicInfo::set_acc_inc_spd_button(bool value) { + + acc_inc_spd_button_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.acc_inc_spd_button) +} + +// bool acc_dec_spd_button = 15; +inline void BasicInfo::clear_acc_dec_spd_button() { + acc_dec_spd_button_ = false; +} +inline bool BasicInfo::acc_dec_spd_button() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.acc_dec_spd_button) + return acc_dec_spd_button_; +} +inline void BasicInfo::set_acc_dec_spd_button(bool value) { + + acc_dec_spd_button_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.acc_dec_spd_button) +} + +// bool acc_inc_gap_button = 16; +inline void BasicInfo::clear_acc_inc_gap_button() { + acc_inc_gap_button_ = false; +} +inline bool BasicInfo::acc_inc_gap_button() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.acc_inc_gap_button) + return acc_inc_gap_button_; +} +inline void BasicInfo::set_acc_inc_gap_button(bool value) { + + acc_inc_gap_button_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.acc_inc_gap_button) +} + +// bool acc_dec_gap_button = 17; +inline void BasicInfo::clear_acc_dec_gap_button() { + acc_dec_gap_button_ = false; +} +inline bool BasicInfo::acc_dec_gap_button() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.acc_dec_gap_button) + return acc_dec_gap_button_; +} +inline void BasicInfo::set_acc_dec_gap_button(bool value) { + + acc_dec_gap_button_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.acc_dec_gap_button) +} + +// bool lka_button = 18; +inline void BasicInfo::clear_lka_button() { + lka_button_ = false; +} +inline bool BasicInfo::lka_button() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.lka_button) + return lka_button_; +} +inline void BasicInfo::set_lka_button(bool value) { + + lka_button_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.lka_button) +} + +// bool canbus_fault = 19; +inline void BasicInfo::clear_canbus_fault() { + canbus_fault_ = false; +} +inline bool BasicInfo::canbus_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.canbus_fault) + return canbus_fault_; +} +inline void BasicInfo::set_canbus_fault(bool value) { + + canbus_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.canbus_fault) +} + +// double latitude = 20; +inline void BasicInfo::clear_latitude() { + latitude_ = 0; +} +inline double BasicInfo::latitude() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.latitude) + return latitude_; +} +inline void BasicInfo::set_latitude(double value) { + + latitude_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.latitude) +} + +// double longitude = 21; +inline void BasicInfo::clear_longitude() { + longitude_ = 0; +} +inline double BasicInfo::longitude() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.longitude) + return longitude_; +} +inline void BasicInfo::set_longitude(double value) { + + longitude_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.longitude) +} + +// bool gps_valid = 22; +inline void BasicInfo::clear_gps_valid() { + gps_valid_ = false; +} +inline bool BasicInfo::gps_valid() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.gps_valid) + return gps_valid_; +} +inline void BasicInfo::set_gps_valid(bool value) { + + gps_valid_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.gps_valid) +} + +// int32 year = 23; +inline void BasicInfo::clear_year() { + year_ = 0; +} +inline ::google::protobuf::int32 BasicInfo::year() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.year) + return year_; +} +inline void BasicInfo::set_year(::google::protobuf::int32 value) { + + year_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.year) +} + +// int32 month = 24; +inline void BasicInfo::clear_month() { + month_ = 0; +} +inline ::google::protobuf::int32 BasicInfo::month() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.month) + return month_; +} +inline void BasicInfo::set_month(::google::protobuf::int32 value) { + + month_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.month) +} + +// int32 day = 25; +inline void BasicInfo::clear_day() { + day_ = 0; +} +inline ::google::protobuf::int32 BasicInfo::day() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.day) + return day_; +} +inline void BasicInfo::set_day(::google::protobuf::int32 value) { + + day_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.day) +} + +// int32 hours = 26; +inline void BasicInfo::clear_hours() { + hours_ = 0; +} +inline ::google::protobuf::int32 BasicInfo::hours() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.hours) + return hours_; +} +inline void BasicInfo::set_hours(::google::protobuf::int32 value) { + + hours_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.hours) +} + +// int32 minutes = 27; +inline void BasicInfo::clear_minutes() { + minutes_ = 0; +} +inline ::google::protobuf::int32 BasicInfo::minutes() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.minutes) + return minutes_; +} +inline void BasicInfo::set_minutes(::google::protobuf::int32 value) { + + minutes_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.minutes) +} + +// int32 seconds = 28; +inline void BasicInfo::clear_seconds() { + seconds_ = 0; +} +inline ::google::protobuf::int32 BasicInfo::seconds() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.seconds) + return seconds_; +} +inline void BasicInfo::set_seconds(::google::protobuf::int32 value) { + + seconds_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.seconds) +} + +// double compass_direction = 29; +inline void BasicInfo::clear_compass_direction() { + compass_direction_ = 0; +} +inline double BasicInfo::compass_direction() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.compass_direction) + return compass_direction_; +} +inline void BasicInfo::set_compass_direction(double value) { + + compass_direction_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.compass_direction) +} + +// double pdop = 30; +inline void BasicInfo::clear_pdop() { + pdop_ = 0; +} +inline double BasicInfo::pdop() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.pdop) + return pdop_; +} +inline void BasicInfo::set_pdop(double value) { + + pdop_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.pdop) +} + +// bool is_gps_fault = 31; +inline void BasicInfo::clear_is_gps_fault() { + is_gps_fault_ = false; +} +inline bool BasicInfo::is_gps_fault() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.is_gps_fault) + return is_gps_fault_; +} +inline void BasicInfo::set_is_gps_fault(bool value) { + + is_gps_fault_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.is_gps_fault) +} + +// bool is_inferred = 32; +inline void BasicInfo::clear_is_inferred() { + is_inferred_ = false; +} +inline bool BasicInfo::is_inferred() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.is_inferred) + return is_inferred_; +} +inline void BasicInfo::set_is_inferred(bool value) { + + is_inferred_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.is_inferred) +} + +// double altitude = 33; +inline void BasicInfo::clear_altitude() { + altitude_ = 0; +} +inline double BasicInfo::altitude() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.altitude) + return altitude_; +} +inline void BasicInfo::set_altitude(double value) { + + altitude_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.altitude) +} + +// double heading = 34; +inline void BasicInfo::clear_heading() { + heading_ = 0; +} +inline double BasicInfo::heading() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.heading) + return heading_; +} +inline void BasicInfo::set_heading(double value) { + + heading_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.heading) +} + +// double hdop = 35; +inline void BasicInfo::clear_hdop() { + hdop_ = 0; +} +inline double BasicInfo::hdop() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.hdop) + return hdop_; +} +inline void BasicInfo::set_hdop(double value) { + + hdop_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.hdop) +} + +// double vdop = 36; +inline void BasicInfo::clear_vdop() { + vdop_ = 0; +} +inline double BasicInfo::vdop() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.vdop) + return vdop_; +} +inline void BasicInfo::set_vdop(double value) { + + vdop_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.vdop) +} + +// .apollo.canbus.BasicInfo.GpsQuality quality = 37; +inline void BasicInfo::clear_quality() { + quality_ = 0; +} +inline ::apollo::canbus::BasicInfo_GpsQuality BasicInfo::quality() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.quality) + return static_cast< ::apollo::canbus::BasicInfo_GpsQuality >(quality_); +} +inline void BasicInfo::set_quality(::apollo::canbus::BasicInfo_GpsQuality value) { + + quality_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.quality) +} + +// int32 num_satellites = 38; +inline void BasicInfo::clear_num_satellites() { + num_satellites_ = 0; +} +inline ::google::protobuf::int32 BasicInfo::num_satellites() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.num_satellites) + return num_satellites_; +} +inline void BasicInfo::set_num_satellites(::google::protobuf::int32 value) { + + num_satellites_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.num_satellites) +} + +// double gps_speed = 39; +inline void BasicInfo::clear_gps_speed() { + gps_speed_ = 0; +} +inline double BasicInfo::gps_speed() const { + // @@protoc_insertion_point(field_get:apollo.canbus.BasicInfo.gps_speed) + return gps_speed_; +} +inline void BasicInfo::set_gps_speed(double value) { + + gps_speed_ = value; + // @@protoc_insertion_point(field_set:apollo.canbus.BasicInfo.gps_speed) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace canbus +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::canbus::ChassisDetail_Type> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::ChassisDetail_Type>() { + return ::apollo::canbus::ChassisDetail_Type_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::Light_TurnLightType> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Light_TurnLightType>() { + return ::apollo::canbus::Light_TurnLightType_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::Light_LampType> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Light_LampType>() { + return ::apollo::canbus::Light_LampType_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::Light_LincolnLampType> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Light_LincolnLampType>() { + return ::apollo::canbus::Light_LincolnLampType_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::Light_LincolnWiperType> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Light_LincolnWiperType>() { + return ::apollo::canbus::Light_LincolnWiperType_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::Light_LincolnAmbientType> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Light_LincolnAmbientType>() { + return ::apollo::canbus::Light_LincolnAmbientType_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::Eps_Type> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Eps_Type>() { + return ::apollo::canbus::Eps_Type_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::VehicleSpd_Type> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::VehicleSpd_Type>() { + return ::apollo::canbus::VehicleSpd_Type_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::Brake_HSAStatusType> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Brake_HSAStatusType>() { + return ::apollo::canbus::Brake_HSAStatusType_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::Brake_HSAModeType> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Brake_HSAModeType>() { + return ::apollo::canbus::Brake_HSAModeType_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::Epb_PBrakeType> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Epb_PBrakeType>() { + return ::apollo::canbus::Epb_PBrakeType_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::Ems_Type> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::Ems_Type>() { + return ::apollo::canbus::Ems_Type_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::BasicInfo_Type> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::BasicInfo_Type>() { + return ::apollo::canbus::BasicInfo_Type_descriptor(); +} +template <> struct is_proto_enum< ::apollo::canbus::BasicInfo_GpsQuality> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::canbus::BasicInfo_GpsQuality>() { + return ::apollo::canbus::BasicInfo_GpsQuality_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_5fdetail_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/common/adapter_config.pb.cc b/apollo_msgs/include/apollo_msgs/proto/common/adapter_config.pb.cc new file mode 100644 index 0000000..5e9d2cc --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/adapter_config.pb.cc @@ -0,0 +1,822 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/adapter_config.proto + +#include "apollo_msgs/proto/common/adapter_config.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_AdapterConfig; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto +namespace apollo { +namespace common { +namespace adapter { +class AdapterConfigDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _AdapterConfig_default_instance_; +class AdapterManagerConfigDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _AdapterManagerConfig_default_instance_; +} // namespace adapter +} // namespace common +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto { +static void InitDefaultsAdapterConfig() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::adapter::_AdapterConfig_default_instance_; + new (ptr) ::apollo::common::adapter::AdapterConfig(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::adapter::AdapterConfig::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_AdapterConfig = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsAdapterConfig}, {}}; + +static void InitDefaultsAdapterManagerConfig() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::adapter::_AdapterManagerConfig_default_instance_; + new (ptr) ::apollo::common::adapter::AdapterManagerConfig(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::adapter::AdapterManagerConfig::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_AdapterManagerConfig = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsAdapterManagerConfig}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::scc_info_AdapterConfig.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_AdapterConfig.base); + ::google::protobuf::internal::InitSCC(&scc_info_AdapterManagerConfig.base); +} + +::google::protobuf::Metadata file_level_metadata[2]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[2]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::adapter::AdapterConfig, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::adapter::AdapterConfig, type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::adapter::AdapterConfig, mode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::adapter::AdapterConfig, message_history_limit_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::adapter::AdapterManagerConfig, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::adapter::AdapterManagerConfig, config_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::adapter::AdapterManagerConfig, is_ros_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::common::adapter::AdapterConfig)}, + { 8, -1, sizeof(::apollo::common::adapter::AdapterManagerConfig)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::common::adapter::_AdapterConfig_default_instance_), + reinterpret_cast(&::apollo::common::adapter::_AdapterManagerConfig_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/common/adapter_config.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 2); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n-apollo_msgs/proto/common/adapter_confi" + "g.proto\022\025apollo.common.adapter\"\352\003\n\rAdapt" + "erConfig\022>\n\004type\030\001 \001(\01620.apollo.common.a" + "dapter.AdapterConfig.MessageType\0227\n\004mode" + "\030\002 \001(\0162).apollo.common.adapter.AdapterCo" + "nfig.Mode\022\035\n\025message_history_limit\030\003 \001(\005" + "\"\210\002\n\013MessageType\022\017\n\013POINT_CLOUD\020\000\022\007\n\003GPS" + "\020\001\022\007\n\003IMU\020\002\022\013\n\007CHASSIS\020\003\022\020\n\014LOCALIZATION" + "\020\004\022\027\n\023PLANNING_TRAJECTORY\020\005\022\013\n\007MONITOR\020\006" + "\022\007\n\003PAD\020\007\022\023\n\017CONTROL_COMMAND\020\010\022\016\n\nPREDIC" + "TION\020\t\022\030\n\024PERCEPTION_OBSTACLES\020\n\022\033\n\027TRAF" + "FIC_LIGHT_DETECTION\020\013\022\022\n\016CHASSIS_DETAIL\020" + "\014\022\014\n\010DECISION\020\r\022\n\n\006CANBUS\020\016\"6\n\004Mode\022\020\n\014R" + "ECEIVE_ONLY\020\000\022\020\n\014PUBLISH_ONLY\020\001\022\n\n\006DUPLE" + "X\020\002\"\\\n\024AdapterManagerConfig\0224\n\006config\030\001 " + "\003(\0132$.apollo.common.adapter.AdapterConfi" + "g\022\016\n\006is_ros\030\002 \001(\010b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 665); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/common/adapter_config.proto", &protobuf_RegisterTypes); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto +namespace apollo { +namespace common { +namespace adapter { +const ::google::protobuf::EnumDescriptor* AdapterConfig_MessageType_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::file_level_enum_descriptors[0]; +} +bool AdapterConfig_MessageType_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + case 6: + case 7: + case 8: + case 9: + case 10: + case 11: + case 12: + case 13: + case 14: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const AdapterConfig_MessageType AdapterConfig::POINT_CLOUD; +const AdapterConfig_MessageType AdapterConfig::GPS; +const AdapterConfig_MessageType AdapterConfig::IMU; +const AdapterConfig_MessageType AdapterConfig::CHASSIS; +const AdapterConfig_MessageType AdapterConfig::LOCALIZATION; +const AdapterConfig_MessageType AdapterConfig::PLANNING_TRAJECTORY; +const AdapterConfig_MessageType AdapterConfig::MONITOR; +const AdapterConfig_MessageType AdapterConfig::PAD; +const AdapterConfig_MessageType AdapterConfig::CONTROL_COMMAND; +const AdapterConfig_MessageType AdapterConfig::PREDICTION; +const AdapterConfig_MessageType AdapterConfig::PERCEPTION_OBSTACLES; +const AdapterConfig_MessageType AdapterConfig::TRAFFIC_LIGHT_DETECTION; +const AdapterConfig_MessageType AdapterConfig::CHASSIS_DETAIL; +const AdapterConfig_MessageType AdapterConfig::DECISION; +const AdapterConfig_MessageType AdapterConfig::CANBUS; +const AdapterConfig_MessageType AdapterConfig::MessageType_MIN; +const AdapterConfig_MessageType AdapterConfig::MessageType_MAX; +const int AdapterConfig::MessageType_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* AdapterConfig_Mode_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::file_level_enum_descriptors[1]; +} +bool AdapterConfig_Mode_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const AdapterConfig_Mode AdapterConfig::RECEIVE_ONLY; +const AdapterConfig_Mode AdapterConfig::PUBLISH_ONLY; +const AdapterConfig_Mode AdapterConfig::DUPLEX; +const AdapterConfig_Mode AdapterConfig::Mode_MIN; +const AdapterConfig_Mode AdapterConfig::Mode_MAX; +const int AdapterConfig::Mode_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +// =================================================================== + +void AdapterConfig::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int AdapterConfig::kTypeFieldNumber; +const int AdapterConfig::kModeFieldNumber; +const int AdapterConfig::kMessageHistoryLimitFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +AdapterConfig::AdapterConfig() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::scc_info_AdapterConfig.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.adapter.AdapterConfig) +} +AdapterConfig::AdapterConfig(const AdapterConfig& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&type_, &from.type_, + static_cast(reinterpret_cast(&message_history_limit_) - + reinterpret_cast(&type_)) + sizeof(message_history_limit_)); + // @@protoc_insertion_point(copy_constructor:apollo.common.adapter.AdapterConfig) +} + +void AdapterConfig::SharedCtor() { + ::memset(&type_, 0, static_cast( + reinterpret_cast(&message_history_limit_) - + reinterpret_cast(&type_)) + sizeof(message_history_limit_)); +} + +AdapterConfig::~AdapterConfig() { + // @@protoc_insertion_point(destructor:apollo.common.adapter.AdapterConfig) + SharedDtor(); +} + +void AdapterConfig::SharedDtor() { +} + +void AdapterConfig::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* AdapterConfig::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const AdapterConfig& AdapterConfig::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::scc_info_AdapterConfig.base); + return *internal_default_instance(); +} + + +void AdapterConfig::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.adapter.AdapterConfig) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&type_, 0, static_cast( + reinterpret_cast(&message_history_limit_) - + reinterpret_cast(&type_)) + sizeof(message_history_limit_)); + _internal_metadata_.Clear(); +} + +bool AdapterConfig::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.adapter.AdapterConfig) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.adapter.AdapterConfig.MessageType type = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_type(static_cast< ::apollo::common::adapter::AdapterConfig_MessageType >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.adapter.AdapterConfig.Mode mode = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_mode(static_cast< ::apollo::common::adapter::AdapterConfig_Mode >(value)); + } else { + goto handle_unusual; + } + break; + } + + // int32 message_history_limit = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &message_history_limit_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.adapter.AdapterConfig) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.adapter.AdapterConfig) + return false; +#undef DO_ +} + +void AdapterConfig::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.adapter.AdapterConfig) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.adapter.AdapterConfig.MessageType type = 1; + if (this->type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->type(), output); + } + + // .apollo.common.adapter.AdapterConfig.Mode mode = 2; + if (this->mode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 2, this->mode(), output); + } + + // int32 message_history_limit = 3; + if (this->message_history_limit() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(3, this->message_history_limit(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.adapter.AdapterConfig) +} + +::google::protobuf::uint8* AdapterConfig::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.adapter.AdapterConfig) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.adapter.AdapterConfig.MessageType type = 1; + if (this->type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->type(), target); + } + + // .apollo.common.adapter.AdapterConfig.Mode mode = 2; + if (this->mode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 2, this->mode(), target); + } + + // int32 message_history_limit = 3; + if (this->message_history_limit() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(3, this->message_history_limit(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.adapter.AdapterConfig) + return target; +} + +size_t AdapterConfig::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.adapter.AdapterConfig) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.adapter.AdapterConfig.MessageType type = 1; + if (this->type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->type()); + } + + // .apollo.common.adapter.AdapterConfig.Mode mode = 2; + if (this->mode() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->mode()); + } + + // int32 message_history_limit = 3; + if (this->message_history_limit() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->message_history_limit()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void AdapterConfig::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.adapter.AdapterConfig) + GOOGLE_DCHECK_NE(&from, this); + const AdapterConfig* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.adapter.AdapterConfig) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.adapter.AdapterConfig) + MergeFrom(*source); + } +} + +void AdapterConfig::MergeFrom(const AdapterConfig& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.adapter.AdapterConfig) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.type() != 0) { + set_type(from.type()); + } + if (from.mode() != 0) { + set_mode(from.mode()); + } + if (from.message_history_limit() != 0) { + set_message_history_limit(from.message_history_limit()); + } +} + +void AdapterConfig::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.adapter.AdapterConfig) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void AdapterConfig::CopyFrom(const AdapterConfig& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.adapter.AdapterConfig) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool AdapterConfig::IsInitialized() const { + return true; +} + +void AdapterConfig::Swap(AdapterConfig* other) { + if (other == this) return; + InternalSwap(other); +} +void AdapterConfig::InternalSwap(AdapterConfig* other) { + using std::swap; + swap(type_, other->type_); + swap(mode_, other->mode_); + swap(message_history_limit_, other->message_history_limit_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata AdapterConfig::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void AdapterManagerConfig::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int AdapterManagerConfig::kConfigFieldNumber; +const int AdapterManagerConfig::kIsRosFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +AdapterManagerConfig::AdapterManagerConfig() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::scc_info_AdapterManagerConfig.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.adapter.AdapterManagerConfig) +} +AdapterManagerConfig::AdapterManagerConfig(const AdapterManagerConfig& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + config_(from.config_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + is_ros_ = from.is_ros_; + // @@protoc_insertion_point(copy_constructor:apollo.common.adapter.AdapterManagerConfig) +} + +void AdapterManagerConfig::SharedCtor() { + is_ros_ = false; +} + +AdapterManagerConfig::~AdapterManagerConfig() { + // @@protoc_insertion_point(destructor:apollo.common.adapter.AdapterManagerConfig) + SharedDtor(); +} + +void AdapterManagerConfig::SharedDtor() { +} + +void AdapterManagerConfig::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* AdapterManagerConfig::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const AdapterManagerConfig& AdapterManagerConfig::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::scc_info_AdapterManagerConfig.base); + return *internal_default_instance(); +} + + +void AdapterManagerConfig::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.adapter.AdapterManagerConfig) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + config_.Clear(); + is_ros_ = false; + _internal_metadata_.Clear(); +} + +bool AdapterManagerConfig::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.adapter.AdapterManagerConfig) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // repeated .apollo.common.adapter.AdapterConfig config = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_config())); + } else { + goto handle_unusual; + } + break; + } + + // bool is_ros = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_ros_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.adapter.AdapterManagerConfig) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.adapter.AdapterManagerConfig) + return false; +#undef DO_ +} + +void AdapterManagerConfig::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.adapter.AdapterManagerConfig) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.common.adapter.AdapterConfig config = 1; + for (unsigned int i = 0, + n = static_cast(this->config_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, + this->config(static_cast(i)), + output); + } + + // bool is_ros = 2; + if (this->is_ros() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_ros(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.adapter.AdapterManagerConfig) +} + +::google::protobuf::uint8* AdapterManagerConfig::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.adapter.AdapterManagerConfig) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.common.adapter.AdapterConfig config = 1; + for (unsigned int i = 0, + n = static_cast(this->config_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->config(static_cast(i)), deterministic, target); + } + + // bool is_ros = 2; + if (this->is_ros() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_ros(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.adapter.AdapterManagerConfig) + return target; +} + +size_t AdapterManagerConfig::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.adapter.AdapterManagerConfig) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.common.adapter.AdapterConfig config = 1; + { + unsigned int count = static_cast(this->config_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->config(static_cast(i))); + } + } + + // bool is_ros = 2; + if (this->is_ros() != 0) { + total_size += 1 + 1; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void AdapterManagerConfig::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.adapter.AdapterManagerConfig) + GOOGLE_DCHECK_NE(&from, this); + const AdapterManagerConfig* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.adapter.AdapterManagerConfig) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.adapter.AdapterManagerConfig) + MergeFrom(*source); + } +} + +void AdapterManagerConfig::MergeFrom(const AdapterManagerConfig& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.adapter.AdapterManagerConfig) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + config_.MergeFrom(from.config_); + if (from.is_ros() != 0) { + set_is_ros(from.is_ros()); + } +} + +void AdapterManagerConfig::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.adapter.AdapterManagerConfig) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void AdapterManagerConfig::CopyFrom(const AdapterManagerConfig& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.adapter.AdapterManagerConfig) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool AdapterManagerConfig::IsInitialized() const { + return true; +} + +void AdapterManagerConfig::Swap(AdapterManagerConfig* other) { + if (other == this) return; + InternalSwap(other); +} +void AdapterManagerConfig::InternalSwap(AdapterManagerConfig* other) { + using std::swap; + CastToBase(&config_)->InternalSwap(CastToBase(&other->config_)); + swap(is_ros_, other->is_ros_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata AdapterManagerConfig::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace adapter +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::adapter::AdapterConfig* Arena::CreateMaybeMessage< ::apollo::common::adapter::AdapterConfig >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::adapter::AdapterConfig >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::adapter::AdapterManagerConfig* Arena::CreateMaybeMessage< ::apollo::common::adapter::AdapterManagerConfig >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::adapter::AdapterManagerConfig >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/common/adapter_config.pb.h b/apollo_msgs/include/apollo_msgs/proto/common/adapter_config.pb.h new file mode 100644 index 0000000..a807690 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/adapter_config.pb.h @@ -0,0 +1,572 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/adapter_config.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[2]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto +namespace apollo { +namespace common { +namespace adapter { +class AdapterConfig; +class AdapterConfigDefaultTypeInternal; +extern AdapterConfigDefaultTypeInternal _AdapterConfig_default_instance_; +class AdapterManagerConfig; +class AdapterManagerConfigDefaultTypeInternal; +extern AdapterManagerConfigDefaultTypeInternal _AdapterManagerConfig_default_instance_; +} // namespace adapter +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::common::adapter::AdapterConfig* Arena::CreateMaybeMessage<::apollo::common::adapter::AdapterConfig>(Arena*); +template<> ::apollo::common::adapter::AdapterManagerConfig* Arena::CreateMaybeMessage<::apollo::common::adapter::AdapterManagerConfig>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace common { +namespace adapter { + +enum AdapterConfig_MessageType { + AdapterConfig_MessageType_POINT_CLOUD = 0, + AdapterConfig_MessageType_GPS = 1, + AdapterConfig_MessageType_IMU = 2, + AdapterConfig_MessageType_CHASSIS = 3, + AdapterConfig_MessageType_LOCALIZATION = 4, + AdapterConfig_MessageType_PLANNING_TRAJECTORY = 5, + AdapterConfig_MessageType_MONITOR = 6, + AdapterConfig_MessageType_PAD = 7, + AdapterConfig_MessageType_CONTROL_COMMAND = 8, + AdapterConfig_MessageType_PREDICTION = 9, + AdapterConfig_MessageType_PERCEPTION_OBSTACLES = 10, + AdapterConfig_MessageType_TRAFFIC_LIGHT_DETECTION = 11, + AdapterConfig_MessageType_CHASSIS_DETAIL = 12, + AdapterConfig_MessageType_DECISION = 13, + AdapterConfig_MessageType_CANBUS = 14, + AdapterConfig_MessageType_AdapterConfig_MessageType_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + AdapterConfig_MessageType_AdapterConfig_MessageType_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool AdapterConfig_MessageType_IsValid(int value); +const AdapterConfig_MessageType AdapterConfig_MessageType_MessageType_MIN = AdapterConfig_MessageType_POINT_CLOUD; +const AdapterConfig_MessageType AdapterConfig_MessageType_MessageType_MAX = AdapterConfig_MessageType_CANBUS; +const int AdapterConfig_MessageType_MessageType_ARRAYSIZE = AdapterConfig_MessageType_MessageType_MAX + 1; + +const ::google::protobuf::EnumDescriptor* AdapterConfig_MessageType_descriptor(); +inline const ::std::string& AdapterConfig_MessageType_Name(AdapterConfig_MessageType value) { + return ::google::protobuf::internal::NameOfEnum( + AdapterConfig_MessageType_descriptor(), value); +} +inline bool AdapterConfig_MessageType_Parse( + const ::std::string& name, AdapterConfig_MessageType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + AdapterConfig_MessageType_descriptor(), name, value); +} +enum AdapterConfig_Mode { + AdapterConfig_Mode_RECEIVE_ONLY = 0, + AdapterConfig_Mode_PUBLISH_ONLY = 1, + AdapterConfig_Mode_DUPLEX = 2, + AdapterConfig_Mode_AdapterConfig_Mode_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + AdapterConfig_Mode_AdapterConfig_Mode_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool AdapterConfig_Mode_IsValid(int value); +const AdapterConfig_Mode AdapterConfig_Mode_Mode_MIN = AdapterConfig_Mode_RECEIVE_ONLY; +const AdapterConfig_Mode AdapterConfig_Mode_Mode_MAX = AdapterConfig_Mode_DUPLEX; +const int AdapterConfig_Mode_Mode_ARRAYSIZE = AdapterConfig_Mode_Mode_MAX + 1; + +const ::google::protobuf::EnumDescriptor* AdapterConfig_Mode_descriptor(); +inline const ::std::string& AdapterConfig_Mode_Name(AdapterConfig_Mode value) { + return ::google::protobuf::internal::NameOfEnum( + AdapterConfig_Mode_descriptor(), value); +} +inline bool AdapterConfig_Mode_Parse( + const ::std::string& name, AdapterConfig_Mode* value) { + return ::google::protobuf::internal::ParseNamedEnum( + AdapterConfig_Mode_descriptor(), name, value); +} +// =================================================================== + +class AdapterConfig : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.adapter.AdapterConfig) */ { + public: + AdapterConfig(); + virtual ~AdapterConfig(); + + AdapterConfig(const AdapterConfig& from); + + inline AdapterConfig& operator=(const AdapterConfig& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + AdapterConfig(AdapterConfig&& from) noexcept + : AdapterConfig() { + *this = ::std::move(from); + } + + inline AdapterConfig& operator=(AdapterConfig&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const AdapterConfig& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const AdapterConfig* internal_default_instance() { + return reinterpret_cast( + &_AdapterConfig_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(AdapterConfig* other); + friend void swap(AdapterConfig& a, AdapterConfig& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline AdapterConfig* New() const final { + return CreateMaybeMessage(NULL); + } + + AdapterConfig* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const AdapterConfig& from); + void MergeFrom(const AdapterConfig& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(AdapterConfig* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef AdapterConfig_MessageType MessageType; + static const MessageType POINT_CLOUD = + AdapterConfig_MessageType_POINT_CLOUD; + static const MessageType GPS = + AdapterConfig_MessageType_GPS; + static const MessageType IMU = + AdapterConfig_MessageType_IMU; + static const MessageType CHASSIS = + AdapterConfig_MessageType_CHASSIS; + static const MessageType LOCALIZATION = + AdapterConfig_MessageType_LOCALIZATION; + static const MessageType PLANNING_TRAJECTORY = + AdapterConfig_MessageType_PLANNING_TRAJECTORY; + static const MessageType MONITOR = + AdapterConfig_MessageType_MONITOR; + static const MessageType PAD = + AdapterConfig_MessageType_PAD; + static const MessageType CONTROL_COMMAND = + AdapterConfig_MessageType_CONTROL_COMMAND; + static const MessageType PREDICTION = + AdapterConfig_MessageType_PREDICTION; + static const MessageType PERCEPTION_OBSTACLES = + AdapterConfig_MessageType_PERCEPTION_OBSTACLES; + static const MessageType TRAFFIC_LIGHT_DETECTION = + AdapterConfig_MessageType_TRAFFIC_LIGHT_DETECTION; + static const MessageType CHASSIS_DETAIL = + AdapterConfig_MessageType_CHASSIS_DETAIL; + static const MessageType DECISION = + AdapterConfig_MessageType_DECISION; + static const MessageType CANBUS = + AdapterConfig_MessageType_CANBUS; + static inline bool MessageType_IsValid(int value) { + return AdapterConfig_MessageType_IsValid(value); + } + static const MessageType MessageType_MIN = + AdapterConfig_MessageType_MessageType_MIN; + static const MessageType MessageType_MAX = + AdapterConfig_MessageType_MessageType_MAX; + static const int MessageType_ARRAYSIZE = + AdapterConfig_MessageType_MessageType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + MessageType_descriptor() { + return AdapterConfig_MessageType_descriptor(); + } + static inline const ::std::string& MessageType_Name(MessageType value) { + return AdapterConfig_MessageType_Name(value); + } + static inline bool MessageType_Parse(const ::std::string& name, + MessageType* value) { + return AdapterConfig_MessageType_Parse(name, value); + } + + typedef AdapterConfig_Mode Mode; + static const Mode RECEIVE_ONLY = + AdapterConfig_Mode_RECEIVE_ONLY; + static const Mode PUBLISH_ONLY = + AdapterConfig_Mode_PUBLISH_ONLY; + static const Mode DUPLEX = + AdapterConfig_Mode_DUPLEX; + static inline bool Mode_IsValid(int value) { + return AdapterConfig_Mode_IsValid(value); + } + static const Mode Mode_MIN = + AdapterConfig_Mode_Mode_MIN; + static const Mode Mode_MAX = + AdapterConfig_Mode_Mode_MAX; + static const int Mode_ARRAYSIZE = + AdapterConfig_Mode_Mode_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Mode_descriptor() { + return AdapterConfig_Mode_descriptor(); + } + static inline const ::std::string& Mode_Name(Mode value) { + return AdapterConfig_Mode_Name(value); + } + static inline bool Mode_Parse(const ::std::string& name, + Mode* value) { + return AdapterConfig_Mode_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // .apollo.common.adapter.AdapterConfig.MessageType type = 1; + void clear_type(); + static const int kTypeFieldNumber = 1; + ::apollo::common::adapter::AdapterConfig_MessageType type() const; + void set_type(::apollo::common::adapter::AdapterConfig_MessageType value); + + // .apollo.common.adapter.AdapterConfig.Mode mode = 2; + void clear_mode(); + static const int kModeFieldNumber = 2; + ::apollo::common::adapter::AdapterConfig_Mode mode() const; + void set_mode(::apollo::common::adapter::AdapterConfig_Mode value); + + // int32 message_history_limit = 3; + void clear_message_history_limit(); + static const int kMessageHistoryLimitFieldNumber = 3; + ::google::protobuf::int32 message_history_limit() const; + void set_message_history_limit(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:apollo.common.adapter.AdapterConfig) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + int type_; + int mode_; + ::google::protobuf::int32 message_history_limit_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class AdapterManagerConfig : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.adapter.AdapterManagerConfig) */ { + public: + AdapterManagerConfig(); + virtual ~AdapterManagerConfig(); + + AdapterManagerConfig(const AdapterManagerConfig& from); + + inline AdapterManagerConfig& operator=(const AdapterManagerConfig& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + AdapterManagerConfig(AdapterManagerConfig&& from) noexcept + : AdapterManagerConfig() { + *this = ::std::move(from); + } + + inline AdapterManagerConfig& operator=(AdapterManagerConfig&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const AdapterManagerConfig& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const AdapterManagerConfig* internal_default_instance() { + return reinterpret_cast( + &_AdapterManagerConfig_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(AdapterManagerConfig* other); + friend void swap(AdapterManagerConfig& a, AdapterManagerConfig& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline AdapterManagerConfig* New() const final { + return CreateMaybeMessage(NULL); + } + + AdapterManagerConfig* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const AdapterManagerConfig& from); + void MergeFrom(const AdapterManagerConfig& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(AdapterManagerConfig* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.common.adapter.AdapterConfig config = 1; + int config_size() const; + void clear_config(); + static const int kConfigFieldNumber = 1; + ::apollo::common::adapter::AdapterConfig* mutable_config(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::common::adapter::AdapterConfig >* + mutable_config(); + const ::apollo::common::adapter::AdapterConfig& config(int index) const; + ::apollo::common::adapter::AdapterConfig* add_config(); + const ::google::protobuf::RepeatedPtrField< ::apollo::common::adapter::AdapterConfig >& + config() const; + + // bool is_ros = 2; + void clear_is_ros(); + static const int kIsRosFieldNumber = 2; + bool is_ros() const; + void set_is_ros(bool value); + + // @@protoc_insertion_point(class_scope:apollo.common.adapter.AdapterManagerConfig) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::common::adapter::AdapterConfig > config_; + bool is_ros_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// AdapterConfig + +// .apollo.common.adapter.AdapterConfig.MessageType type = 1; +inline void AdapterConfig::clear_type() { + type_ = 0; +} +inline ::apollo::common::adapter::AdapterConfig_MessageType AdapterConfig::type() const { + // @@protoc_insertion_point(field_get:apollo.common.adapter.AdapterConfig.type) + return static_cast< ::apollo::common::adapter::AdapterConfig_MessageType >(type_); +} +inline void AdapterConfig::set_type(::apollo::common::adapter::AdapterConfig_MessageType value) { + + type_ = value; + // @@protoc_insertion_point(field_set:apollo.common.adapter.AdapterConfig.type) +} + +// .apollo.common.adapter.AdapterConfig.Mode mode = 2; +inline void AdapterConfig::clear_mode() { + mode_ = 0; +} +inline ::apollo::common::adapter::AdapterConfig_Mode AdapterConfig::mode() const { + // @@protoc_insertion_point(field_get:apollo.common.adapter.AdapterConfig.mode) + return static_cast< ::apollo::common::adapter::AdapterConfig_Mode >(mode_); +} +inline void AdapterConfig::set_mode(::apollo::common::adapter::AdapterConfig_Mode value) { + + mode_ = value; + // @@protoc_insertion_point(field_set:apollo.common.adapter.AdapterConfig.mode) +} + +// int32 message_history_limit = 3; +inline void AdapterConfig::clear_message_history_limit() { + message_history_limit_ = 0; +} +inline ::google::protobuf::int32 AdapterConfig::message_history_limit() const { + // @@protoc_insertion_point(field_get:apollo.common.adapter.AdapterConfig.message_history_limit) + return message_history_limit_; +} +inline void AdapterConfig::set_message_history_limit(::google::protobuf::int32 value) { + + message_history_limit_ = value; + // @@protoc_insertion_point(field_set:apollo.common.adapter.AdapterConfig.message_history_limit) +} + +// ------------------------------------------------------------------- + +// AdapterManagerConfig + +// repeated .apollo.common.adapter.AdapterConfig config = 1; +inline int AdapterManagerConfig::config_size() const { + return config_.size(); +} +inline void AdapterManagerConfig::clear_config() { + config_.Clear(); +} +inline ::apollo::common::adapter::AdapterConfig* AdapterManagerConfig::mutable_config(int index) { + // @@protoc_insertion_point(field_mutable:apollo.common.adapter.AdapterManagerConfig.config) + return config_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::common::adapter::AdapterConfig >* +AdapterManagerConfig::mutable_config() { + // @@protoc_insertion_point(field_mutable_list:apollo.common.adapter.AdapterManagerConfig.config) + return &config_; +} +inline const ::apollo::common::adapter::AdapterConfig& AdapterManagerConfig::config(int index) const { + // @@protoc_insertion_point(field_get:apollo.common.adapter.AdapterManagerConfig.config) + return config_.Get(index); +} +inline ::apollo::common::adapter::AdapterConfig* AdapterManagerConfig::add_config() { + // @@protoc_insertion_point(field_add:apollo.common.adapter.AdapterManagerConfig.config) + return config_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::common::adapter::AdapterConfig >& +AdapterManagerConfig::config() const { + // @@protoc_insertion_point(field_list:apollo.common.adapter.AdapterManagerConfig.config) + return config_; +} + +// bool is_ros = 2; +inline void AdapterManagerConfig::clear_is_ros() { + is_ros_ = false; +} +inline bool AdapterManagerConfig::is_ros() const { + // @@protoc_insertion_point(field_get:apollo.common.adapter.AdapterManagerConfig.is_ros) + return is_ros_; +} +inline void AdapterManagerConfig::set_is_ros(bool value) { + + is_ros_ = value; + // @@protoc_insertion_point(field_set:apollo.common.adapter.AdapterManagerConfig.is_ros) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace adapter +} // namespace common +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::common::adapter::AdapterConfig_MessageType> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::common::adapter::AdapterConfig_MessageType>() { + return ::apollo::common::adapter::AdapterConfig_MessageType_descriptor(); +} +template <> struct is_proto_enum< ::apollo::common::adapter::AdapterConfig_Mode> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::common::adapter::AdapterConfig_Mode>() { + return ::apollo::common::adapter::AdapterConfig_Mode_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fadapter_5fconfig_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/common/config_extrinsics.pb.cc b/apollo_msgs/include/apollo_msgs/proto/common/config_extrinsics.pb.cc new file mode 100644 index 0000000..98a5a62 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/config_extrinsics.pb.cc @@ -0,0 +1,797 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/config_extrinsics.proto + +#include "apollo_msgs/proto/common/config_extrinsics.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_Transform; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Point3D; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Quaternion; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto +namespace apollo { +namespace common { +namespace config { +class TransformDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Transform_default_instance_; +class ExtrinsicsDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Extrinsics_default_instance_; +} // namespace config +} // namespace common +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto { +static void InitDefaultsTransform() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::config::_Transform_default_instance_; + new (ptr) ::apollo::common::config::Transform(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::config::Transform::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_Transform = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsTransform}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_Point3D.base, + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_Quaternion.base,}}; + +static void InitDefaultsExtrinsics() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::config::_Extrinsics_default_instance_; + new (ptr) ::apollo::common::config::Extrinsics(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::config::Extrinsics::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_Extrinsics = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsExtrinsics}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::scc_info_Transform.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_Transform.base); + ::google::protobuf::internal::InitSCC(&scc_info_Extrinsics.base); +} + +::google::protobuf::Metadata file_level_metadata[2]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::Transform, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::Transform, source_frame_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::Transform, target_frame_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::Transform, translation_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::Transform, rotation_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::Extrinsics, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::Extrinsics, tansforms_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::common::config::Transform)}, + { 9, -1, sizeof(::apollo::common::config::Extrinsics)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::common::config::_Transform_default_instance_), + reinterpret_cast(&::apollo::common::config::_Extrinsics_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/common/config_extrinsics.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 2); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n0apollo_msgs/proto/common/config_extrin" + "sics.proto\022\024apollo.common.config\032\'apollo" + "_msgs/proto/common/geometry.proto\"\221\001\n\tTr" + "ansform\022\024\n\014source_frame\030\001 \001(\014\022\024\n\014target_" + "frame\030\002 \001(\014\022+\n\013translation\030\003 \001(\0132\026.apoll" + "o.common.Point3D\022+\n\010rotation\030\004 \001(\0132\031.apo" + "llo.common.Quaternion\"@\n\nExtrinsics\0222\n\tt" + "ansforms\030\001 \003(\0132\037.apollo.common.config.Tr" + "ansformb\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 335); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/common/config_extrinsics.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto +namespace apollo { +namespace common { +namespace config { + +// =================================================================== + +void Transform::InitAsDefaultInstance() { + ::apollo::common::config::_Transform_default_instance_._instance.get_mutable()->translation_ = const_cast< ::apollo::common::Point3D*>( + ::apollo::common::Point3D::internal_default_instance()); + ::apollo::common::config::_Transform_default_instance_._instance.get_mutable()->rotation_ = const_cast< ::apollo::common::Quaternion*>( + ::apollo::common::Quaternion::internal_default_instance()); +} +void Transform::clear_translation() { + if (GetArenaNoVirtual() == NULL && translation_ != NULL) { + delete translation_; + } + translation_ = NULL; +} +void Transform::clear_rotation() { + if (GetArenaNoVirtual() == NULL && rotation_ != NULL) { + delete rotation_; + } + rotation_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Transform::kSourceFrameFieldNumber; +const int Transform::kTargetFrameFieldNumber; +const int Transform::kTranslationFieldNumber; +const int Transform::kRotationFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Transform::Transform() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::scc_info_Transform.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.config.Transform) +} +Transform::Transform(const Transform& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + source_frame_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.source_frame().size() > 0) { + source_frame_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.source_frame_); + } + target_frame_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.target_frame().size() > 0) { + target_frame_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.target_frame_); + } + if (from.has_translation()) { + translation_ = new ::apollo::common::Point3D(*from.translation_); + } else { + translation_ = NULL; + } + if (from.has_rotation()) { + rotation_ = new ::apollo::common::Quaternion(*from.rotation_); + } else { + rotation_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.common.config.Transform) +} + +void Transform::SharedCtor() { + source_frame_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + target_frame_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&translation_, 0, static_cast( + reinterpret_cast(&rotation_) - + reinterpret_cast(&translation_)) + sizeof(rotation_)); +} + +Transform::~Transform() { + // @@protoc_insertion_point(destructor:apollo.common.config.Transform) + SharedDtor(); +} + +void Transform::SharedDtor() { + source_frame_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + target_frame_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (this != internal_default_instance()) delete translation_; + if (this != internal_default_instance()) delete rotation_; +} + +void Transform::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Transform::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Transform& Transform::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::scc_info_Transform.base); + return *internal_default_instance(); +} + + +void Transform::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.config.Transform) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + source_frame_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + target_frame_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (GetArenaNoVirtual() == NULL && translation_ != NULL) { + delete translation_; + } + translation_ = NULL; + if (GetArenaNoVirtual() == NULL && rotation_ != NULL) { + delete rotation_; + } + rotation_ = NULL; + _internal_metadata_.Clear(); +} + +bool Transform::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.config.Transform) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bytes source_frame = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( + input, this->mutable_source_frame())); + } else { + goto handle_unusual; + } + break; + } + + // bytes target_frame = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( + input, this->mutable_target_frame())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Point3D translation = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_translation())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Quaternion rotation = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_rotation())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.config.Transform) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.config.Transform) + return false; +#undef DO_ +} + +void Transform::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.config.Transform) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bytes source_frame = 1; + if (this->source_frame().size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteBytesMaybeAliased( + 1, this->source_frame(), output); + } + + // bytes target_frame = 2; + if (this->target_frame().size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteBytesMaybeAliased( + 2, this->target_frame(), output); + } + + // .apollo.common.Point3D translation = 3; + if (this->has_translation()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_translation(), output); + } + + // .apollo.common.Quaternion rotation = 4; + if (this->has_rotation()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, this->_internal_rotation(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.config.Transform) +} + +::google::protobuf::uint8* Transform::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.config.Transform) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bytes source_frame = 1; + if (this->source_frame().size() > 0) { + target = + ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( + 1, this->source_frame(), target); + } + + // bytes target_frame = 2; + if (this->target_frame().size() > 0) { + target = + ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( + 2, this->target_frame(), target); + } + + // .apollo.common.Point3D translation = 3; + if (this->has_translation()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_translation(), deterministic, target); + } + + // .apollo.common.Quaternion rotation = 4; + if (this->has_rotation()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->_internal_rotation(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.config.Transform) + return target; +} + +size_t Transform::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.config.Transform) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // bytes source_frame = 1; + if (this->source_frame().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::BytesSize( + this->source_frame()); + } + + // bytes target_frame = 2; + if (this->target_frame().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::BytesSize( + this->target_frame()); + } + + // .apollo.common.Point3D translation = 3; + if (this->has_translation()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *translation_); + } + + // .apollo.common.Quaternion rotation = 4; + if (this->has_rotation()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *rotation_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Transform::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.config.Transform) + GOOGLE_DCHECK_NE(&from, this); + const Transform* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.config.Transform) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.config.Transform) + MergeFrom(*source); + } +} + +void Transform::MergeFrom(const Transform& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.config.Transform) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.source_frame().size() > 0) { + + source_frame_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.source_frame_); + } + if (from.target_frame().size() > 0) { + + target_frame_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.target_frame_); + } + if (from.has_translation()) { + mutable_translation()->::apollo::common::Point3D::MergeFrom(from.translation()); + } + if (from.has_rotation()) { + mutable_rotation()->::apollo::common::Quaternion::MergeFrom(from.rotation()); + } +} + +void Transform::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.config.Transform) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Transform::CopyFrom(const Transform& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.config.Transform) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Transform::IsInitialized() const { + return true; +} + +void Transform::Swap(Transform* other) { + if (other == this) return; + InternalSwap(other); +} +void Transform::InternalSwap(Transform* other) { + using std::swap; + source_frame_.Swap(&other->source_frame_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + target_frame_.Swap(&other->target_frame_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(translation_, other->translation_); + swap(rotation_, other->rotation_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Transform::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Extrinsics::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Extrinsics::kTansformsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Extrinsics::Extrinsics() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::scc_info_Extrinsics.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.config.Extrinsics) +} +Extrinsics::Extrinsics(const Extrinsics& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + tansforms_(from.tansforms_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:apollo.common.config.Extrinsics) +} + +void Extrinsics::SharedCtor() { +} + +Extrinsics::~Extrinsics() { + // @@protoc_insertion_point(destructor:apollo.common.config.Extrinsics) + SharedDtor(); +} + +void Extrinsics::SharedDtor() { +} + +void Extrinsics::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Extrinsics::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Extrinsics& Extrinsics::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::scc_info_Extrinsics.base); + return *internal_default_instance(); +} + + +void Extrinsics::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.config.Extrinsics) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + tansforms_.Clear(); + _internal_metadata_.Clear(); +} + +bool Extrinsics::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.config.Extrinsics) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // repeated .apollo.common.config.Transform tansforms = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_tansforms())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.config.Extrinsics) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.config.Extrinsics) + return false; +#undef DO_ +} + +void Extrinsics::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.config.Extrinsics) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.common.config.Transform tansforms = 1; + for (unsigned int i = 0, + n = static_cast(this->tansforms_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, + this->tansforms(static_cast(i)), + output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.config.Extrinsics) +} + +::google::protobuf::uint8* Extrinsics::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.config.Extrinsics) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.common.config.Transform tansforms = 1; + for (unsigned int i = 0, + n = static_cast(this->tansforms_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->tansforms(static_cast(i)), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.config.Extrinsics) + return target; +} + +size_t Extrinsics::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.config.Extrinsics) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.common.config.Transform tansforms = 1; + { + unsigned int count = static_cast(this->tansforms_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->tansforms(static_cast(i))); + } + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Extrinsics::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.config.Extrinsics) + GOOGLE_DCHECK_NE(&from, this); + const Extrinsics* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.config.Extrinsics) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.config.Extrinsics) + MergeFrom(*source); + } +} + +void Extrinsics::MergeFrom(const Extrinsics& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.config.Extrinsics) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + tansforms_.MergeFrom(from.tansforms_); +} + +void Extrinsics::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.config.Extrinsics) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Extrinsics::CopyFrom(const Extrinsics& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.config.Extrinsics) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Extrinsics::IsInitialized() const { + return true; +} + +void Extrinsics::Swap(Extrinsics* other) { + if (other == this) return; + InternalSwap(other); +} +void Extrinsics::InternalSwap(Extrinsics* other) { + using std::swap; + CastToBase(&tansforms_)->InternalSwap(CastToBase(&other->tansforms_)); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Extrinsics::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace config +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::config::Transform* Arena::CreateMaybeMessage< ::apollo::common::config::Transform >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::config::Transform >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::config::Extrinsics* Arena::CreateMaybeMessage< ::apollo::common::config::Extrinsics >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::config::Extrinsics >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/common/config_extrinsics.pb.h b/apollo_msgs/include/apollo_msgs/proto/common/config_extrinsics.pb.h new file mode 100644 index 0000000..e6b1a9a --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/config_extrinsics.pb.h @@ -0,0 +1,593 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/config_extrinsics.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include "apollo_msgs/proto/common/geometry.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[2]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto +namespace apollo { +namespace common { +namespace config { +class Extrinsics; +class ExtrinsicsDefaultTypeInternal; +extern ExtrinsicsDefaultTypeInternal _Extrinsics_default_instance_; +class Transform; +class TransformDefaultTypeInternal; +extern TransformDefaultTypeInternal _Transform_default_instance_; +} // namespace config +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::common::config::Extrinsics* Arena::CreateMaybeMessage<::apollo::common::config::Extrinsics>(Arena*); +template<> ::apollo::common::config::Transform* Arena::CreateMaybeMessage<::apollo::common::config::Transform>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace common { +namespace config { + +// =================================================================== + +class Transform : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.config.Transform) */ { + public: + Transform(); + virtual ~Transform(); + + Transform(const Transform& from); + + inline Transform& operator=(const Transform& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Transform(Transform&& from) noexcept + : Transform() { + *this = ::std::move(from); + } + + inline Transform& operator=(Transform&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Transform& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Transform* internal_default_instance() { + return reinterpret_cast( + &_Transform_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(Transform* other); + friend void swap(Transform& a, Transform& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Transform* New() const final { + return CreateMaybeMessage(NULL); + } + + Transform* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Transform& from); + void MergeFrom(const Transform& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Transform* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // bytes source_frame = 1; + void clear_source_frame(); + static const int kSourceFrameFieldNumber = 1; + const ::std::string& source_frame() const; + void set_source_frame(const ::std::string& value); + #if LANG_CXX11 + void set_source_frame(::std::string&& value); + #endif + void set_source_frame(const char* value); + void set_source_frame(const void* value, size_t size); + ::std::string* mutable_source_frame(); + ::std::string* release_source_frame(); + void set_allocated_source_frame(::std::string* source_frame); + + // bytes target_frame = 2; + void clear_target_frame(); + static const int kTargetFrameFieldNumber = 2; + const ::std::string& target_frame() const; + void set_target_frame(const ::std::string& value); + #if LANG_CXX11 + void set_target_frame(::std::string&& value); + #endif + void set_target_frame(const char* value); + void set_target_frame(const void* value, size_t size); + ::std::string* mutable_target_frame(); + ::std::string* release_target_frame(); + void set_allocated_target_frame(::std::string* target_frame); + + // .apollo.common.Point3D translation = 3; + bool has_translation() const; + void clear_translation(); + static const int kTranslationFieldNumber = 3; + private: + const ::apollo::common::Point3D& _internal_translation() const; + public: + const ::apollo::common::Point3D& translation() const; + ::apollo::common::Point3D* release_translation(); + ::apollo::common::Point3D* mutable_translation(); + void set_allocated_translation(::apollo::common::Point3D* translation); + + // .apollo.common.Quaternion rotation = 4; + bool has_rotation() const; + void clear_rotation(); + static const int kRotationFieldNumber = 4; + private: + const ::apollo::common::Quaternion& _internal_rotation() const; + public: + const ::apollo::common::Quaternion& rotation() const; + ::apollo::common::Quaternion* release_rotation(); + ::apollo::common::Quaternion* mutable_rotation(); + void set_allocated_rotation(::apollo::common::Quaternion* rotation); + + // @@protoc_insertion_point(class_scope:apollo.common.config.Transform) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr source_frame_; + ::google::protobuf::internal::ArenaStringPtr target_frame_; + ::apollo::common::Point3D* translation_; + ::apollo::common::Quaternion* rotation_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Extrinsics : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.config.Extrinsics) */ { + public: + Extrinsics(); + virtual ~Extrinsics(); + + Extrinsics(const Extrinsics& from); + + inline Extrinsics& operator=(const Extrinsics& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Extrinsics(Extrinsics&& from) noexcept + : Extrinsics() { + *this = ::std::move(from); + } + + inline Extrinsics& operator=(Extrinsics&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Extrinsics& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Extrinsics* internal_default_instance() { + return reinterpret_cast( + &_Extrinsics_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(Extrinsics* other); + friend void swap(Extrinsics& a, Extrinsics& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Extrinsics* New() const final { + return CreateMaybeMessage(NULL); + } + + Extrinsics* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Extrinsics& from); + void MergeFrom(const Extrinsics& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Extrinsics* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.common.config.Transform tansforms = 1; + int tansforms_size() const; + void clear_tansforms(); + static const int kTansformsFieldNumber = 1; + ::apollo::common::config::Transform* mutable_tansforms(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::common::config::Transform >* + mutable_tansforms(); + const ::apollo::common::config::Transform& tansforms(int index) const; + ::apollo::common::config::Transform* add_tansforms(); + const ::google::protobuf::RepeatedPtrField< ::apollo::common::config::Transform >& + tansforms() const; + + // @@protoc_insertion_point(class_scope:apollo.common.config.Extrinsics) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::common::config::Transform > tansforms_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// Transform + +// bytes source_frame = 1; +inline void Transform::clear_source_frame() { + source_frame_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& Transform::source_frame() const { + // @@protoc_insertion_point(field_get:apollo.common.config.Transform.source_frame) + return source_frame_.GetNoArena(); +} +inline void Transform::set_source_frame(const ::std::string& value) { + + source_frame_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.common.config.Transform.source_frame) +} +#if LANG_CXX11 +inline void Transform::set_source_frame(::std::string&& value) { + + source_frame_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.common.config.Transform.source_frame) +} +#endif +inline void Transform::set_source_frame(const char* value) { + GOOGLE_DCHECK(value != NULL); + + source_frame_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.common.config.Transform.source_frame) +} +inline void Transform::set_source_frame(const void* value, size_t size) { + + source_frame_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.common.config.Transform.source_frame) +} +inline ::std::string* Transform::mutable_source_frame() { + + // @@protoc_insertion_point(field_mutable:apollo.common.config.Transform.source_frame) + return source_frame_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* Transform::release_source_frame() { + // @@protoc_insertion_point(field_release:apollo.common.config.Transform.source_frame) + + return source_frame_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void Transform::set_allocated_source_frame(::std::string* source_frame) { + if (source_frame != NULL) { + + } else { + + } + source_frame_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), source_frame); + // @@protoc_insertion_point(field_set_allocated:apollo.common.config.Transform.source_frame) +} + +// bytes target_frame = 2; +inline void Transform::clear_target_frame() { + target_frame_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& Transform::target_frame() const { + // @@protoc_insertion_point(field_get:apollo.common.config.Transform.target_frame) + return target_frame_.GetNoArena(); +} +inline void Transform::set_target_frame(const ::std::string& value) { + + target_frame_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.common.config.Transform.target_frame) +} +#if LANG_CXX11 +inline void Transform::set_target_frame(::std::string&& value) { + + target_frame_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.common.config.Transform.target_frame) +} +#endif +inline void Transform::set_target_frame(const char* value) { + GOOGLE_DCHECK(value != NULL); + + target_frame_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.common.config.Transform.target_frame) +} +inline void Transform::set_target_frame(const void* value, size_t size) { + + target_frame_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.common.config.Transform.target_frame) +} +inline ::std::string* Transform::mutable_target_frame() { + + // @@protoc_insertion_point(field_mutable:apollo.common.config.Transform.target_frame) + return target_frame_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* Transform::release_target_frame() { + // @@protoc_insertion_point(field_release:apollo.common.config.Transform.target_frame) + + return target_frame_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void Transform::set_allocated_target_frame(::std::string* target_frame) { + if (target_frame != NULL) { + + } else { + + } + target_frame_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), target_frame); + // @@protoc_insertion_point(field_set_allocated:apollo.common.config.Transform.target_frame) +} + +// .apollo.common.Point3D translation = 3; +inline bool Transform::has_translation() const { + return this != internal_default_instance() && translation_ != NULL; +} +inline const ::apollo::common::Point3D& Transform::_internal_translation() const { + return *translation_; +} +inline const ::apollo::common::Point3D& Transform::translation() const { + const ::apollo::common::Point3D* p = translation_; + // @@protoc_insertion_point(field_get:apollo.common.config.Transform.translation) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Point3D_default_instance_); +} +inline ::apollo::common::Point3D* Transform::release_translation() { + // @@protoc_insertion_point(field_release:apollo.common.config.Transform.translation) + + ::apollo::common::Point3D* temp = translation_; + translation_ = NULL; + return temp; +} +inline ::apollo::common::Point3D* Transform::mutable_translation() { + + if (translation_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Point3D>(GetArenaNoVirtual()); + translation_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.common.config.Transform.translation) + return translation_; +} +inline void Transform::set_allocated_translation(::apollo::common::Point3D* translation) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(translation_); + } + if (translation) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + translation = ::google::protobuf::internal::GetOwnedMessage( + message_arena, translation, submessage_arena); + } + + } else { + + } + translation_ = translation; + // @@protoc_insertion_point(field_set_allocated:apollo.common.config.Transform.translation) +} + +// .apollo.common.Quaternion rotation = 4; +inline bool Transform::has_rotation() const { + return this != internal_default_instance() && rotation_ != NULL; +} +inline const ::apollo::common::Quaternion& Transform::_internal_rotation() const { + return *rotation_; +} +inline const ::apollo::common::Quaternion& Transform::rotation() const { + const ::apollo::common::Quaternion* p = rotation_; + // @@protoc_insertion_point(field_get:apollo.common.config.Transform.rotation) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Quaternion_default_instance_); +} +inline ::apollo::common::Quaternion* Transform::release_rotation() { + // @@protoc_insertion_point(field_release:apollo.common.config.Transform.rotation) + + ::apollo::common::Quaternion* temp = rotation_; + rotation_ = NULL; + return temp; +} +inline ::apollo::common::Quaternion* Transform::mutable_rotation() { + + if (rotation_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Quaternion>(GetArenaNoVirtual()); + rotation_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.common.config.Transform.rotation) + return rotation_; +} +inline void Transform::set_allocated_rotation(::apollo::common::Quaternion* rotation) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(rotation_); + } + if (rotation) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + rotation = ::google::protobuf::internal::GetOwnedMessage( + message_arena, rotation, submessage_arena); + } + + } else { + + } + rotation_ = rotation; + // @@protoc_insertion_point(field_set_allocated:apollo.common.config.Transform.rotation) +} + +// ------------------------------------------------------------------- + +// Extrinsics + +// repeated .apollo.common.config.Transform tansforms = 1; +inline int Extrinsics::tansforms_size() const { + return tansforms_.size(); +} +inline void Extrinsics::clear_tansforms() { + tansforms_.Clear(); +} +inline ::apollo::common::config::Transform* Extrinsics::mutable_tansforms(int index) { + // @@protoc_insertion_point(field_mutable:apollo.common.config.Extrinsics.tansforms) + return tansforms_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::common::config::Transform >* +Extrinsics::mutable_tansforms() { + // @@protoc_insertion_point(field_mutable_list:apollo.common.config.Extrinsics.tansforms) + return &tansforms_; +} +inline const ::apollo::common::config::Transform& Extrinsics::tansforms(int index) const { + // @@protoc_insertion_point(field_get:apollo.common.config.Extrinsics.tansforms) + return tansforms_.Get(index); +} +inline ::apollo::common::config::Transform* Extrinsics::add_tansforms() { + // @@protoc_insertion_point(field_add:apollo.common.config.Extrinsics.tansforms) + return tansforms_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::common::config::Transform >& +Extrinsics::tansforms() const { + // @@protoc_insertion_point(field_list:apollo.common.config.Extrinsics.tansforms) + return tansforms_; +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace config +} // namespace common +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/common/error_code.pb.cc b/apollo_msgs/include/apollo_msgs/proto/common/error_code.pb.cc new file mode 100644 index 0000000..5b8bb54 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/error_code.pb.cc @@ -0,0 +1,441 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/error_code.proto + +#include "apollo_msgs/proto/common/error_code.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace apollo { +namespace common { +class StatusPbDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _StatusPb_default_instance_; +} // namespace common +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto { +static void InitDefaultsStatusPb() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::_StatusPb_default_instance_; + new (ptr) ::apollo::common::StatusPb(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::StatusPb::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_StatusPb = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsStatusPb}, {}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_StatusPb.base); +} + +::google::protobuf::Metadata file_level_metadata[1]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::StatusPb, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::StatusPb, error_code_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::StatusPb, msg_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::common::StatusPb)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::common::_StatusPb_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/common/error_code.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 1); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n)apollo_msgs/proto/common/error_code.pr" + "oto\022\rapollo.common\"E\n\010StatusPb\022,\n\nerror_" + "code\030\001 \001(\0162\030.apollo.common.ErrorCode\022\013\n\003" + "msg\030\002 \001(\t*\265\002\n\tErrorCode\022\006\n\002OK\020\000\022\022\n\rCONTR" + "OL_ERROR\020\350\007\022\027\n\022CONTROL_INIT_ERROR\020\351\007\022\032\n\025" + "CONTROL_COMPUTE_ERROR\020\352\007\022\021\n\014CANBUS_ERROR" + "\020\320\017\022\032\n\025CAN_CLIENT_ERROR_BASE\020\264\020\022(\n#CAN_C" + "LIENT_ERROR_OPEN_DEVICE_FAILED\020\265\020\022\037\n\032CAN" + "_CLIENT_ERROR_FRAME_NUM\020\266\020\022!\n\034CAN_CLIENT" + "_ERROR_SEND_FAILED\020\267\020\022!\n\034CAN_CLIENT_ERRO" + "R_RECV_FAILED\020\270\020\022\027\n\022LOCALIZATION_ERROR\020\270" + "\027b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 449); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/common/error_code.proto", &protobuf_RegisterTypes); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto +namespace apollo { +namespace common { +const ::google::protobuf::EnumDescriptor* ErrorCode_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto::file_level_enum_descriptors[0]; +} +bool ErrorCode_IsValid(int value) { + switch (value) { + case 0: + case 1000: + case 1001: + case 1002: + case 2000: + case 2100: + case 2101: + case 2102: + case 2103: + case 2104: + case 3000: + return true; + default: + return false; + } +} + + +// =================================================================== + +void StatusPb::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int StatusPb::kErrorCodeFieldNumber; +const int StatusPb::kMsgFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +StatusPb::StatusPb() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto::scc_info_StatusPb.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.StatusPb) +} +StatusPb::StatusPb(const StatusPb& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + msg_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.msg().size() > 0) { + msg_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.msg_); + } + error_code_ = from.error_code_; + // @@protoc_insertion_point(copy_constructor:apollo.common.StatusPb) +} + +void StatusPb::SharedCtor() { + msg_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + error_code_ = 0; +} + +StatusPb::~StatusPb() { + // @@protoc_insertion_point(destructor:apollo.common.StatusPb) + SharedDtor(); +} + +void StatusPb::SharedDtor() { + msg_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + +void StatusPb::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* StatusPb::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const StatusPb& StatusPb::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto::scc_info_StatusPb.base); + return *internal_default_instance(); +} + + +void StatusPb::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.StatusPb) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + msg_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + error_code_ = 0; + _internal_metadata_.Clear(); +} + +bool StatusPb::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.StatusPb) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.ErrorCode error_code = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_error_code(static_cast< ::apollo::common::ErrorCode >(value)); + } else { + goto handle_unusual; + } + break; + } + + // string msg = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_msg())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->msg().data(), static_cast(this->msg().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.common.StatusPb.msg")); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.StatusPb) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.StatusPb) + return false; +#undef DO_ +} + +void StatusPb::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.StatusPb) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.ErrorCode error_code = 1; + if (this->error_code() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->error_code(), output); + } + + // string msg = 2; + if (this->msg().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->msg().data(), static_cast(this->msg().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.common.StatusPb.msg"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 2, this->msg(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.StatusPb) +} + +::google::protobuf::uint8* StatusPb::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.StatusPb) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.ErrorCode error_code = 1; + if (this->error_code() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->error_code(), target); + } + + // string msg = 2; + if (this->msg().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->msg().data(), static_cast(this->msg().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.common.StatusPb.msg"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 2, this->msg(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.StatusPb) + return target; +} + +size_t StatusPb::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.StatusPb) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // string msg = 2; + if (this->msg().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->msg()); + } + + // .apollo.common.ErrorCode error_code = 1; + if (this->error_code() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->error_code()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void StatusPb::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.StatusPb) + GOOGLE_DCHECK_NE(&from, this); + const StatusPb* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.StatusPb) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.StatusPb) + MergeFrom(*source); + } +} + +void StatusPb::MergeFrom(const StatusPb& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.StatusPb) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.msg().size() > 0) { + + msg_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.msg_); + } + if (from.error_code() != 0) { + set_error_code(from.error_code()); + } +} + +void StatusPb::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.StatusPb) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void StatusPb::CopyFrom(const StatusPb& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.StatusPb) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool StatusPb::IsInitialized() const { + return true; +} + +void StatusPb::Swap(StatusPb* other) { + if (other == this) return; + InternalSwap(other); +} +void StatusPb::InternalSwap(StatusPb* other) { + using std::swap; + msg_.Swap(&other->msg_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(error_code_, other->error_code_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata StatusPb::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::StatusPb* Arena::CreateMaybeMessage< ::apollo::common::StatusPb >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::StatusPb >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/common/error_code.pb.h b/apollo_msgs/include/apollo_msgs/proto/common/error_code.pb.h new file mode 100644 index 0000000..35171d3 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/error_code.pb.h @@ -0,0 +1,313 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/error_code.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[1]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto +namespace apollo { +namespace common { +class StatusPb; +class StatusPbDefaultTypeInternal; +extern StatusPbDefaultTypeInternal _StatusPb_default_instance_; +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::common::StatusPb* Arena::CreateMaybeMessage<::apollo::common::StatusPb>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace common { + +enum ErrorCode { + OK = 0, + CONTROL_ERROR = 1000, + CONTROL_INIT_ERROR = 1001, + CONTROL_COMPUTE_ERROR = 1002, + CANBUS_ERROR = 2000, + CAN_CLIENT_ERROR_BASE = 2100, + CAN_CLIENT_ERROR_OPEN_DEVICE_FAILED = 2101, + CAN_CLIENT_ERROR_FRAME_NUM = 2102, + CAN_CLIENT_ERROR_SEND_FAILED = 2103, + CAN_CLIENT_ERROR_RECV_FAILED = 2104, + LOCALIZATION_ERROR = 3000, + ErrorCode_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + ErrorCode_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool ErrorCode_IsValid(int value); +const ErrorCode ErrorCode_MIN = OK; +const ErrorCode ErrorCode_MAX = LOCALIZATION_ERROR; +const int ErrorCode_ARRAYSIZE = ErrorCode_MAX + 1; + +const ::google::protobuf::EnumDescriptor* ErrorCode_descriptor(); +inline const ::std::string& ErrorCode_Name(ErrorCode value) { + return ::google::protobuf::internal::NameOfEnum( + ErrorCode_descriptor(), value); +} +inline bool ErrorCode_Parse( + const ::std::string& name, ErrorCode* value) { + return ::google::protobuf::internal::ParseNamedEnum( + ErrorCode_descriptor(), name, value); +} +// =================================================================== + +class StatusPb : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.StatusPb) */ { + public: + StatusPb(); + virtual ~StatusPb(); + + StatusPb(const StatusPb& from); + + inline StatusPb& operator=(const StatusPb& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + StatusPb(StatusPb&& from) noexcept + : StatusPb() { + *this = ::std::move(from); + } + + inline StatusPb& operator=(StatusPb&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const StatusPb& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const StatusPb* internal_default_instance() { + return reinterpret_cast( + &_StatusPb_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(StatusPb* other); + friend void swap(StatusPb& a, StatusPb& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline StatusPb* New() const final { + return CreateMaybeMessage(NULL); + } + + StatusPb* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const StatusPb& from); + void MergeFrom(const StatusPb& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(StatusPb* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // string msg = 2; + void clear_msg(); + static const int kMsgFieldNumber = 2; + const ::std::string& msg() const; + void set_msg(const ::std::string& value); + #if LANG_CXX11 + void set_msg(::std::string&& value); + #endif + void set_msg(const char* value); + void set_msg(const char* value, size_t size); + ::std::string* mutable_msg(); + ::std::string* release_msg(); + void set_allocated_msg(::std::string* msg); + + // .apollo.common.ErrorCode error_code = 1; + void clear_error_code(); + static const int kErrorCodeFieldNumber = 1; + ::apollo::common::ErrorCode error_code() const; + void set_error_code(::apollo::common::ErrorCode value); + + // @@protoc_insertion_point(class_scope:apollo.common.StatusPb) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr msg_; + int error_code_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// StatusPb + +// .apollo.common.ErrorCode error_code = 1; +inline void StatusPb::clear_error_code() { + error_code_ = 0; +} +inline ::apollo::common::ErrorCode StatusPb::error_code() const { + // @@protoc_insertion_point(field_get:apollo.common.StatusPb.error_code) + return static_cast< ::apollo::common::ErrorCode >(error_code_); +} +inline void StatusPb::set_error_code(::apollo::common::ErrorCode value) { + + error_code_ = value; + // @@protoc_insertion_point(field_set:apollo.common.StatusPb.error_code) +} + +// string msg = 2; +inline void StatusPb::clear_msg() { + msg_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& StatusPb::msg() const { + // @@protoc_insertion_point(field_get:apollo.common.StatusPb.msg) + return msg_.GetNoArena(); +} +inline void StatusPb::set_msg(const ::std::string& value) { + + msg_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.common.StatusPb.msg) +} +#if LANG_CXX11 +inline void StatusPb::set_msg(::std::string&& value) { + + msg_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.common.StatusPb.msg) +} +#endif +inline void StatusPb::set_msg(const char* value) { + GOOGLE_DCHECK(value != NULL); + + msg_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.common.StatusPb.msg) +} +inline void StatusPb::set_msg(const char* value, size_t size) { + + msg_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.common.StatusPb.msg) +} +inline ::std::string* StatusPb::mutable_msg() { + + // @@protoc_insertion_point(field_mutable:apollo.common.StatusPb.msg) + return msg_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* StatusPb::release_msg() { + // @@protoc_insertion_point(field_release:apollo.common.StatusPb.msg) + + return msg_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void StatusPb::set_allocated_msg(::std::string* msg) { + if (msg != NULL) { + + } else { + + } + msg_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), msg); + // @@protoc_insertion_point(field_set_allocated:apollo.common.StatusPb.msg) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) + +} // namespace common +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::common::ErrorCode> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::common::ErrorCode>() { + return ::apollo::common::ErrorCode_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/common/geometry.pb.cc b/apollo_msgs/include/apollo_msgs/proto/common/geometry.pb.cc new file mode 100644 index 0000000..7b9a362 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/geometry.pb.cc @@ -0,0 +1,1738 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/geometry.proto + +#include "apollo_msgs/proto/common/geometry.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace apollo { +namespace common { +class PointENUDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _PointENU_default_instance_; +class PointLLHDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _PointLLH_default_instance_; +class Point2DDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Point2D_default_instance_; +class Point3DDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Point3D_default_instance_; +class QuaternionDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Quaternion_default_instance_; +} // namespace common +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto { +static void InitDefaultsPointENU() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::_PointENU_default_instance_; + new (ptr) ::apollo::common::PointENU(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::PointENU::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_PointENU = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsPointENU}, {}}; + +static void InitDefaultsPointLLH() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::_PointLLH_default_instance_; + new (ptr) ::apollo::common::PointLLH(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::PointLLH::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_PointLLH = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsPointLLH}, {}}; + +static void InitDefaultsPoint2D() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::_Point2D_default_instance_; + new (ptr) ::apollo::common::Point2D(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::Point2D::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Point2D = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsPoint2D}, {}}; + +static void InitDefaultsPoint3D() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::_Point3D_default_instance_; + new (ptr) ::apollo::common::Point3D(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::Point3D::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Point3D = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsPoint3D}, {}}; + +static void InitDefaultsQuaternion() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::_Quaternion_default_instance_; + new (ptr) ::apollo::common::Quaternion(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::Quaternion::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Quaternion = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsQuaternion}, {}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_PointENU.base); + ::google::protobuf::internal::InitSCC(&scc_info_PointLLH.base); + ::google::protobuf::internal::InitSCC(&scc_info_Point2D.base); + ::google::protobuf::internal::InitSCC(&scc_info_Point3D.base); + ::google::protobuf::internal::InitSCC(&scc_info_Quaternion.base); +} + +::google::protobuf::Metadata file_level_metadata[5]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::PointENU, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::PointENU, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::PointENU, y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::PointENU, z_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::PointLLH, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::PointLLH, lon_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::PointLLH, lat_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::PointLLH, height_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Point2D, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Point2D, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Point2D, y_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Point3D, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Point3D, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Point3D, y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Point3D, z_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Quaternion, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Quaternion, qx_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Quaternion, qy_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Quaternion, qz_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Quaternion, qw_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::common::PointENU)}, + { 8, -1, sizeof(::apollo::common::PointLLH)}, + { 16, -1, sizeof(::apollo::common::Point2D)}, + { 23, -1, sizeof(::apollo::common::Point3D)}, + { 31, -1, sizeof(::apollo::common::Quaternion)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::common::_PointENU_default_instance_), + reinterpret_cast(&::apollo::common::_PointLLH_default_instance_), + reinterpret_cast(&::apollo::common::_Point2D_default_instance_), + reinterpret_cast(&::apollo::common::_Point3D_default_instance_), + reinterpret_cast(&::apollo::common::_Quaternion_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/common/geometry.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 5); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n\'apollo_msgs/proto/common/geometry.prot" + "o\022\rapollo.common\"+\n\010PointENU\022\t\n\001x\030\001 \001(\001\022" + "\t\n\001y\030\002 \001(\001\022\t\n\001z\030\003 \001(\001\"4\n\010PointLLH\022\013\n\003lon" + "\030\001 \001(\001\022\013\n\003lat\030\002 \001(\001\022\016\n\006height\030\003 \001(\001\"\037\n\007P" + "oint2D\022\t\n\001x\030\001 \001(\001\022\t\n\001y\030\002 \001(\001\"*\n\007Point3D\022" + "\t\n\001x\030\001 \001(\001\022\t\n\001y\030\002 \001(\001\022\t\n\001z\030\003 \001(\001\"<\n\nQuat" + "ernion\022\n\n\002qx\030\001 \001(\001\022\n\n\002qy\030\002 \001(\001\022\n\n\002qz\030\003 \001" + "(\001\022\n\n\002qw\030\004 \001(\001b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 302); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/common/geometry.proto", &protobuf_RegisterTypes); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto +namespace apollo { +namespace common { + +// =================================================================== + +void PointENU::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PointENU::kXFieldNumber; +const int PointENU::kYFieldNumber; +const int PointENU::kZFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PointENU::PointENU() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_PointENU.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.PointENU) +} +PointENU::PointENU(const PointENU& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&x_, &from.x_, + static_cast(reinterpret_cast(&z_) - + reinterpret_cast(&x_)) + sizeof(z_)); + // @@protoc_insertion_point(copy_constructor:apollo.common.PointENU) +} + +void PointENU::SharedCtor() { + ::memset(&x_, 0, static_cast( + reinterpret_cast(&z_) - + reinterpret_cast(&x_)) + sizeof(z_)); +} + +PointENU::~PointENU() { + // @@protoc_insertion_point(destructor:apollo.common.PointENU) + SharedDtor(); +} + +void PointENU::SharedDtor() { +} + +void PointENU::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* PointENU::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const PointENU& PointENU::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_PointENU.base); + return *internal_default_instance(); +} + + +void PointENU::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.PointENU) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&x_, 0, static_cast( + reinterpret_cast(&z_) - + reinterpret_cast(&x_)) + sizeof(z_)); + _internal_metadata_.Clear(); +} + +bool PointENU::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.PointENU) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double x = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &x_))); + } else { + goto handle_unusual; + } + break; + } + + // double y = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &y_))); + } else { + goto handle_unusual; + } + break; + } + + // double z = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &z_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.PointENU) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.PointENU) + return false; +#undef DO_ +} + +void PointENU::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.PointENU) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output); + } + + // double y = 2; + if (this->y() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output); + } + + // double z = 3; + if (this->z() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->z(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.PointENU) +} + +::google::protobuf::uint8* PointENU::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.PointENU) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target); + } + + // double y = 2; + if (this->y() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target); + } + + // double z = 3; + if (this->z() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->z(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.PointENU) + return target; +} + +size_t PointENU::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.PointENU) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double x = 1; + if (this->x() != 0) { + total_size += 1 + 8; + } + + // double y = 2; + if (this->y() != 0) { + total_size += 1 + 8; + } + + // double z = 3; + if (this->z() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void PointENU::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.PointENU) + GOOGLE_DCHECK_NE(&from, this); + const PointENU* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.PointENU) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.PointENU) + MergeFrom(*source); + } +} + +void PointENU::MergeFrom(const PointENU& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.PointENU) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.x() != 0) { + set_x(from.x()); + } + if (from.y() != 0) { + set_y(from.y()); + } + if (from.z() != 0) { + set_z(from.z()); + } +} + +void PointENU::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.PointENU) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PointENU::CopyFrom(const PointENU& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.PointENU) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PointENU::IsInitialized() const { + return true; +} + +void PointENU::Swap(PointENU* other) { + if (other == this) return; + InternalSwap(other); +} +void PointENU::InternalSwap(PointENU* other) { + using std::swap; + swap(x_, other->x_); + swap(y_, other->y_); + swap(z_, other->z_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata PointENU::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void PointLLH::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PointLLH::kLonFieldNumber; +const int PointLLH::kLatFieldNumber; +const int PointLLH::kHeightFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PointLLH::PointLLH() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_PointLLH.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.PointLLH) +} +PointLLH::PointLLH(const PointLLH& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&lon_, &from.lon_, + static_cast(reinterpret_cast(&height_) - + reinterpret_cast(&lon_)) + sizeof(height_)); + // @@protoc_insertion_point(copy_constructor:apollo.common.PointLLH) +} + +void PointLLH::SharedCtor() { + ::memset(&lon_, 0, static_cast( + reinterpret_cast(&height_) - + reinterpret_cast(&lon_)) + sizeof(height_)); +} + +PointLLH::~PointLLH() { + // @@protoc_insertion_point(destructor:apollo.common.PointLLH) + SharedDtor(); +} + +void PointLLH::SharedDtor() { +} + +void PointLLH::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* PointLLH::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const PointLLH& PointLLH::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_PointLLH.base); + return *internal_default_instance(); +} + + +void PointLLH::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.PointLLH) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&lon_, 0, static_cast( + reinterpret_cast(&height_) - + reinterpret_cast(&lon_)) + sizeof(height_)); + _internal_metadata_.Clear(); +} + +bool PointLLH::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.PointLLH) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double lon = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lon_))); + } else { + goto handle_unusual; + } + break; + } + + // double lat = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lat_))); + } else { + goto handle_unusual; + } + break; + } + + // double height = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &height_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.PointLLH) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.PointLLH) + return false; +#undef DO_ +} + +void PointLLH::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.PointLLH) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double lon = 1; + if (this->lon() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->lon(), output); + } + + // double lat = 2; + if (this->lat() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->lat(), output); + } + + // double height = 3; + if (this->height() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->height(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.PointLLH) +} + +::google::protobuf::uint8* PointLLH::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.PointLLH) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double lon = 1; + if (this->lon() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->lon(), target); + } + + // double lat = 2; + if (this->lat() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->lat(), target); + } + + // double height = 3; + if (this->height() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->height(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.PointLLH) + return target; +} + +size_t PointLLH::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.PointLLH) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double lon = 1; + if (this->lon() != 0) { + total_size += 1 + 8; + } + + // double lat = 2; + if (this->lat() != 0) { + total_size += 1 + 8; + } + + // double height = 3; + if (this->height() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void PointLLH::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.PointLLH) + GOOGLE_DCHECK_NE(&from, this); + const PointLLH* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.PointLLH) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.PointLLH) + MergeFrom(*source); + } +} + +void PointLLH::MergeFrom(const PointLLH& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.PointLLH) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.lon() != 0) { + set_lon(from.lon()); + } + if (from.lat() != 0) { + set_lat(from.lat()); + } + if (from.height() != 0) { + set_height(from.height()); + } +} + +void PointLLH::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.PointLLH) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PointLLH::CopyFrom(const PointLLH& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.PointLLH) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PointLLH::IsInitialized() const { + return true; +} + +void PointLLH::Swap(PointLLH* other) { + if (other == this) return; + InternalSwap(other); +} +void PointLLH::InternalSwap(PointLLH* other) { + using std::swap; + swap(lon_, other->lon_); + swap(lat_, other->lat_); + swap(height_, other->height_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata PointLLH::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Point2D::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Point2D::kXFieldNumber; +const int Point2D::kYFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Point2D::Point2D() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_Point2D.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.Point2D) +} +Point2D::Point2D(const Point2D& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&x_, &from.x_, + static_cast(reinterpret_cast(&y_) - + reinterpret_cast(&x_)) + sizeof(y_)); + // @@protoc_insertion_point(copy_constructor:apollo.common.Point2D) +} + +void Point2D::SharedCtor() { + ::memset(&x_, 0, static_cast( + reinterpret_cast(&y_) - + reinterpret_cast(&x_)) + sizeof(y_)); +} + +Point2D::~Point2D() { + // @@protoc_insertion_point(destructor:apollo.common.Point2D) + SharedDtor(); +} + +void Point2D::SharedDtor() { +} + +void Point2D::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Point2D::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Point2D& Point2D::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_Point2D.base); + return *internal_default_instance(); +} + + +void Point2D::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.Point2D) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&x_, 0, static_cast( + reinterpret_cast(&y_) - + reinterpret_cast(&x_)) + sizeof(y_)); + _internal_metadata_.Clear(); +} + +bool Point2D::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.Point2D) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double x = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &x_))); + } else { + goto handle_unusual; + } + break; + } + + // double y = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &y_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.Point2D) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.Point2D) + return false; +#undef DO_ +} + +void Point2D::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.Point2D) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output); + } + + // double y = 2; + if (this->y() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.Point2D) +} + +::google::protobuf::uint8* Point2D::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.Point2D) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target); + } + + // double y = 2; + if (this->y() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.Point2D) + return target; +} + +size_t Point2D::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.Point2D) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double x = 1; + if (this->x() != 0) { + total_size += 1 + 8; + } + + // double y = 2; + if (this->y() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Point2D::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.Point2D) + GOOGLE_DCHECK_NE(&from, this); + const Point2D* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.Point2D) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.Point2D) + MergeFrom(*source); + } +} + +void Point2D::MergeFrom(const Point2D& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.Point2D) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.x() != 0) { + set_x(from.x()); + } + if (from.y() != 0) { + set_y(from.y()); + } +} + +void Point2D::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.Point2D) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Point2D::CopyFrom(const Point2D& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.Point2D) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Point2D::IsInitialized() const { + return true; +} + +void Point2D::Swap(Point2D* other) { + if (other == this) return; + InternalSwap(other); +} +void Point2D::InternalSwap(Point2D* other) { + using std::swap; + swap(x_, other->x_); + swap(y_, other->y_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Point2D::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Point3D::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Point3D::kXFieldNumber; +const int Point3D::kYFieldNumber; +const int Point3D::kZFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Point3D::Point3D() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_Point3D.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.Point3D) +} +Point3D::Point3D(const Point3D& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&x_, &from.x_, + static_cast(reinterpret_cast(&z_) - + reinterpret_cast(&x_)) + sizeof(z_)); + // @@protoc_insertion_point(copy_constructor:apollo.common.Point3D) +} + +void Point3D::SharedCtor() { + ::memset(&x_, 0, static_cast( + reinterpret_cast(&z_) - + reinterpret_cast(&x_)) + sizeof(z_)); +} + +Point3D::~Point3D() { + // @@protoc_insertion_point(destructor:apollo.common.Point3D) + SharedDtor(); +} + +void Point3D::SharedDtor() { +} + +void Point3D::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Point3D::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Point3D& Point3D::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_Point3D.base); + return *internal_default_instance(); +} + + +void Point3D::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.Point3D) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&x_, 0, static_cast( + reinterpret_cast(&z_) - + reinterpret_cast(&x_)) + sizeof(z_)); + _internal_metadata_.Clear(); +} + +bool Point3D::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.Point3D) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double x = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &x_))); + } else { + goto handle_unusual; + } + break; + } + + // double y = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &y_))); + } else { + goto handle_unusual; + } + break; + } + + // double z = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &z_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.Point3D) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.Point3D) + return false; +#undef DO_ +} + +void Point3D::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.Point3D) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output); + } + + // double y = 2; + if (this->y() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output); + } + + // double z = 3; + if (this->z() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->z(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.Point3D) +} + +::google::protobuf::uint8* Point3D::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.Point3D) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target); + } + + // double y = 2; + if (this->y() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target); + } + + // double z = 3; + if (this->z() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->z(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.Point3D) + return target; +} + +size_t Point3D::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.Point3D) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double x = 1; + if (this->x() != 0) { + total_size += 1 + 8; + } + + // double y = 2; + if (this->y() != 0) { + total_size += 1 + 8; + } + + // double z = 3; + if (this->z() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Point3D::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.Point3D) + GOOGLE_DCHECK_NE(&from, this); + const Point3D* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.Point3D) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.Point3D) + MergeFrom(*source); + } +} + +void Point3D::MergeFrom(const Point3D& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.Point3D) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.x() != 0) { + set_x(from.x()); + } + if (from.y() != 0) { + set_y(from.y()); + } + if (from.z() != 0) { + set_z(from.z()); + } +} + +void Point3D::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.Point3D) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Point3D::CopyFrom(const Point3D& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.Point3D) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Point3D::IsInitialized() const { + return true; +} + +void Point3D::Swap(Point3D* other) { + if (other == this) return; + InternalSwap(other); +} +void Point3D::InternalSwap(Point3D* other) { + using std::swap; + swap(x_, other->x_); + swap(y_, other->y_); + swap(z_, other->z_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Point3D::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Quaternion::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Quaternion::kQxFieldNumber; +const int Quaternion::kQyFieldNumber; +const int Quaternion::kQzFieldNumber; +const int Quaternion::kQwFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Quaternion::Quaternion() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_Quaternion.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.Quaternion) +} +Quaternion::Quaternion(const Quaternion& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&qx_, &from.qx_, + static_cast(reinterpret_cast(&qw_) - + reinterpret_cast(&qx_)) + sizeof(qw_)); + // @@protoc_insertion_point(copy_constructor:apollo.common.Quaternion) +} + +void Quaternion::SharedCtor() { + ::memset(&qx_, 0, static_cast( + reinterpret_cast(&qw_) - + reinterpret_cast(&qx_)) + sizeof(qw_)); +} + +Quaternion::~Quaternion() { + // @@protoc_insertion_point(destructor:apollo.common.Quaternion) + SharedDtor(); +} + +void Quaternion::SharedDtor() { +} + +void Quaternion::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Quaternion::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Quaternion& Quaternion::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_Quaternion.base); + return *internal_default_instance(); +} + + +void Quaternion::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.Quaternion) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&qx_, 0, static_cast( + reinterpret_cast(&qw_) - + reinterpret_cast(&qx_)) + sizeof(qw_)); + _internal_metadata_.Clear(); +} + +bool Quaternion::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.Quaternion) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double qx = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &qx_))); + } else { + goto handle_unusual; + } + break; + } + + // double qy = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &qy_))); + } else { + goto handle_unusual; + } + break; + } + + // double qz = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &qz_))); + } else { + goto handle_unusual; + } + break; + } + + // double qw = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &qw_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.Quaternion) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.Quaternion) + return false; +#undef DO_ +} + +void Quaternion::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.Quaternion) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double qx = 1; + if (this->qx() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->qx(), output); + } + + // double qy = 2; + if (this->qy() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->qy(), output); + } + + // double qz = 3; + if (this->qz() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->qz(), output); + } + + // double qw = 4; + if (this->qw() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->qw(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.Quaternion) +} + +::google::protobuf::uint8* Quaternion::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.Quaternion) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double qx = 1; + if (this->qx() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->qx(), target); + } + + // double qy = 2; + if (this->qy() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->qy(), target); + } + + // double qz = 3; + if (this->qz() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->qz(), target); + } + + // double qw = 4; + if (this->qw() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->qw(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.Quaternion) + return target; +} + +size_t Quaternion::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.Quaternion) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double qx = 1; + if (this->qx() != 0) { + total_size += 1 + 8; + } + + // double qy = 2; + if (this->qy() != 0) { + total_size += 1 + 8; + } + + // double qz = 3; + if (this->qz() != 0) { + total_size += 1 + 8; + } + + // double qw = 4; + if (this->qw() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Quaternion::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.Quaternion) + GOOGLE_DCHECK_NE(&from, this); + const Quaternion* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.Quaternion) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.Quaternion) + MergeFrom(*source); + } +} + +void Quaternion::MergeFrom(const Quaternion& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.Quaternion) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.qx() != 0) { + set_qx(from.qx()); + } + if (from.qy() != 0) { + set_qy(from.qy()); + } + if (from.qz() != 0) { + set_qz(from.qz()); + } + if (from.qw() != 0) { + set_qw(from.qw()); + } +} + +void Quaternion::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.Quaternion) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Quaternion::CopyFrom(const Quaternion& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.Quaternion) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Quaternion::IsInitialized() const { + return true; +} + +void Quaternion::Swap(Quaternion* other) { + if (other == this) return; + InternalSwap(other); +} +void Quaternion::InternalSwap(Quaternion* other) { + using std::swap; + swap(qx_, other->qx_); + swap(qy_, other->qy_); + swap(qz_, other->qz_); + swap(qw_, other->qw_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Quaternion::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::PointENU* Arena::CreateMaybeMessage< ::apollo::common::PointENU >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::PointENU >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::PointLLH* Arena::CreateMaybeMessage< ::apollo::common::PointLLH >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::PointLLH >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::Point2D* Arena::CreateMaybeMessage< ::apollo::common::Point2D >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::Point2D >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::Point3D* Arena::CreateMaybeMessage< ::apollo::common::Point3D >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::Point3D >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::Quaternion* Arena::CreateMaybeMessage< ::apollo::common::Quaternion >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::Quaternion >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/common/geometry.pb.h b/apollo_msgs/include/apollo_msgs/proto/common/geometry.pb.h new file mode 100644 index 0000000..b16b5b1 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/geometry.pb.h @@ -0,0 +1,920 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/geometry.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[5]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto +namespace apollo { +namespace common { +class Point2D; +class Point2DDefaultTypeInternal; +extern Point2DDefaultTypeInternal _Point2D_default_instance_; +class Point3D; +class Point3DDefaultTypeInternal; +extern Point3DDefaultTypeInternal _Point3D_default_instance_; +class PointENU; +class PointENUDefaultTypeInternal; +extern PointENUDefaultTypeInternal _PointENU_default_instance_; +class PointLLH; +class PointLLHDefaultTypeInternal; +extern PointLLHDefaultTypeInternal _PointLLH_default_instance_; +class Quaternion; +class QuaternionDefaultTypeInternal; +extern QuaternionDefaultTypeInternal _Quaternion_default_instance_; +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::common::Point2D* Arena::CreateMaybeMessage<::apollo::common::Point2D>(Arena*); +template<> ::apollo::common::Point3D* Arena::CreateMaybeMessage<::apollo::common::Point3D>(Arena*); +template<> ::apollo::common::PointENU* Arena::CreateMaybeMessage<::apollo::common::PointENU>(Arena*); +template<> ::apollo::common::PointLLH* Arena::CreateMaybeMessage<::apollo::common::PointLLH>(Arena*); +template<> ::apollo::common::Quaternion* Arena::CreateMaybeMessage<::apollo::common::Quaternion>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace common { + +// =================================================================== + +class PointENU : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.PointENU) */ { + public: + PointENU(); + virtual ~PointENU(); + + PointENU(const PointENU& from); + + inline PointENU& operator=(const PointENU& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + PointENU(PointENU&& from) noexcept + : PointENU() { + *this = ::std::move(from); + } + + inline PointENU& operator=(PointENU&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const PointENU& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const PointENU* internal_default_instance() { + return reinterpret_cast( + &_PointENU_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(PointENU* other); + friend void swap(PointENU& a, PointENU& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline PointENU* New() const final { + return CreateMaybeMessage(NULL); + } + + PointENU* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const PointENU& from); + void MergeFrom(const PointENU& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(PointENU* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double x = 1; + void clear_x(); + static const int kXFieldNumber = 1; + double x() const; + void set_x(double value); + + // double y = 2; + void clear_y(); + static const int kYFieldNumber = 2; + double y() const; + void set_y(double value); + + // double z = 3; + void clear_z(); + static const int kZFieldNumber = 3; + double z() const; + void set_z(double value); + + // @@protoc_insertion_point(class_scope:apollo.common.PointENU) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double x_; + double y_; + double z_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class PointLLH : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.PointLLH) */ { + public: + PointLLH(); + virtual ~PointLLH(); + + PointLLH(const PointLLH& from); + + inline PointLLH& operator=(const PointLLH& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + PointLLH(PointLLH&& from) noexcept + : PointLLH() { + *this = ::std::move(from); + } + + inline PointLLH& operator=(PointLLH&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const PointLLH& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const PointLLH* internal_default_instance() { + return reinterpret_cast( + &_PointLLH_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(PointLLH* other); + friend void swap(PointLLH& a, PointLLH& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline PointLLH* New() const final { + return CreateMaybeMessage(NULL); + } + + PointLLH* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const PointLLH& from); + void MergeFrom(const PointLLH& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(PointLLH* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double lon = 1; + void clear_lon(); + static const int kLonFieldNumber = 1; + double lon() const; + void set_lon(double value); + + // double lat = 2; + void clear_lat(); + static const int kLatFieldNumber = 2; + double lat() const; + void set_lat(double value); + + // double height = 3; + void clear_height(); + static const int kHeightFieldNumber = 3; + double height() const; + void set_height(double value); + + // @@protoc_insertion_point(class_scope:apollo.common.PointLLH) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double lon_; + double lat_; + double height_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Point2D : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.Point2D) */ { + public: + Point2D(); + virtual ~Point2D(); + + Point2D(const Point2D& from); + + inline Point2D& operator=(const Point2D& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Point2D(Point2D&& from) noexcept + : Point2D() { + *this = ::std::move(from); + } + + inline Point2D& operator=(Point2D&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Point2D& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Point2D* internal_default_instance() { + return reinterpret_cast( + &_Point2D_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + void Swap(Point2D* other); + friend void swap(Point2D& a, Point2D& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Point2D* New() const final { + return CreateMaybeMessage(NULL); + } + + Point2D* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Point2D& from); + void MergeFrom(const Point2D& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Point2D* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double x = 1; + void clear_x(); + static const int kXFieldNumber = 1; + double x() const; + void set_x(double value); + + // double y = 2; + void clear_y(); + static const int kYFieldNumber = 2; + double y() const; + void set_y(double value); + + // @@protoc_insertion_point(class_scope:apollo.common.Point2D) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double x_; + double y_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Point3D : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.Point3D) */ { + public: + Point3D(); + virtual ~Point3D(); + + Point3D(const Point3D& from); + + inline Point3D& operator=(const Point3D& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Point3D(Point3D&& from) noexcept + : Point3D() { + *this = ::std::move(from); + } + + inline Point3D& operator=(Point3D&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Point3D& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Point3D* internal_default_instance() { + return reinterpret_cast( + &_Point3D_default_instance_); + } + static constexpr int kIndexInFileMessages = + 3; + + void Swap(Point3D* other); + friend void swap(Point3D& a, Point3D& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Point3D* New() const final { + return CreateMaybeMessage(NULL); + } + + Point3D* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Point3D& from); + void MergeFrom(const Point3D& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Point3D* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double x = 1; + void clear_x(); + static const int kXFieldNumber = 1; + double x() const; + void set_x(double value); + + // double y = 2; + void clear_y(); + static const int kYFieldNumber = 2; + double y() const; + void set_y(double value); + + // double z = 3; + void clear_z(); + static const int kZFieldNumber = 3; + double z() const; + void set_z(double value); + + // @@protoc_insertion_point(class_scope:apollo.common.Point3D) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double x_; + double y_; + double z_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Quaternion : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.Quaternion) */ { + public: + Quaternion(); + virtual ~Quaternion(); + + Quaternion(const Quaternion& from); + + inline Quaternion& operator=(const Quaternion& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Quaternion(Quaternion&& from) noexcept + : Quaternion() { + *this = ::std::move(from); + } + + inline Quaternion& operator=(Quaternion&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Quaternion& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Quaternion* internal_default_instance() { + return reinterpret_cast( + &_Quaternion_default_instance_); + } + static constexpr int kIndexInFileMessages = + 4; + + void Swap(Quaternion* other); + friend void swap(Quaternion& a, Quaternion& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Quaternion* New() const final { + return CreateMaybeMessage(NULL); + } + + Quaternion* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Quaternion& from); + void MergeFrom(const Quaternion& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Quaternion* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double qx = 1; + void clear_qx(); + static const int kQxFieldNumber = 1; + double qx() const; + void set_qx(double value); + + // double qy = 2; + void clear_qy(); + static const int kQyFieldNumber = 2; + double qy() const; + void set_qy(double value); + + // double qz = 3; + void clear_qz(); + static const int kQzFieldNumber = 3; + double qz() const; + void set_qz(double value); + + // double qw = 4; + void clear_qw(); + static const int kQwFieldNumber = 4; + double qw() const; + void set_qw(double value); + + // @@protoc_insertion_point(class_scope:apollo.common.Quaternion) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double qx_; + double qy_; + double qz_; + double qw_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// PointENU + +// double x = 1; +inline void PointENU::clear_x() { + x_ = 0; +} +inline double PointENU::x() const { + // @@protoc_insertion_point(field_get:apollo.common.PointENU.x) + return x_; +} +inline void PointENU::set_x(double value) { + + x_ = value; + // @@protoc_insertion_point(field_set:apollo.common.PointENU.x) +} + +// double y = 2; +inline void PointENU::clear_y() { + y_ = 0; +} +inline double PointENU::y() const { + // @@protoc_insertion_point(field_get:apollo.common.PointENU.y) + return y_; +} +inline void PointENU::set_y(double value) { + + y_ = value; + // @@protoc_insertion_point(field_set:apollo.common.PointENU.y) +} + +// double z = 3; +inline void PointENU::clear_z() { + z_ = 0; +} +inline double PointENU::z() const { + // @@protoc_insertion_point(field_get:apollo.common.PointENU.z) + return z_; +} +inline void PointENU::set_z(double value) { + + z_ = value; + // @@protoc_insertion_point(field_set:apollo.common.PointENU.z) +} + +// ------------------------------------------------------------------- + +// PointLLH + +// double lon = 1; +inline void PointLLH::clear_lon() { + lon_ = 0; +} +inline double PointLLH::lon() const { + // @@protoc_insertion_point(field_get:apollo.common.PointLLH.lon) + return lon_; +} +inline void PointLLH::set_lon(double value) { + + lon_ = value; + // @@protoc_insertion_point(field_set:apollo.common.PointLLH.lon) +} + +// double lat = 2; +inline void PointLLH::clear_lat() { + lat_ = 0; +} +inline double PointLLH::lat() const { + // @@protoc_insertion_point(field_get:apollo.common.PointLLH.lat) + return lat_; +} +inline void PointLLH::set_lat(double value) { + + lat_ = value; + // @@protoc_insertion_point(field_set:apollo.common.PointLLH.lat) +} + +// double height = 3; +inline void PointLLH::clear_height() { + height_ = 0; +} +inline double PointLLH::height() const { + // @@protoc_insertion_point(field_get:apollo.common.PointLLH.height) + return height_; +} +inline void PointLLH::set_height(double value) { + + height_ = value; + // @@protoc_insertion_point(field_set:apollo.common.PointLLH.height) +} + +// ------------------------------------------------------------------- + +// Point2D + +// double x = 1; +inline void Point2D::clear_x() { + x_ = 0; +} +inline double Point2D::x() const { + // @@protoc_insertion_point(field_get:apollo.common.Point2D.x) + return x_; +} +inline void Point2D::set_x(double value) { + + x_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Point2D.x) +} + +// double y = 2; +inline void Point2D::clear_y() { + y_ = 0; +} +inline double Point2D::y() const { + // @@protoc_insertion_point(field_get:apollo.common.Point2D.y) + return y_; +} +inline void Point2D::set_y(double value) { + + y_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Point2D.y) +} + +// ------------------------------------------------------------------- + +// Point3D + +// double x = 1; +inline void Point3D::clear_x() { + x_ = 0; +} +inline double Point3D::x() const { + // @@protoc_insertion_point(field_get:apollo.common.Point3D.x) + return x_; +} +inline void Point3D::set_x(double value) { + + x_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Point3D.x) +} + +// double y = 2; +inline void Point3D::clear_y() { + y_ = 0; +} +inline double Point3D::y() const { + // @@protoc_insertion_point(field_get:apollo.common.Point3D.y) + return y_; +} +inline void Point3D::set_y(double value) { + + y_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Point3D.y) +} + +// double z = 3; +inline void Point3D::clear_z() { + z_ = 0; +} +inline double Point3D::z() const { + // @@protoc_insertion_point(field_get:apollo.common.Point3D.z) + return z_; +} +inline void Point3D::set_z(double value) { + + z_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Point3D.z) +} + +// ------------------------------------------------------------------- + +// Quaternion + +// double qx = 1; +inline void Quaternion::clear_qx() { + qx_ = 0; +} +inline double Quaternion::qx() const { + // @@protoc_insertion_point(field_get:apollo.common.Quaternion.qx) + return qx_; +} +inline void Quaternion::set_qx(double value) { + + qx_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Quaternion.qx) +} + +// double qy = 2; +inline void Quaternion::clear_qy() { + qy_ = 0; +} +inline double Quaternion::qy() const { + // @@protoc_insertion_point(field_get:apollo.common.Quaternion.qy) + return qy_; +} +inline void Quaternion::set_qy(double value) { + + qy_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Quaternion.qy) +} + +// double qz = 3; +inline void Quaternion::clear_qz() { + qz_ = 0; +} +inline double Quaternion::qz() const { + // @@protoc_insertion_point(field_get:apollo.common.Quaternion.qz) + return qz_; +} +inline void Quaternion::set_qz(double value) { + + qz_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Quaternion.qz) +} + +// double qw = 4; +inline void Quaternion::clear_qw() { + qw_ = 0; +} +inline double Quaternion::qw() const { + // @@protoc_insertion_point(field_get:apollo.common.Quaternion.qw) + return qw_; +} +inline void Quaternion::set_qw(double value) { + + qw_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Quaternion.qw) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace common +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/common/gnss_status.pb.cc b/apollo_msgs/include/apollo_msgs/proto/common/gnss_status.pb.cc new file mode 100644 index 0000000..f0f9de6 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/gnss_status.pb.cc @@ -0,0 +1,1300 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/gnss_status.proto + +#include "apollo_msgs/proto/common/gnss_status.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace apollo { +namespace common { +namespace gnss_status { +class StreamStatusDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _StreamStatus_default_instance_; +class InsStatusDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _InsStatus_default_instance_; +class GnssStatusDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _GnssStatus_default_instance_; +} // namespace gnss_status +} // namespace common +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto { +static void InitDefaultsStreamStatus() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::gnss_status::_StreamStatus_default_instance_; + new (ptr) ::apollo::common::gnss_status::StreamStatus(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::gnss_status::StreamStatus::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_StreamStatus = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsStreamStatus}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base,}}; + +static void InitDefaultsInsStatus() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::gnss_status::_InsStatus_default_instance_; + new (ptr) ::apollo::common::gnss_status::InsStatus(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::gnss_status::InsStatus::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_InsStatus = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsInsStatus}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base,}}; + +static void InitDefaultsGnssStatus() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::gnss_status::_GnssStatus_default_instance_; + new (ptr) ::apollo::common::gnss_status::GnssStatus(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::gnss_status::GnssStatus::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_GnssStatus = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsGnssStatus}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_StreamStatus.base); + ::google::protobuf::internal::InitSCC(&scc_info_InsStatus.base); + ::google::protobuf::internal::InitSCC(&scc_info_GnssStatus.base); +} + +::google::protobuf::Metadata file_level_metadata[3]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[2]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::StreamStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::StreamStatus, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::StreamStatus, ins_stream_type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::StreamStatus, rtk_stream_in_type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::StreamStatus, rtk_stream_out_type_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::InsStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::InsStatus, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::InsStatus, type_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::GnssStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::GnssStatus, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::GnssStatus, solution_completed_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::GnssStatus, solution_status_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::GnssStatus, position_type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::gnss_status::GnssStatus, num_sats_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::common::gnss_status::StreamStatus)}, + { 9, -1, sizeof(::apollo::common::gnss_status::InsStatus)}, + { 16, -1, sizeof(::apollo::common::gnss_status::GnssStatus)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::common::gnss_status::_StreamStatus_default_instance_), + reinterpret_cast(&::apollo::common::gnss_status::_InsStatus_default_instance_), + reinterpret_cast(&::apollo::common::gnss_status::_GnssStatus_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/common/gnss_status.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 3); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n*apollo_msgs/proto/common/gnss_status.p" + "roto\022\031apollo.common.gnss_status\032%apollo_" + "msgs/proto/common/header.proto\"\272\002\n\014Strea" + "mStatus\022%\n\006header\030\001 \001(\0132\025.apollo.common." + "Header\022E\n\017ins_stream_type\030\002 \001(\0162,.apollo" + ".common.gnss_status.StreamStatus.Type\022H\n" + "\022rtk_stream_in_type\030\003 \001(\0162,.apollo.commo" + "n.gnss_status.StreamStatus.Type\022I\n\023rtk_s" + "tream_out_type\030\004 \001(\0162,.apollo.common.gns" + "s_status.StreamStatus.Type\"\'\n\004Type\022\020\n\014DI" + "SCONNECTED\020\000\022\r\n\tCONNECTED\020\001\"\232\001\n\tInsStatu" + "s\022%\n\006header\030\001 \001(\0132\025.apollo.common.Header" + "\0227\n\004type\030\002 \001(\0162).apollo.common.gnss_stat" + "us.InsStatus.Type\"-\n\004Type\022\013\n\007INVALID\020\000\022\016" + "\n\nCONVERGING\020\001\022\010\n\004GOOD\020\002\"\221\001\n\nGnssStatus\022" + "%\n\006header\030\001 \001(\0132\025.apollo.common.Header\022\032" + "\n\022solution_completed\030\002 \001(\010\022\027\n\017solution_s" + "tatus\030\003 \001(\r\022\025\n\rposition_type\030\004 \001(\r\022\020\n\010nu" + "m_sats\030\005 \001(\005b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 740); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/common/gnss_status.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto +namespace apollo { +namespace common { +namespace gnss_status { +const ::google::protobuf::EnumDescriptor* StreamStatus_Type_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::file_level_enum_descriptors[0]; +} +bool StreamStatus_Type_IsValid(int value) { + switch (value) { + case 0: + case 1: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const StreamStatus_Type StreamStatus::DISCONNECTED; +const StreamStatus_Type StreamStatus::CONNECTED; +const StreamStatus_Type StreamStatus::Type_MIN; +const StreamStatus_Type StreamStatus::Type_MAX; +const int StreamStatus::Type_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* InsStatus_Type_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::file_level_enum_descriptors[1]; +} +bool InsStatus_Type_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const InsStatus_Type InsStatus::INVALID; +const InsStatus_Type InsStatus::CONVERGING; +const InsStatus_Type InsStatus::GOOD; +const InsStatus_Type InsStatus::Type_MIN; +const InsStatus_Type InsStatus::Type_MAX; +const int InsStatus::Type_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +// =================================================================== + +void StreamStatus::InitAsDefaultInstance() { + ::apollo::common::gnss_status::_StreamStatus_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); +} +void StreamStatus::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int StreamStatus::kHeaderFieldNumber; +const int StreamStatus::kInsStreamTypeFieldNumber; +const int StreamStatus::kRtkStreamInTypeFieldNumber; +const int StreamStatus::kRtkStreamOutTypeFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +StreamStatus::StreamStatus() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::scc_info_StreamStatus.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.gnss_status.StreamStatus) +} +StreamStatus::StreamStatus(const StreamStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + ::memcpy(&ins_stream_type_, &from.ins_stream_type_, + static_cast(reinterpret_cast(&rtk_stream_out_type_) - + reinterpret_cast(&ins_stream_type_)) + sizeof(rtk_stream_out_type_)); + // @@protoc_insertion_point(copy_constructor:apollo.common.gnss_status.StreamStatus) +} + +void StreamStatus::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&rtk_stream_out_type_) - + reinterpret_cast(&header_)) + sizeof(rtk_stream_out_type_)); +} + +StreamStatus::~StreamStatus() { + // @@protoc_insertion_point(destructor:apollo.common.gnss_status.StreamStatus) + SharedDtor(); +} + +void StreamStatus::SharedDtor() { + if (this != internal_default_instance()) delete header_; +} + +void StreamStatus::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* StreamStatus::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const StreamStatus& StreamStatus::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::scc_info_StreamStatus.base); + return *internal_default_instance(); +} + + +void StreamStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.gnss_status.StreamStatus) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + ::memset(&ins_stream_type_, 0, static_cast( + reinterpret_cast(&rtk_stream_out_type_) - + reinterpret_cast(&ins_stream_type_)) + sizeof(rtk_stream_out_type_)); + _internal_metadata_.Clear(); +} + +bool StreamStatus::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.gnss_status.StreamStatus) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.gnss_status.StreamStatus.Type ins_stream_type = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_ins_stream_type(static_cast< ::apollo::common::gnss_status::StreamStatus_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.gnss_status.StreamStatus.Type rtk_stream_in_type = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_rtk_stream_in_type(static_cast< ::apollo::common::gnss_status::StreamStatus_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.gnss_status.StreamStatus.Type rtk_stream_out_type = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_rtk_stream_out_type(static_cast< ::apollo::common::gnss_status::StreamStatus_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.gnss_status.StreamStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.gnss_status.StreamStatus) + return false; +#undef DO_ +} + +void StreamStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.gnss_status.StreamStatus) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // .apollo.common.gnss_status.StreamStatus.Type ins_stream_type = 2; + if (this->ins_stream_type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 2, this->ins_stream_type(), output); + } + + // .apollo.common.gnss_status.StreamStatus.Type rtk_stream_in_type = 3; + if (this->rtk_stream_in_type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 3, this->rtk_stream_in_type(), output); + } + + // .apollo.common.gnss_status.StreamStatus.Type rtk_stream_out_type = 4; + if (this->rtk_stream_out_type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 4, this->rtk_stream_out_type(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.gnss_status.StreamStatus) +} + +::google::protobuf::uint8* StreamStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.gnss_status.StreamStatus) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // .apollo.common.gnss_status.StreamStatus.Type ins_stream_type = 2; + if (this->ins_stream_type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 2, this->ins_stream_type(), target); + } + + // .apollo.common.gnss_status.StreamStatus.Type rtk_stream_in_type = 3; + if (this->rtk_stream_in_type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 3, this->rtk_stream_in_type(), target); + } + + // .apollo.common.gnss_status.StreamStatus.Type rtk_stream_out_type = 4; + if (this->rtk_stream_out_type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 4, this->rtk_stream_out_type(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.gnss_status.StreamStatus) + return target; +} + +size_t StreamStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.gnss_status.StreamStatus) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.common.gnss_status.StreamStatus.Type ins_stream_type = 2; + if (this->ins_stream_type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->ins_stream_type()); + } + + // .apollo.common.gnss_status.StreamStatus.Type rtk_stream_in_type = 3; + if (this->rtk_stream_in_type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->rtk_stream_in_type()); + } + + // .apollo.common.gnss_status.StreamStatus.Type rtk_stream_out_type = 4; + if (this->rtk_stream_out_type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->rtk_stream_out_type()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void StreamStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.gnss_status.StreamStatus) + GOOGLE_DCHECK_NE(&from, this); + const StreamStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.gnss_status.StreamStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.gnss_status.StreamStatus) + MergeFrom(*source); + } +} + +void StreamStatus::MergeFrom(const StreamStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.gnss_status.StreamStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.ins_stream_type() != 0) { + set_ins_stream_type(from.ins_stream_type()); + } + if (from.rtk_stream_in_type() != 0) { + set_rtk_stream_in_type(from.rtk_stream_in_type()); + } + if (from.rtk_stream_out_type() != 0) { + set_rtk_stream_out_type(from.rtk_stream_out_type()); + } +} + +void StreamStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.gnss_status.StreamStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void StreamStatus::CopyFrom(const StreamStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.gnss_status.StreamStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool StreamStatus::IsInitialized() const { + return true; +} + +void StreamStatus::Swap(StreamStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void StreamStatus::InternalSwap(StreamStatus* other) { + using std::swap; + swap(header_, other->header_); + swap(ins_stream_type_, other->ins_stream_type_); + swap(rtk_stream_in_type_, other->rtk_stream_in_type_); + swap(rtk_stream_out_type_, other->rtk_stream_out_type_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata StreamStatus::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void InsStatus::InitAsDefaultInstance() { + ::apollo::common::gnss_status::_InsStatus_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); +} +void InsStatus::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int InsStatus::kHeaderFieldNumber; +const int InsStatus::kTypeFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +InsStatus::InsStatus() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::scc_info_InsStatus.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.gnss_status.InsStatus) +} +InsStatus::InsStatus(const InsStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + type_ = from.type_; + // @@protoc_insertion_point(copy_constructor:apollo.common.gnss_status.InsStatus) +} + +void InsStatus::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&type_) - + reinterpret_cast(&header_)) + sizeof(type_)); +} + +InsStatus::~InsStatus() { + // @@protoc_insertion_point(destructor:apollo.common.gnss_status.InsStatus) + SharedDtor(); +} + +void InsStatus::SharedDtor() { + if (this != internal_default_instance()) delete header_; +} + +void InsStatus::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* InsStatus::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const InsStatus& InsStatus::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::scc_info_InsStatus.base); + return *internal_default_instance(); +} + + +void InsStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.gnss_status.InsStatus) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + type_ = 0; + _internal_metadata_.Clear(); +} + +bool InsStatus::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.gnss_status.InsStatus) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.gnss_status.InsStatus.Type type = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_type(static_cast< ::apollo::common::gnss_status::InsStatus_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.gnss_status.InsStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.gnss_status.InsStatus) + return false; +#undef DO_ +} + +void InsStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.gnss_status.InsStatus) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // .apollo.common.gnss_status.InsStatus.Type type = 2; + if (this->type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 2, this->type(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.gnss_status.InsStatus) +} + +::google::protobuf::uint8* InsStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.gnss_status.InsStatus) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // .apollo.common.gnss_status.InsStatus.Type type = 2; + if (this->type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 2, this->type(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.gnss_status.InsStatus) + return target; +} + +size_t InsStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.gnss_status.InsStatus) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.common.gnss_status.InsStatus.Type type = 2; + if (this->type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->type()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void InsStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.gnss_status.InsStatus) + GOOGLE_DCHECK_NE(&from, this); + const InsStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.gnss_status.InsStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.gnss_status.InsStatus) + MergeFrom(*source); + } +} + +void InsStatus::MergeFrom(const InsStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.gnss_status.InsStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.type() != 0) { + set_type(from.type()); + } +} + +void InsStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.gnss_status.InsStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void InsStatus::CopyFrom(const InsStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.gnss_status.InsStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool InsStatus::IsInitialized() const { + return true; +} + +void InsStatus::Swap(InsStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void InsStatus::InternalSwap(InsStatus* other) { + using std::swap; + swap(header_, other->header_); + swap(type_, other->type_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata InsStatus::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void GnssStatus::InitAsDefaultInstance() { + ::apollo::common::gnss_status::_GnssStatus_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); +} +void GnssStatus::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int GnssStatus::kHeaderFieldNumber; +const int GnssStatus::kSolutionCompletedFieldNumber; +const int GnssStatus::kSolutionStatusFieldNumber; +const int GnssStatus::kPositionTypeFieldNumber; +const int GnssStatus::kNumSatsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +GnssStatus::GnssStatus() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::scc_info_GnssStatus.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.gnss_status.GnssStatus) +} +GnssStatus::GnssStatus(const GnssStatus& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + ::memcpy(&solution_completed_, &from.solution_completed_, + static_cast(reinterpret_cast(&num_sats_) - + reinterpret_cast(&solution_completed_)) + sizeof(num_sats_)); + // @@protoc_insertion_point(copy_constructor:apollo.common.gnss_status.GnssStatus) +} + +void GnssStatus::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&num_sats_) - + reinterpret_cast(&header_)) + sizeof(num_sats_)); +} + +GnssStatus::~GnssStatus() { + // @@protoc_insertion_point(destructor:apollo.common.gnss_status.GnssStatus) + SharedDtor(); +} + +void GnssStatus::SharedDtor() { + if (this != internal_default_instance()) delete header_; +} + +void GnssStatus::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* GnssStatus::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const GnssStatus& GnssStatus::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::scc_info_GnssStatus.base); + return *internal_default_instance(); +} + + +void GnssStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.gnss_status.GnssStatus) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + ::memset(&solution_completed_, 0, static_cast( + reinterpret_cast(&num_sats_) - + reinterpret_cast(&solution_completed_)) + sizeof(num_sats_)); + _internal_metadata_.Clear(); +} + +bool GnssStatus::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.gnss_status.GnssStatus) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // bool solution_completed = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &solution_completed_))); + } else { + goto handle_unusual; + } + break; + } + + // uint32 solution_status = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &solution_status_))); + } else { + goto handle_unusual; + } + break; + } + + // uint32 position_type = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &position_type_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 num_sats = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(40u /* 40 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &num_sats_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.gnss_status.GnssStatus) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.gnss_status.GnssStatus) + return false; +#undef DO_ +} + +void GnssStatus::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.gnss_status.GnssStatus) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // bool solution_completed = 2; + if (this->solution_completed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->solution_completed(), output); + } + + // uint32 solution_status = 3; + if (this->solution_status() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(3, this->solution_status(), output); + } + + // uint32 position_type = 4; + if (this->position_type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(4, this->position_type(), output); + } + + // int32 num_sats = 5; + if (this->num_sats() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(5, this->num_sats(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.gnss_status.GnssStatus) +} + +::google::protobuf::uint8* GnssStatus::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.gnss_status.GnssStatus) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // bool solution_completed = 2; + if (this->solution_completed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->solution_completed(), target); + } + + // uint32 solution_status = 3; + if (this->solution_status() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(3, this->solution_status(), target); + } + + // uint32 position_type = 4; + if (this->position_type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(4, this->position_type(), target); + } + + // int32 num_sats = 5; + if (this->num_sats() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(5, this->num_sats(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.gnss_status.GnssStatus) + return target; +} + +size_t GnssStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.gnss_status.GnssStatus) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // bool solution_completed = 2; + if (this->solution_completed() != 0) { + total_size += 1 + 1; + } + + // uint32 solution_status = 3; + if (this->solution_status() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->solution_status()); + } + + // uint32 position_type = 4; + if (this->position_type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->position_type()); + } + + // int32 num_sats = 5; + if (this->num_sats() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->num_sats()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void GnssStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.gnss_status.GnssStatus) + GOOGLE_DCHECK_NE(&from, this); + const GnssStatus* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.gnss_status.GnssStatus) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.gnss_status.GnssStatus) + MergeFrom(*source); + } +} + +void GnssStatus::MergeFrom(const GnssStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.gnss_status.GnssStatus) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.solution_completed() != 0) { + set_solution_completed(from.solution_completed()); + } + if (from.solution_status() != 0) { + set_solution_status(from.solution_status()); + } + if (from.position_type() != 0) { + set_position_type(from.position_type()); + } + if (from.num_sats() != 0) { + set_num_sats(from.num_sats()); + } +} + +void GnssStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.gnss_status.GnssStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void GnssStatus::CopyFrom(const GnssStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.gnss_status.GnssStatus) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool GnssStatus::IsInitialized() const { + return true; +} + +void GnssStatus::Swap(GnssStatus* other) { + if (other == this) return; + InternalSwap(other); +} +void GnssStatus::InternalSwap(GnssStatus* other) { + using std::swap; + swap(header_, other->header_); + swap(solution_completed_, other->solution_completed_); + swap(solution_status_, other->solution_status_); + swap(position_type_, other->position_type_); + swap(num_sats_, other->num_sats_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata GnssStatus::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace gnss_status +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::gnss_status::StreamStatus* Arena::CreateMaybeMessage< ::apollo::common::gnss_status::StreamStatus >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::gnss_status::StreamStatus >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::gnss_status::InsStatus* Arena::CreateMaybeMessage< ::apollo::common::gnss_status::InsStatus >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::gnss_status::InsStatus >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::gnss_status::GnssStatus* Arena::CreateMaybeMessage< ::apollo::common::gnss_status::GnssStatus >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::gnss_status::GnssStatus >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/common/gnss_status.pb.h b/apollo_msgs/include/apollo_msgs/proto/common/gnss_status.pb.h new file mode 100644 index 0000000..59b6941 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/gnss_status.pb.h @@ -0,0 +1,864 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/gnss_status.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "apollo_msgs/proto/common/header.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[3]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto +namespace apollo { +namespace common { +namespace gnss_status { +class GnssStatus; +class GnssStatusDefaultTypeInternal; +extern GnssStatusDefaultTypeInternal _GnssStatus_default_instance_; +class InsStatus; +class InsStatusDefaultTypeInternal; +extern InsStatusDefaultTypeInternal _InsStatus_default_instance_; +class StreamStatus; +class StreamStatusDefaultTypeInternal; +extern StreamStatusDefaultTypeInternal _StreamStatus_default_instance_; +} // namespace gnss_status +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::common::gnss_status::GnssStatus* Arena::CreateMaybeMessage<::apollo::common::gnss_status::GnssStatus>(Arena*); +template<> ::apollo::common::gnss_status::InsStatus* Arena::CreateMaybeMessage<::apollo::common::gnss_status::InsStatus>(Arena*); +template<> ::apollo::common::gnss_status::StreamStatus* Arena::CreateMaybeMessage<::apollo::common::gnss_status::StreamStatus>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace common { +namespace gnss_status { + +enum StreamStatus_Type { + StreamStatus_Type_DISCONNECTED = 0, + StreamStatus_Type_CONNECTED = 1, + StreamStatus_Type_StreamStatus_Type_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + StreamStatus_Type_StreamStatus_Type_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool StreamStatus_Type_IsValid(int value); +const StreamStatus_Type StreamStatus_Type_Type_MIN = StreamStatus_Type_DISCONNECTED; +const StreamStatus_Type StreamStatus_Type_Type_MAX = StreamStatus_Type_CONNECTED; +const int StreamStatus_Type_Type_ARRAYSIZE = StreamStatus_Type_Type_MAX + 1; + +const ::google::protobuf::EnumDescriptor* StreamStatus_Type_descriptor(); +inline const ::std::string& StreamStatus_Type_Name(StreamStatus_Type value) { + return ::google::protobuf::internal::NameOfEnum( + StreamStatus_Type_descriptor(), value); +} +inline bool StreamStatus_Type_Parse( + const ::std::string& name, StreamStatus_Type* value) { + return ::google::protobuf::internal::ParseNamedEnum( + StreamStatus_Type_descriptor(), name, value); +} +enum InsStatus_Type { + InsStatus_Type_INVALID = 0, + InsStatus_Type_CONVERGING = 1, + InsStatus_Type_GOOD = 2, + InsStatus_Type_InsStatus_Type_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + InsStatus_Type_InsStatus_Type_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool InsStatus_Type_IsValid(int value); +const InsStatus_Type InsStatus_Type_Type_MIN = InsStatus_Type_INVALID; +const InsStatus_Type InsStatus_Type_Type_MAX = InsStatus_Type_GOOD; +const int InsStatus_Type_Type_ARRAYSIZE = InsStatus_Type_Type_MAX + 1; + +const ::google::protobuf::EnumDescriptor* InsStatus_Type_descriptor(); +inline const ::std::string& InsStatus_Type_Name(InsStatus_Type value) { + return ::google::protobuf::internal::NameOfEnum( + InsStatus_Type_descriptor(), value); +} +inline bool InsStatus_Type_Parse( + const ::std::string& name, InsStatus_Type* value) { + return ::google::protobuf::internal::ParseNamedEnum( + InsStatus_Type_descriptor(), name, value); +} +// =================================================================== + +class StreamStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.gnss_status.StreamStatus) */ { + public: + StreamStatus(); + virtual ~StreamStatus(); + + StreamStatus(const StreamStatus& from); + + inline StreamStatus& operator=(const StreamStatus& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + StreamStatus(StreamStatus&& from) noexcept + : StreamStatus() { + *this = ::std::move(from); + } + + inline StreamStatus& operator=(StreamStatus&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const StreamStatus& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const StreamStatus* internal_default_instance() { + return reinterpret_cast( + &_StreamStatus_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(StreamStatus* other); + friend void swap(StreamStatus& a, StreamStatus& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline StreamStatus* New() const final { + return CreateMaybeMessage(NULL); + } + + StreamStatus* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const StreamStatus& from); + void MergeFrom(const StreamStatus& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(StreamStatus* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef StreamStatus_Type Type; + static const Type DISCONNECTED = + StreamStatus_Type_DISCONNECTED; + static const Type CONNECTED = + StreamStatus_Type_CONNECTED; + static inline bool Type_IsValid(int value) { + return StreamStatus_Type_IsValid(value); + } + static const Type Type_MIN = + StreamStatus_Type_Type_MIN; + static const Type Type_MAX = + StreamStatus_Type_Type_MAX; + static const int Type_ARRAYSIZE = + StreamStatus_Type_Type_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Type_descriptor() { + return StreamStatus_Type_descriptor(); + } + static inline const ::std::string& Type_Name(Type value) { + return StreamStatus_Type_Name(value); + } + static inline bool Type_Parse(const ::std::string& name, + Type* value) { + return StreamStatus_Type_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.common.gnss_status.StreamStatus.Type ins_stream_type = 2; + void clear_ins_stream_type(); + static const int kInsStreamTypeFieldNumber = 2; + ::apollo::common::gnss_status::StreamStatus_Type ins_stream_type() const; + void set_ins_stream_type(::apollo::common::gnss_status::StreamStatus_Type value); + + // .apollo.common.gnss_status.StreamStatus.Type rtk_stream_in_type = 3; + void clear_rtk_stream_in_type(); + static const int kRtkStreamInTypeFieldNumber = 3; + ::apollo::common::gnss_status::StreamStatus_Type rtk_stream_in_type() const; + void set_rtk_stream_in_type(::apollo::common::gnss_status::StreamStatus_Type value); + + // .apollo.common.gnss_status.StreamStatus.Type rtk_stream_out_type = 4; + void clear_rtk_stream_out_type(); + static const int kRtkStreamOutTypeFieldNumber = 4; + ::apollo::common::gnss_status::StreamStatus_Type rtk_stream_out_type() const; + void set_rtk_stream_out_type(::apollo::common::gnss_status::StreamStatus_Type value); + + // @@protoc_insertion_point(class_scope:apollo.common.gnss_status.StreamStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::Header* header_; + int ins_stream_type_; + int rtk_stream_in_type_; + int rtk_stream_out_type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class InsStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.gnss_status.InsStatus) */ { + public: + InsStatus(); + virtual ~InsStatus(); + + InsStatus(const InsStatus& from); + + inline InsStatus& operator=(const InsStatus& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + InsStatus(InsStatus&& from) noexcept + : InsStatus() { + *this = ::std::move(from); + } + + inline InsStatus& operator=(InsStatus&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const InsStatus& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const InsStatus* internal_default_instance() { + return reinterpret_cast( + &_InsStatus_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(InsStatus* other); + friend void swap(InsStatus& a, InsStatus& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline InsStatus* New() const final { + return CreateMaybeMessage(NULL); + } + + InsStatus* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const InsStatus& from); + void MergeFrom(const InsStatus& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(InsStatus* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef InsStatus_Type Type; + static const Type INVALID = + InsStatus_Type_INVALID; + static const Type CONVERGING = + InsStatus_Type_CONVERGING; + static const Type GOOD = + InsStatus_Type_GOOD; + static inline bool Type_IsValid(int value) { + return InsStatus_Type_IsValid(value); + } + static const Type Type_MIN = + InsStatus_Type_Type_MIN; + static const Type Type_MAX = + InsStatus_Type_Type_MAX; + static const int Type_ARRAYSIZE = + InsStatus_Type_Type_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Type_descriptor() { + return InsStatus_Type_descriptor(); + } + static inline const ::std::string& Type_Name(Type value) { + return InsStatus_Type_Name(value); + } + static inline bool Type_Parse(const ::std::string& name, + Type* value) { + return InsStatus_Type_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.common.gnss_status.InsStatus.Type type = 2; + void clear_type(); + static const int kTypeFieldNumber = 2; + ::apollo::common::gnss_status::InsStatus_Type type() const; + void set_type(::apollo::common::gnss_status::InsStatus_Type value); + + // @@protoc_insertion_point(class_scope:apollo.common.gnss_status.InsStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::Header* header_; + int type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class GnssStatus : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.gnss_status.GnssStatus) */ { + public: + GnssStatus(); + virtual ~GnssStatus(); + + GnssStatus(const GnssStatus& from); + + inline GnssStatus& operator=(const GnssStatus& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + GnssStatus(GnssStatus&& from) noexcept + : GnssStatus() { + *this = ::std::move(from); + } + + inline GnssStatus& operator=(GnssStatus&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const GnssStatus& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const GnssStatus* internal_default_instance() { + return reinterpret_cast( + &_GnssStatus_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + void Swap(GnssStatus* other); + friend void swap(GnssStatus& a, GnssStatus& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline GnssStatus* New() const final { + return CreateMaybeMessage(NULL); + } + + GnssStatus* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const GnssStatus& from); + void MergeFrom(const GnssStatus& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(GnssStatus* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // bool solution_completed = 2; + void clear_solution_completed(); + static const int kSolutionCompletedFieldNumber = 2; + bool solution_completed() const; + void set_solution_completed(bool value); + + // uint32 solution_status = 3; + void clear_solution_status(); + static const int kSolutionStatusFieldNumber = 3; + ::google::protobuf::uint32 solution_status() const; + void set_solution_status(::google::protobuf::uint32 value); + + // uint32 position_type = 4; + void clear_position_type(); + static const int kPositionTypeFieldNumber = 4; + ::google::protobuf::uint32 position_type() const; + void set_position_type(::google::protobuf::uint32 value); + + // int32 num_sats = 5; + void clear_num_sats(); + static const int kNumSatsFieldNumber = 5; + ::google::protobuf::int32 num_sats() const; + void set_num_sats(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:apollo.common.gnss_status.GnssStatus) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::Header* header_; + bool solution_completed_; + ::google::protobuf::uint32 solution_status_; + ::google::protobuf::uint32 position_type_; + ::google::protobuf::int32 num_sats_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// StreamStatus + +// .apollo.common.Header header = 1; +inline bool StreamStatus::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& StreamStatus::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& StreamStatus::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.common.gnss_status.StreamStatus.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* StreamStatus::release_header() { + // @@protoc_insertion_point(field_release:apollo.common.gnss_status.StreamStatus.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* StreamStatus::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.common.gnss_status.StreamStatus.header) + return header_; +} +inline void StreamStatus::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.common.gnss_status.StreamStatus.header) +} + +// .apollo.common.gnss_status.StreamStatus.Type ins_stream_type = 2; +inline void StreamStatus::clear_ins_stream_type() { + ins_stream_type_ = 0; +} +inline ::apollo::common::gnss_status::StreamStatus_Type StreamStatus::ins_stream_type() const { + // @@protoc_insertion_point(field_get:apollo.common.gnss_status.StreamStatus.ins_stream_type) + return static_cast< ::apollo::common::gnss_status::StreamStatus_Type >(ins_stream_type_); +} +inline void StreamStatus::set_ins_stream_type(::apollo::common::gnss_status::StreamStatus_Type value) { + + ins_stream_type_ = value; + // @@protoc_insertion_point(field_set:apollo.common.gnss_status.StreamStatus.ins_stream_type) +} + +// .apollo.common.gnss_status.StreamStatus.Type rtk_stream_in_type = 3; +inline void StreamStatus::clear_rtk_stream_in_type() { + rtk_stream_in_type_ = 0; +} +inline ::apollo::common::gnss_status::StreamStatus_Type StreamStatus::rtk_stream_in_type() const { + // @@protoc_insertion_point(field_get:apollo.common.gnss_status.StreamStatus.rtk_stream_in_type) + return static_cast< ::apollo::common::gnss_status::StreamStatus_Type >(rtk_stream_in_type_); +} +inline void StreamStatus::set_rtk_stream_in_type(::apollo::common::gnss_status::StreamStatus_Type value) { + + rtk_stream_in_type_ = value; + // @@protoc_insertion_point(field_set:apollo.common.gnss_status.StreamStatus.rtk_stream_in_type) +} + +// .apollo.common.gnss_status.StreamStatus.Type rtk_stream_out_type = 4; +inline void StreamStatus::clear_rtk_stream_out_type() { + rtk_stream_out_type_ = 0; +} +inline ::apollo::common::gnss_status::StreamStatus_Type StreamStatus::rtk_stream_out_type() const { + // @@protoc_insertion_point(field_get:apollo.common.gnss_status.StreamStatus.rtk_stream_out_type) + return static_cast< ::apollo::common::gnss_status::StreamStatus_Type >(rtk_stream_out_type_); +} +inline void StreamStatus::set_rtk_stream_out_type(::apollo::common::gnss_status::StreamStatus_Type value) { + + rtk_stream_out_type_ = value; + // @@protoc_insertion_point(field_set:apollo.common.gnss_status.StreamStatus.rtk_stream_out_type) +} + +// ------------------------------------------------------------------- + +// InsStatus + +// .apollo.common.Header header = 1; +inline bool InsStatus::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& InsStatus::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& InsStatus::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.common.gnss_status.InsStatus.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* InsStatus::release_header() { + // @@protoc_insertion_point(field_release:apollo.common.gnss_status.InsStatus.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* InsStatus::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.common.gnss_status.InsStatus.header) + return header_; +} +inline void InsStatus::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.common.gnss_status.InsStatus.header) +} + +// .apollo.common.gnss_status.InsStatus.Type type = 2; +inline void InsStatus::clear_type() { + type_ = 0; +} +inline ::apollo::common::gnss_status::InsStatus_Type InsStatus::type() const { + // @@protoc_insertion_point(field_get:apollo.common.gnss_status.InsStatus.type) + return static_cast< ::apollo::common::gnss_status::InsStatus_Type >(type_); +} +inline void InsStatus::set_type(::apollo::common::gnss_status::InsStatus_Type value) { + + type_ = value; + // @@protoc_insertion_point(field_set:apollo.common.gnss_status.InsStatus.type) +} + +// ------------------------------------------------------------------- + +// GnssStatus + +// .apollo.common.Header header = 1; +inline bool GnssStatus::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& GnssStatus::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& GnssStatus::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.common.gnss_status.GnssStatus.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* GnssStatus::release_header() { + // @@protoc_insertion_point(field_release:apollo.common.gnss_status.GnssStatus.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* GnssStatus::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.common.gnss_status.GnssStatus.header) + return header_; +} +inline void GnssStatus::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.common.gnss_status.GnssStatus.header) +} + +// bool solution_completed = 2; +inline void GnssStatus::clear_solution_completed() { + solution_completed_ = false; +} +inline bool GnssStatus::solution_completed() const { + // @@protoc_insertion_point(field_get:apollo.common.gnss_status.GnssStatus.solution_completed) + return solution_completed_; +} +inline void GnssStatus::set_solution_completed(bool value) { + + solution_completed_ = value; + // @@protoc_insertion_point(field_set:apollo.common.gnss_status.GnssStatus.solution_completed) +} + +// uint32 solution_status = 3; +inline void GnssStatus::clear_solution_status() { + solution_status_ = 0u; +} +inline ::google::protobuf::uint32 GnssStatus::solution_status() const { + // @@protoc_insertion_point(field_get:apollo.common.gnss_status.GnssStatus.solution_status) + return solution_status_; +} +inline void GnssStatus::set_solution_status(::google::protobuf::uint32 value) { + + solution_status_ = value; + // @@protoc_insertion_point(field_set:apollo.common.gnss_status.GnssStatus.solution_status) +} + +// uint32 position_type = 4; +inline void GnssStatus::clear_position_type() { + position_type_ = 0u; +} +inline ::google::protobuf::uint32 GnssStatus::position_type() const { + // @@protoc_insertion_point(field_get:apollo.common.gnss_status.GnssStatus.position_type) + return position_type_; +} +inline void GnssStatus::set_position_type(::google::protobuf::uint32 value) { + + position_type_ = value; + // @@protoc_insertion_point(field_set:apollo.common.gnss_status.GnssStatus.position_type) +} + +// int32 num_sats = 5; +inline void GnssStatus::clear_num_sats() { + num_sats_ = 0; +} +inline ::google::protobuf::int32 GnssStatus::num_sats() const { + // @@protoc_insertion_point(field_get:apollo.common.gnss_status.GnssStatus.num_sats) + return num_sats_; +} +inline void GnssStatus::set_num_sats(::google::protobuf::int32 value) { + + num_sats_ = value; + // @@protoc_insertion_point(field_set:apollo.common.gnss_status.GnssStatus.num_sats) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace gnss_status +} // namespace common +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::common::gnss_status::StreamStatus_Type> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::common::gnss_status::StreamStatus_Type>() { + return ::apollo::common::gnss_status::StreamStatus_Type_descriptor(); +} +template <> struct is_proto_enum< ::apollo::common::gnss_status::InsStatus_Type> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::common::gnss_status::InsStatus_Type>() { + return ::apollo::common::gnss_status::InsStatus_Type_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fgnss_5fstatus_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/common/header.pb.cc b/apollo_msgs/include/apollo_msgs/proto/common/header.pb.cc new file mode 100644 index 0000000..1323a64 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/header.pb.cc @@ -0,0 +1,661 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/header.proto + +#include "apollo_msgs/proto/common/header.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_StatusPb; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto +namespace apollo { +namespace common { +class HeaderDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed
+ _instance; +} _Header_default_instance_; +} // namespace common +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +static void InitDefaultsHeader() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::_Header_default_instance_; + new (ptr) ::apollo::common::Header(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::Header::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_Header = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsHeader}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto::scc_info_StatusPb.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_Header.base); +} + +::google::protobuf::Metadata file_level_metadata[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Header, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Header, timestamp_sec_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Header, module_name_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Header, sequence_num_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Header, lidar_timestamp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Header, camera_timestamp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Header, radar_timestamp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Header, version_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::Header, status_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::common::Header)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::common::_Header_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/common/header.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 1); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n%apollo_msgs/proto/common/header.proto\022" + "\rapollo.common\032)apollo_msgs/proto/common" + "/error_code.proto\"\320\001\n\006Header\022\025\n\rtimestam" + "p_sec\030\001 \001(\001\022\023\n\013module_name\030\002 \001(\t\022\024\n\014sequ" + "ence_num\030\003 \001(\r\022\027\n\017lidar_timestamp\030\004 \001(\004\022" + "\030\n\020camera_timestamp\030\005 \001(\004\022\027\n\017radar_times" + "tamp\030\006 \001(\004\022\017\n\007version\030\007 \001(\r\022\'\n\006status\030\010 " + "\001(\0132\027.apollo.common.StatusPbb\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 316); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/common/header.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2ferror_5fcode_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace apollo { +namespace common { + +// =================================================================== + +void Header::InitAsDefaultInstance() { + ::apollo::common::_Header_default_instance_._instance.get_mutable()->status_ = const_cast< ::apollo::common::StatusPb*>( + ::apollo::common::StatusPb::internal_default_instance()); +} +void Header::clear_status() { + if (GetArenaNoVirtual() == NULL && status_ != NULL) { + delete status_; + } + status_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Header::kTimestampSecFieldNumber; +const int Header::kModuleNameFieldNumber; +const int Header::kSequenceNumFieldNumber; +const int Header::kLidarTimestampFieldNumber; +const int Header::kCameraTimestampFieldNumber; +const int Header::kRadarTimestampFieldNumber; +const int Header::kVersionFieldNumber; +const int Header::kStatusFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Header::Header() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.Header) +} +Header::Header(const Header& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + module_name_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.module_name().size() > 0) { + module_name_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.module_name_); + } + if (from.has_status()) { + status_ = new ::apollo::common::StatusPb(*from.status_); + } else { + status_ = NULL; + } + ::memcpy(×tamp_sec_, &from.timestamp_sec_, + static_cast(reinterpret_cast(&radar_timestamp_) - + reinterpret_cast(×tamp_sec_)) + sizeof(radar_timestamp_)); + // @@protoc_insertion_point(copy_constructor:apollo.common.Header) +} + +void Header::SharedCtor() { + module_name_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&status_, 0, static_cast( + reinterpret_cast(&radar_timestamp_) - + reinterpret_cast(&status_)) + sizeof(radar_timestamp_)); +} + +Header::~Header() { + // @@protoc_insertion_point(destructor:apollo.common.Header) + SharedDtor(); +} + +void Header::SharedDtor() { + module_name_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (this != internal_default_instance()) delete status_; +} + +void Header::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Header::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Header& Header::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base); + return *internal_default_instance(); +} + + +void Header::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.Header) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + module_name_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (GetArenaNoVirtual() == NULL && status_ != NULL) { + delete status_; + } + status_ = NULL; + ::memset(×tamp_sec_, 0, static_cast( + reinterpret_cast(&radar_timestamp_) - + reinterpret_cast(×tamp_sec_)) + sizeof(radar_timestamp_)); + _internal_metadata_.Clear(); +} + +bool Header::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.Header) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double timestamp_sec = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, ×tamp_sec_))); + } else { + goto handle_unusual; + } + break; + } + + // string module_name = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_module_name())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->module_name().data(), static_cast(this->module_name().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.common.Header.module_name")); + } else { + goto handle_unusual; + } + break; + } + + // uint32 sequence_num = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &sequence_num_))); + } else { + goto handle_unusual; + } + break; + } + + // uint64 lidar_timestamp = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint64, ::google::protobuf::internal::WireFormatLite::TYPE_UINT64>( + input, &lidar_timestamp_))); + } else { + goto handle_unusual; + } + break; + } + + // uint64 camera_timestamp = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(40u /* 40 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint64, ::google::protobuf::internal::WireFormatLite::TYPE_UINT64>( + input, &camera_timestamp_))); + } else { + goto handle_unusual; + } + break; + } + + // uint64 radar_timestamp = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(48u /* 48 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint64, ::google::protobuf::internal::WireFormatLite::TYPE_UINT64>( + input, &radar_timestamp_))); + } else { + goto handle_unusual; + } + break; + } + + // uint32 version = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(56u /* 56 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &version_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.StatusPb status = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(66u /* 66 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_status())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.Header) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.Header) + return false; +#undef DO_ +} + +void Header::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.Header) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double timestamp_sec = 1; + if (this->timestamp_sec() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->timestamp_sec(), output); + } + + // string module_name = 2; + if (this->module_name().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->module_name().data(), static_cast(this->module_name().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.common.Header.module_name"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 2, this->module_name(), output); + } + + // uint32 sequence_num = 3; + if (this->sequence_num() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(3, this->sequence_num(), output); + } + + // uint64 lidar_timestamp = 4; + if (this->lidar_timestamp() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt64(4, this->lidar_timestamp(), output); + } + + // uint64 camera_timestamp = 5; + if (this->camera_timestamp() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt64(5, this->camera_timestamp(), output); + } + + // uint64 radar_timestamp = 6; + if (this->radar_timestamp() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt64(6, this->radar_timestamp(), output); + } + + // uint32 version = 7; + if (this->version() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(7, this->version(), output); + } + + // .apollo.common.StatusPb status = 8; + if (this->has_status()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 8, this->_internal_status(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.Header) +} + +::google::protobuf::uint8* Header::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.Header) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double timestamp_sec = 1; + if (this->timestamp_sec() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->timestamp_sec(), target); + } + + // string module_name = 2; + if (this->module_name().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->module_name().data(), static_cast(this->module_name().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.common.Header.module_name"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 2, this->module_name(), target); + } + + // uint32 sequence_num = 3; + if (this->sequence_num() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(3, this->sequence_num(), target); + } + + // uint64 lidar_timestamp = 4; + if (this->lidar_timestamp() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt64ToArray(4, this->lidar_timestamp(), target); + } + + // uint64 camera_timestamp = 5; + if (this->camera_timestamp() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt64ToArray(5, this->camera_timestamp(), target); + } + + // uint64 radar_timestamp = 6; + if (this->radar_timestamp() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt64ToArray(6, this->radar_timestamp(), target); + } + + // uint32 version = 7; + if (this->version() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(7, this->version(), target); + } + + // .apollo.common.StatusPb status = 8; + if (this->has_status()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 8, this->_internal_status(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.Header) + return target; +} + +size_t Header::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.Header) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // string module_name = 2; + if (this->module_name().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->module_name()); + } + + // .apollo.common.StatusPb status = 8; + if (this->has_status()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *status_); + } + + // double timestamp_sec = 1; + if (this->timestamp_sec() != 0) { + total_size += 1 + 8; + } + + // uint64 lidar_timestamp = 4; + if (this->lidar_timestamp() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt64Size( + this->lidar_timestamp()); + } + + // uint64 camera_timestamp = 5; + if (this->camera_timestamp() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt64Size( + this->camera_timestamp()); + } + + // uint32 sequence_num = 3; + if (this->sequence_num() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->sequence_num()); + } + + // uint32 version = 7; + if (this->version() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->version()); + } + + // uint64 radar_timestamp = 6; + if (this->radar_timestamp() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt64Size( + this->radar_timestamp()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Header::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.Header) + GOOGLE_DCHECK_NE(&from, this); + const Header* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.Header) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.Header) + MergeFrom(*source); + } +} + +void Header::MergeFrom(const Header& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.Header) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.module_name().size() > 0) { + + module_name_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.module_name_); + } + if (from.has_status()) { + mutable_status()->::apollo::common::StatusPb::MergeFrom(from.status()); + } + if (from.timestamp_sec() != 0) { + set_timestamp_sec(from.timestamp_sec()); + } + if (from.lidar_timestamp() != 0) { + set_lidar_timestamp(from.lidar_timestamp()); + } + if (from.camera_timestamp() != 0) { + set_camera_timestamp(from.camera_timestamp()); + } + if (from.sequence_num() != 0) { + set_sequence_num(from.sequence_num()); + } + if (from.version() != 0) { + set_version(from.version()); + } + if (from.radar_timestamp() != 0) { + set_radar_timestamp(from.radar_timestamp()); + } +} + +void Header::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.Header) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Header::CopyFrom(const Header& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.Header) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Header::IsInitialized() const { + return true; +} + +void Header::Swap(Header* other) { + if (other == this) return; + InternalSwap(other); +} +void Header::InternalSwap(Header* other) { + using std::swap; + module_name_.Swap(&other->module_name_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(status_, other->status_); + swap(timestamp_sec_, other->timestamp_sec_); + swap(lidar_timestamp_, other->lidar_timestamp_); + swap(camera_timestamp_, other->camera_timestamp_); + swap(sequence_num_, other->sequence_num_); + swap(version_, other->version_); + swap(radar_timestamp_, other->radar_timestamp_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Header::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::Header* Arena::CreateMaybeMessage< ::apollo::common::Header >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::Header >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/common/header.pb.h b/apollo_msgs/include/apollo_msgs/proto/common/header.pb.h new file mode 100644 index 0000000..14badce --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/header.pb.h @@ -0,0 +1,437 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/header.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include "apollo_msgs/proto/common/error_code.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[1]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace apollo { +namespace common { +class Header; +class HeaderDefaultTypeInternal; +extern HeaderDefaultTypeInternal _Header_default_instance_; +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::common::Header* Arena::CreateMaybeMessage<::apollo::common::Header>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace common { + +// =================================================================== + +class Header : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.Header) */ { + public: + Header(); + virtual ~Header(); + + Header(const Header& from); + + inline Header& operator=(const Header& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Header(Header&& from) noexcept + : Header() { + *this = ::std::move(from); + } + + inline Header& operator=(Header&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Header& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Header* internal_default_instance() { + return reinterpret_cast( + &_Header_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(Header* other); + friend void swap(Header& a, Header& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Header* New() const final { + return CreateMaybeMessage
(NULL); + } + + Header* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage
(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Header& from); + void MergeFrom(const Header& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Header* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // string module_name = 2; + void clear_module_name(); + static const int kModuleNameFieldNumber = 2; + const ::std::string& module_name() const; + void set_module_name(const ::std::string& value); + #if LANG_CXX11 + void set_module_name(::std::string&& value); + #endif + void set_module_name(const char* value); + void set_module_name(const char* value, size_t size); + ::std::string* mutable_module_name(); + ::std::string* release_module_name(); + void set_allocated_module_name(::std::string* module_name); + + // .apollo.common.StatusPb status = 8; + bool has_status() const; + void clear_status(); + static const int kStatusFieldNumber = 8; + private: + const ::apollo::common::StatusPb& _internal_status() const; + public: + const ::apollo::common::StatusPb& status() const; + ::apollo::common::StatusPb* release_status(); + ::apollo::common::StatusPb* mutable_status(); + void set_allocated_status(::apollo::common::StatusPb* status); + + // double timestamp_sec = 1; + void clear_timestamp_sec(); + static const int kTimestampSecFieldNumber = 1; + double timestamp_sec() const; + void set_timestamp_sec(double value); + + // uint64 lidar_timestamp = 4; + void clear_lidar_timestamp(); + static const int kLidarTimestampFieldNumber = 4; + ::google::protobuf::uint64 lidar_timestamp() const; + void set_lidar_timestamp(::google::protobuf::uint64 value); + + // uint64 camera_timestamp = 5; + void clear_camera_timestamp(); + static const int kCameraTimestampFieldNumber = 5; + ::google::protobuf::uint64 camera_timestamp() const; + void set_camera_timestamp(::google::protobuf::uint64 value); + + // uint32 sequence_num = 3; + void clear_sequence_num(); + static const int kSequenceNumFieldNumber = 3; + ::google::protobuf::uint32 sequence_num() const; + void set_sequence_num(::google::protobuf::uint32 value); + + // uint32 version = 7; + void clear_version(); + static const int kVersionFieldNumber = 7; + ::google::protobuf::uint32 version() const; + void set_version(::google::protobuf::uint32 value); + + // uint64 radar_timestamp = 6; + void clear_radar_timestamp(); + static const int kRadarTimestampFieldNumber = 6; + ::google::protobuf::uint64 radar_timestamp() const; + void set_radar_timestamp(::google::protobuf::uint64 value); + + // @@protoc_insertion_point(class_scope:apollo.common.Header) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr module_name_; + ::apollo::common::StatusPb* status_; + double timestamp_sec_; + ::google::protobuf::uint64 lidar_timestamp_; + ::google::protobuf::uint64 camera_timestamp_; + ::google::protobuf::uint32 sequence_num_; + ::google::protobuf::uint32 version_; + ::google::protobuf::uint64 radar_timestamp_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// Header + +// double timestamp_sec = 1; +inline void Header::clear_timestamp_sec() { + timestamp_sec_ = 0; +} +inline double Header::timestamp_sec() const { + // @@protoc_insertion_point(field_get:apollo.common.Header.timestamp_sec) + return timestamp_sec_; +} +inline void Header::set_timestamp_sec(double value) { + + timestamp_sec_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Header.timestamp_sec) +} + +// string module_name = 2; +inline void Header::clear_module_name() { + module_name_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& Header::module_name() const { + // @@protoc_insertion_point(field_get:apollo.common.Header.module_name) + return module_name_.GetNoArena(); +} +inline void Header::set_module_name(const ::std::string& value) { + + module_name_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.common.Header.module_name) +} +#if LANG_CXX11 +inline void Header::set_module_name(::std::string&& value) { + + module_name_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.common.Header.module_name) +} +#endif +inline void Header::set_module_name(const char* value) { + GOOGLE_DCHECK(value != NULL); + + module_name_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.common.Header.module_name) +} +inline void Header::set_module_name(const char* value, size_t size) { + + module_name_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.common.Header.module_name) +} +inline ::std::string* Header::mutable_module_name() { + + // @@protoc_insertion_point(field_mutable:apollo.common.Header.module_name) + return module_name_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* Header::release_module_name() { + // @@protoc_insertion_point(field_release:apollo.common.Header.module_name) + + return module_name_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void Header::set_allocated_module_name(::std::string* module_name) { + if (module_name != NULL) { + + } else { + + } + module_name_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), module_name); + // @@protoc_insertion_point(field_set_allocated:apollo.common.Header.module_name) +} + +// uint32 sequence_num = 3; +inline void Header::clear_sequence_num() { + sequence_num_ = 0u; +} +inline ::google::protobuf::uint32 Header::sequence_num() const { + // @@protoc_insertion_point(field_get:apollo.common.Header.sequence_num) + return sequence_num_; +} +inline void Header::set_sequence_num(::google::protobuf::uint32 value) { + + sequence_num_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Header.sequence_num) +} + +// uint64 lidar_timestamp = 4; +inline void Header::clear_lidar_timestamp() { + lidar_timestamp_ = GOOGLE_ULONGLONG(0); +} +inline ::google::protobuf::uint64 Header::lidar_timestamp() const { + // @@protoc_insertion_point(field_get:apollo.common.Header.lidar_timestamp) + return lidar_timestamp_; +} +inline void Header::set_lidar_timestamp(::google::protobuf::uint64 value) { + + lidar_timestamp_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Header.lidar_timestamp) +} + +// uint64 camera_timestamp = 5; +inline void Header::clear_camera_timestamp() { + camera_timestamp_ = GOOGLE_ULONGLONG(0); +} +inline ::google::protobuf::uint64 Header::camera_timestamp() const { + // @@protoc_insertion_point(field_get:apollo.common.Header.camera_timestamp) + return camera_timestamp_; +} +inline void Header::set_camera_timestamp(::google::protobuf::uint64 value) { + + camera_timestamp_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Header.camera_timestamp) +} + +// uint64 radar_timestamp = 6; +inline void Header::clear_radar_timestamp() { + radar_timestamp_ = GOOGLE_ULONGLONG(0); +} +inline ::google::protobuf::uint64 Header::radar_timestamp() const { + // @@protoc_insertion_point(field_get:apollo.common.Header.radar_timestamp) + return radar_timestamp_; +} +inline void Header::set_radar_timestamp(::google::protobuf::uint64 value) { + + radar_timestamp_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Header.radar_timestamp) +} + +// uint32 version = 7; +inline void Header::clear_version() { + version_ = 0u; +} +inline ::google::protobuf::uint32 Header::version() const { + // @@protoc_insertion_point(field_get:apollo.common.Header.version) + return version_; +} +inline void Header::set_version(::google::protobuf::uint32 value) { + + version_ = value; + // @@protoc_insertion_point(field_set:apollo.common.Header.version) +} + +// .apollo.common.StatusPb status = 8; +inline bool Header::has_status() const { + return this != internal_default_instance() && status_ != NULL; +} +inline const ::apollo::common::StatusPb& Header::_internal_status() const { + return *status_; +} +inline const ::apollo::common::StatusPb& Header::status() const { + const ::apollo::common::StatusPb* p = status_; + // @@protoc_insertion_point(field_get:apollo.common.Header.status) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_StatusPb_default_instance_); +} +inline ::apollo::common::StatusPb* Header::release_status() { + // @@protoc_insertion_point(field_release:apollo.common.Header.status) + + ::apollo::common::StatusPb* temp = status_; + status_ = NULL; + return temp; +} +inline ::apollo::common::StatusPb* Header::mutable_status() { + + if (status_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::StatusPb>(GetArenaNoVirtual()); + status_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.common.Header.status) + return status_; +} +inline void Header::set_allocated_status(::apollo::common::StatusPb* status) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(status_); + } + if (status) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + status = ::google::protobuf::internal::GetOwnedMessage( + message_arena, status, submessage_arena); + } + + } else { + + } + status_ = status; + // @@protoc_insertion_point(field_set_allocated:apollo.common.Header.status) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) + +} // namespace common +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/common/monitor.pb.cc b/apollo_msgs/include/apollo_msgs/proto/common/monitor.pb.cc new file mode 100644 index 0000000..c9ebdcc --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/monitor.pb.cc @@ -0,0 +1,857 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/monitor.proto + +#include "apollo_msgs/proto/common/monitor.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_MonitorMessageItem; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto +namespace apollo { +namespace common { +namespace monitor { +class MonitorMessageItemDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _MonitorMessageItem_default_instance_; +class MonitorMessageDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _MonitorMessage_default_instance_; +} // namespace monitor +} // namespace common +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto { +static void InitDefaultsMonitorMessageItem() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::monitor::_MonitorMessageItem_default_instance_; + new (ptr) ::apollo::common::monitor::MonitorMessageItem(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::monitor::MonitorMessageItem::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_MonitorMessageItem = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsMonitorMessageItem}, {}}; + +static void InitDefaultsMonitorMessage() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::monitor::_MonitorMessage_default_instance_; + new (ptr) ::apollo::common::monitor::MonitorMessage(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::monitor::MonitorMessage::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_MonitorMessage = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsMonitorMessage}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base, + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::scc_info_MonitorMessageItem.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_MonitorMessageItem.base); + ::google::protobuf::internal::InitSCC(&scc_info_MonitorMessage.base); +} + +::google::protobuf::Metadata file_level_metadata[2]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[2]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::monitor::MonitorMessageItem, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::monitor::MonitorMessageItem, source_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::monitor::MonitorMessageItem, msg_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::monitor::MonitorMessageItem, log_level_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::monitor::MonitorMessage, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::monitor::MonitorMessage, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::monitor::MonitorMessage, item_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::common::monitor::MonitorMessageItem)}, + { 8, -1, sizeof(::apollo::common::monitor::MonitorMessage)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::common::monitor::_MonitorMessageItem_default_instance_), + reinterpret_cast(&::apollo::common::monitor::_MonitorMessage_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/common/monitor.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 2); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n&apollo_msgs/proto/common/monitor.proto" + "\022\025apollo.common.monitor\032%apollo_msgs/pro" + "to/common/header.proto\"\367\002\n\022MonitorMessag" + "eItem\022G\n\006source\030\001 \001(\01627.apollo.common.mo" + "nitor.MonitorMessageItem.MessageSource\022\013" + "\n\003msg\030\002 \001(\t\022E\n\tlog_level\030\003 \001(\01622.apollo." + "common.monitor.MonitorMessageItem.LogLev" + "el\"\215\001\n\rMessageSource\022\013\n\007UNKNOWN\020\000\022\n\n\006CAN" + "BUS\020\001\022\013\n\007CONTROL\020\002\022\014\n\010DECISION\020\003\022\020\n\014LOCA" + "LIZATION\020\004\022\014\n\010PLANNING\020\005\022\016\n\nPREDICTION\020\006" + "\022\r\n\tSIMULATOR\020\007\022\t\n\005HWSYS\020\010\"4\n\010LogLevel\022\010" + "\n\004INFO\020\000\022\010\n\004WARN\020\001\022\t\n\005ERROR\020\002\022\t\n\005FATAL\020\003" + "\"p\n\016MonitorMessage\022%\n\006header\030\001 \001(\0132\025.apo" + "llo.common.Header\0227\n\004item\030\002 \003(\0132).apollo" + ".common.monitor.MonitorMessageItemb\006prot" + "o3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 602); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/common/monitor.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto +namespace apollo { +namespace common { +namespace monitor { +const ::google::protobuf::EnumDescriptor* MonitorMessageItem_MessageSource_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::file_level_enum_descriptors[0]; +} +bool MonitorMessageItem_MessageSource_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + case 6: + case 7: + case 8: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const MonitorMessageItem_MessageSource MonitorMessageItem::UNKNOWN; +const MonitorMessageItem_MessageSource MonitorMessageItem::CANBUS; +const MonitorMessageItem_MessageSource MonitorMessageItem::CONTROL; +const MonitorMessageItem_MessageSource MonitorMessageItem::DECISION; +const MonitorMessageItem_MessageSource MonitorMessageItem::LOCALIZATION; +const MonitorMessageItem_MessageSource MonitorMessageItem::PLANNING; +const MonitorMessageItem_MessageSource MonitorMessageItem::PREDICTION; +const MonitorMessageItem_MessageSource MonitorMessageItem::SIMULATOR; +const MonitorMessageItem_MessageSource MonitorMessageItem::HWSYS; +const MonitorMessageItem_MessageSource MonitorMessageItem::MessageSource_MIN; +const MonitorMessageItem_MessageSource MonitorMessageItem::MessageSource_MAX; +const int MonitorMessageItem::MessageSource_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* MonitorMessageItem_LogLevel_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::file_level_enum_descriptors[1]; +} +bool MonitorMessageItem_LogLevel_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const MonitorMessageItem_LogLevel MonitorMessageItem::INFO; +const MonitorMessageItem_LogLevel MonitorMessageItem::WARN; +const MonitorMessageItem_LogLevel MonitorMessageItem::ERROR; +const MonitorMessageItem_LogLevel MonitorMessageItem::FATAL; +const MonitorMessageItem_LogLevel MonitorMessageItem::LogLevel_MIN; +const MonitorMessageItem_LogLevel MonitorMessageItem::LogLevel_MAX; +const int MonitorMessageItem::LogLevel_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +// =================================================================== + +void MonitorMessageItem::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int MonitorMessageItem::kSourceFieldNumber; +const int MonitorMessageItem::kMsgFieldNumber; +const int MonitorMessageItem::kLogLevelFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +MonitorMessageItem::MonitorMessageItem() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::scc_info_MonitorMessageItem.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.monitor.MonitorMessageItem) +} +MonitorMessageItem::MonitorMessageItem(const MonitorMessageItem& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + msg_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.msg().size() > 0) { + msg_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.msg_); + } + ::memcpy(&source_, &from.source_, + static_cast(reinterpret_cast(&log_level_) - + reinterpret_cast(&source_)) + sizeof(log_level_)); + // @@protoc_insertion_point(copy_constructor:apollo.common.monitor.MonitorMessageItem) +} + +void MonitorMessageItem::SharedCtor() { + msg_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&source_, 0, static_cast( + reinterpret_cast(&log_level_) - + reinterpret_cast(&source_)) + sizeof(log_level_)); +} + +MonitorMessageItem::~MonitorMessageItem() { + // @@protoc_insertion_point(destructor:apollo.common.monitor.MonitorMessageItem) + SharedDtor(); +} + +void MonitorMessageItem::SharedDtor() { + msg_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + +void MonitorMessageItem::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* MonitorMessageItem::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const MonitorMessageItem& MonitorMessageItem::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::scc_info_MonitorMessageItem.base); + return *internal_default_instance(); +} + + +void MonitorMessageItem::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.monitor.MonitorMessageItem) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + msg_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&source_, 0, static_cast( + reinterpret_cast(&log_level_) - + reinterpret_cast(&source_)) + sizeof(log_level_)); + _internal_metadata_.Clear(); +} + +bool MonitorMessageItem::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.monitor.MonitorMessageItem) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.monitor.MonitorMessageItem.MessageSource source = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_source(static_cast< ::apollo::common::monitor::MonitorMessageItem_MessageSource >(value)); + } else { + goto handle_unusual; + } + break; + } + + // string msg = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_msg())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->msg().data(), static_cast(this->msg().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.common.monitor.MonitorMessageItem.msg")); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.monitor.MonitorMessageItem.LogLevel log_level = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_log_level(static_cast< ::apollo::common::monitor::MonitorMessageItem_LogLevel >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.monitor.MonitorMessageItem) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.monitor.MonitorMessageItem) + return false; +#undef DO_ +} + +void MonitorMessageItem::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.monitor.MonitorMessageItem) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.monitor.MonitorMessageItem.MessageSource source = 1; + if (this->source() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->source(), output); + } + + // string msg = 2; + if (this->msg().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->msg().data(), static_cast(this->msg().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.common.monitor.MonitorMessageItem.msg"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 2, this->msg(), output); + } + + // .apollo.common.monitor.MonitorMessageItem.LogLevel log_level = 3; + if (this->log_level() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 3, this->log_level(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.monitor.MonitorMessageItem) +} + +::google::protobuf::uint8* MonitorMessageItem::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.monitor.MonitorMessageItem) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.monitor.MonitorMessageItem.MessageSource source = 1; + if (this->source() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->source(), target); + } + + // string msg = 2; + if (this->msg().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->msg().data(), static_cast(this->msg().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.common.monitor.MonitorMessageItem.msg"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 2, this->msg(), target); + } + + // .apollo.common.monitor.MonitorMessageItem.LogLevel log_level = 3; + if (this->log_level() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 3, this->log_level(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.monitor.MonitorMessageItem) + return target; +} + +size_t MonitorMessageItem::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.monitor.MonitorMessageItem) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // string msg = 2; + if (this->msg().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->msg()); + } + + // .apollo.common.monitor.MonitorMessageItem.MessageSource source = 1; + if (this->source() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->source()); + } + + // .apollo.common.monitor.MonitorMessageItem.LogLevel log_level = 3; + if (this->log_level() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->log_level()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void MonitorMessageItem::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.monitor.MonitorMessageItem) + GOOGLE_DCHECK_NE(&from, this); + const MonitorMessageItem* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.monitor.MonitorMessageItem) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.monitor.MonitorMessageItem) + MergeFrom(*source); + } +} + +void MonitorMessageItem::MergeFrom(const MonitorMessageItem& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.monitor.MonitorMessageItem) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.msg().size() > 0) { + + msg_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.msg_); + } + if (from.source() != 0) { + set_source(from.source()); + } + if (from.log_level() != 0) { + set_log_level(from.log_level()); + } +} + +void MonitorMessageItem::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.monitor.MonitorMessageItem) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void MonitorMessageItem::CopyFrom(const MonitorMessageItem& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.monitor.MonitorMessageItem) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool MonitorMessageItem::IsInitialized() const { + return true; +} + +void MonitorMessageItem::Swap(MonitorMessageItem* other) { + if (other == this) return; + InternalSwap(other); +} +void MonitorMessageItem::InternalSwap(MonitorMessageItem* other) { + using std::swap; + msg_.Swap(&other->msg_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(source_, other->source_); + swap(log_level_, other->log_level_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata MonitorMessageItem::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void MonitorMessage::InitAsDefaultInstance() { + ::apollo::common::monitor::_MonitorMessage_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); +} +void MonitorMessage::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int MonitorMessage::kHeaderFieldNumber; +const int MonitorMessage::kItemFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +MonitorMessage::MonitorMessage() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::scc_info_MonitorMessage.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.monitor.MonitorMessage) +} +MonitorMessage::MonitorMessage(const MonitorMessage& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + item_(from.item_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.common.monitor.MonitorMessage) +} + +void MonitorMessage::SharedCtor() { + header_ = NULL; +} + +MonitorMessage::~MonitorMessage() { + // @@protoc_insertion_point(destructor:apollo.common.monitor.MonitorMessage) + SharedDtor(); +} + +void MonitorMessage::SharedDtor() { + if (this != internal_default_instance()) delete header_; +} + +void MonitorMessage::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* MonitorMessage::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const MonitorMessage& MonitorMessage::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::scc_info_MonitorMessage.base); + return *internal_default_instance(); +} + + +void MonitorMessage::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.monitor.MonitorMessage) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + item_.Clear(); + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + _internal_metadata_.Clear(); +} + +bool MonitorMessage::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.monitor.MonitorMessage) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.common.monitor.MonitorMessageItem item = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_item())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.monitor.MonitorMessage) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.monitor.MonitorMessage) + return false; +#undef DO_ +} + +void MonitorMessage::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.monitor.MonitorMessage) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // repeated .apollo.common.monitor.MonitorMessageItem item = 2; + for (unsigned int i = 0, + n = static_cast(this->item_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, + this->item(static_cast(i)), + output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.monitor.MonitorMessage) +} + +::google::protobuf::uint8* MonitorMessage::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.monitor.MonitorMessage) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // repeated .apollo.common.monitor.MonitorMessageItem item = 2; + for (unsigned int i = 0, + n = static_cast(this->item_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->item(static_cast(i)), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.monitor.MonitorMessage) + return target; +} + +size_t MonitorMessage::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.monitor.MonitorMessage) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.common.monitor.MonitorMessageItem item = 2; + { + unsigned int count = static_cast(this->item_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->item(static_cast(i))); + } + } + + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void MonitorMessage::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.monitor.MonitorMessage) + GOOGLE_DCHECK_NE(&from, this); + const MonitorMessage* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.monitor.MonitorMessage) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.monitor.MonitorMessage) + MergeFrom(*source); + } +} + +void MonitorMessage::MergeFrom(const MonitorMessage& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.monitor.MonitorMessage) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + item_.MergeFrom(from.item_); + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } +} + +void MonitorMessage::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.monitor.MonitorMessage) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void MonitorMessage::CopyFrom(const MonitorMessage& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.monitor.MonitorMessage) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool MonitorMessage::IsInitialized() const { + return true; +} + +void MonitorMessage::Swap(MonitorMessage* other) { + if (other == this) return; + InternalSwap(other); +} +void MonitorMessage::InternalSwap(MonitorMessage* other) { + using std::swap; + CastToBase(&item_)->InternalSwap(CastToBase(&other->item_)); + swap(header_, other->header_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata MonitorMessage::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace monitor +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::monitor::MonitorMessageItem* Arena::CreateMaybeMessage< ::apollo::common::monitor::MonitorMessageItem >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::monitor::MonitorMessageItem >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::monitor::MonitorMessage* Arena::CreateMaybeMessage< ::apollo::common::monitor::MonitorMessage >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::monitor::MonitorMessage >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/common/monitor.pb.h b/apollo_msgs/include/apollo_msgs/proto/common/monitor.pb.h new file mode 100644 index 0000000..a482b13 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/monitor.pb.h @@ -0,0 +1,645 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/monitor.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "apollo_msgs/proto/common/header.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[2]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto +namespace apollo { +namespace common { +namespace monitor { +class MonitorMessage; +class MonitorMessageDefaultTypeInternal; +extern MonitorMessageDefaultTypeInternal _MonitorMessage_default_instance_; +class MonitorMessageItem; +class MonitorMessageItemDefaultTypeInternal; +extern MonitorMessageItemDefaultTypeInternal _MonitorMessageItem_default_instance_; +} // namespace monitor +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::common::monitor::MonitorMessage* Arena::CreateMaybeMessage<::apollo::common::monitor::MonitorMessage>(Arena*); +template<> ::apollo::common::monitor::MonitorMessageItem* Arena::CreateMaybeMessage<::apollo::common::monitor::MonitorMessageItem>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace common { +namespace monitor { + +enum MonitorMessageItem_MessageSource { + MonitorMessageItem_MessageSource_UNKNOWN = 0, + MonitorMessageItem_MessageSource_CANBUS = 1, + MonitorMessageItem_MessageSource_CONTROL = 2, + MonitorMessageItem_MessageSource_DECISION = 3, + MonitorMessageItem_MessageSource_LOCALIZATION = 4, + MonitorMessageItem_MessageSource_PLANNING = 5, + MonitorMessageItem_MessageSource_PREDICTION = 6, + MonitorMessageItem_MessageSource_SIMULATOR = 7, + MonitorMessageItem_MessageSource_HWSYS = 8, + MonitorMessageItem_MessageSource_MonitorMessageItem_MessageSource_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + MonitorMessageItem_MessageSource_MonitorMessageItem_MessageSource_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool MonitorMessageItem_MessageSource_IsValid(int value); +const MonitorMessageItem_MessageSource MonitorMessageItem_MessageSource_MessageSource_MIN = MonitorMessageItem_MessageSource_UNKNOWN; +const MonitorMessageItem_MessageSource MonitorMessageItem_MessageSource_MessageSource_MAX = MonitorMessageItem_MessageSource_HWSYS; +const int MonitorMessageItem_MessageSource_MessageSource_ARRAYSIZE = MonitorMessageItem_MessageSource_MessageSource_MAX + 1; + +const ::google::protobuf::EnumDescriptor* MonitorMessageItem_MessageSource_descriptor(); +inline const ::std::string& MonitorMessageItem_MessageSource_Name(MonitorMessageItem_MessageSource value) { + return ::google::protobuf::internal::NameOfEnum( + MonitorMessageItem_MessageSource_descriptor(), value); +} +inline bool MonitorMessageItem_MessageSource_Parse( + const ::std::string& name, MonitorMessageItem_MessageSource* value) { + return ::google::protobuf::internal::ParseNamedEnum( + MonitorMessageItem_MessageSource_descriptor(), name, value); +} +enum MonitorMessageItem_LogLevel { + MonitorMessageItem_LogLevel_INFO = 0, + MonitorMessageItem_LogLevel_WARN = 1, + MonitorMessageItem_LogLevel_ERROR = 2, + MonitorMessageItem_LogLevel_FATAL = 3, + MonitorMessageItem_LogLevel_MonitorMessageItem_LogLevel_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + MonitorMessageItem_LogLevel_MonitorMessageItem_LogLevel_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool MonitorMessageItem_LogLevel_IsValid(int value); +const MonitorMessageItem_LogLevel MonitorMessageItem_LogLevel_LogLevel_MIN = MonitorMessageItem_LogLevel_INFO; +const MonitorMessageItem_LogLevel MonitorMessageItem_LogLevel_LogLevel_MAX = MonitorMessageItem_LogLevel_FATAL; +const int MonitorMessageItem_LogLevel_LogLevel_ARRAYSIZE = MonitorMessageItem_LogLevel_LogLevel_MAX + 1; + +const ::google::protobuf::EnumDescriptor* MonitorMessageItem_LogLevel_descriptor(); +inline const ::std::string& MonitorMessageItem_LogLevel_Name(MonitorMessageItem_LogLevel value) { + return ::google::protobuf::internal::NameOfEnum( + MonitorMessageItem_LogLevel_descriptor(), value); +} +inline bool MonitorMessageItem_LogLevel_Parse( + const ::std::string& name, MonitorMessageItem_LogLevel* value) { + return ::google::protobuf::internal::ParseNamedEnum( + MonitorMessageItem_LogLevel_descriptor(), name, value); +} +// =================================================================== + +class MonitorMessageItem : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.monitor.MonitorMessageItem) */ { + public: + MonitorMessageItem(); + virtual ~MonitorMessageItem(); + + MonitorMessageItem(const MonitorMessageItem& from); + + inline MonitorMessageItem& operator=(const MonitorMessageItem& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + MonitorMessageItem(MonitorMessageItem&& from) noexcept + : MonitorMessageItem() { + *this = ::std::move(from); + } + + inline MonitorMessageItem& operator=(MonitorMessageItem&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const MonitorMessageItem& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const MonitorMessageItem* internal_default_instance() { + return reinterpret_cast( + &_MonitorMessageItem_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(MonitorMessageItem* other); + friend void swap(MonitorMessageItem& a, MonitorMessageItem& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline MonitorMessageItem* New() const final { + return CreateMaybeMessage(NULL); + } + + MonitorMessageItem* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const MonitorMessageItem& from); + void MergeFrom(const MonitorMessageItem& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(MonitorMessageItem* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef MonitorMessageItem_MessageSource MessageSource; + static const MessageSource UNKNOWN = + MonitorMessageItem_MessageSource_UNKNOWN; + static const MessageSource CANBUS = + MonitorMessageItem_MessageSource_CANBUS; + static const MessageSource CONTROL = + MonitorMessageItem_MessageSource_CONTROL; + static const MessageSource DECISION = + MonitorMessageItem_MessageSource_DECISION; + static const MessageSource LOCALIZATION = + MonitorMessageItem_MessageSource_LOCALIZATION; + static const MessageSource PLANNING = + MonitorMessageItem_MessageSource_PLANNING; + static const MessageSource PREDICTION = + MonitorMessageItem_MessageSource_PREDICTION; + static const MessageSource SIMULATOR = + MonitorMessageItem_MessageSource_SIMULATOR; + static const MessageSource HWSYS = + MonitorMessageItem_MessageSource_HWSYS; + static inline bool MessageSource_IsValid(int value) { + return MonitorMessageItem_MessageSource_IsValid(value); + } + static const MessageSource MessageSource_MIN = + MonitorMessageItem_MessageSource_MessageSource_MIN; + static const MessageSource MessageSource_MAX = + MonitorMessageItem_MessageSource_MessageSource_MAX; + static const int MessageSource_ARRAYSIZE = + MonitorMessageItem_MessageSource_MessageSource_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + MessageSource_descriptor() { + return MonitorMessageItem_MessageSource_descriptor(); + } + static inline const ::std::string& MessageSource_Name(MessageSource value) { + return MonitorMessageItem_MessageSource_Name(value); + } + static inline bool MessageSource_Parse(const ::std::string& name, + MessageSource* value) { + return MonitorMessageItem_MessageSource_Parse(name, value); + } + + typedef MonitorMessageItem_LogLevel LogLevel; + static const LogLevel INFO = + MonitorMessageItem_LogLevel_INFO; + static const LogLevel WARN = + MonitorMessageItem_LogLevel_WARN; + static const LogLevel ERROR = + MonitorMessageItem_LogLevel_ERROR; + static const LogLevel FATAL = + MonitorMessageItem_LogLevel_FATAL; + static inline bool LogLevel_IsValid(int value) { + return MonitorMessageItem_LogLevel_IsValid(value); + } + static const LogLevel LogLevel_MIN = + MonitorMessageItem_LogLevel_LogLevel_MIN; + static const LogLevel LogLevel_MAX = + MonitorMessageItem_LogLevel_LogLevel_MAX; + static const int LogLevel_ARRAYSIZE = + MonitorMessageItem_LogLevel_LogLevel_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + LogLevel_descriptor() { + return MonitorMessageItem_LogLevel_descriptor(); + } + static inline const ::std::string& LogLevel_Name(LogLevel value) { + return MonitorMessageItem_LogLevel_Name(value); + } + static inline bool LogLevel_Parse(const ::std::string& name, + LogLevel* value) { + return MonitorMessageItem_LogLevel_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // string msg = 2; + void clear_msg(); + static const int kMsgFieldNumber = 2; + const ::std::string& msg() const; + void set_msg(const ::std::string& value); + #if LANG_CXX11 + void set_msg(::std::string&& value); + #endif + void set_msg(const char* value); + void set_msg(const char* value, size_t size); + ::std::string* mutable_msg(); + ::std::string* release_msg(); + void set_allocated_msg(::std::string* msg); + + // .apollo.common.monitor.MonitorMessageItem.MessageSource source = 1; + void clear_source(); + static const int kSourceFieldNumber = 1; + ::apollo::common::monitor::MonitorMessageItem_MessageSource source() const; + void set_source(::apollo::common::monitor::MonitorMessageItem_MessageSource value); + + // .apollo.common.monitor.MonitorMessageItem.LogLevel log_level = 3; + void clear_log_level(); + static const int kLogLevelFieldNumber = 3; + ::apollo::common::monitor::MonitorMessageItem_LogLevel log_level() const; + void set_log_level(::apollo::common::monitor::MonitorMessageItem_LogLevel value); + + // @@protoc_insertion_point(class_scope:apollo.common.monitor.MonitorMessageItem) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr msg_; + int source_; + int log_level_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class MonitorMessage : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.monitor.MonitorMessage) */ { + public: + MonitorMessage(); + virtual ~MonitorMessage(); + + MonitorMessage(const MonitorMessage& from); + + inline MonitorMessage& operator=(const MonitorMessage& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + MonitorMessage(MonitorMessage&& from) noexcept + : MonitorMessage() { + *this = ::std::move(from); + } + + inline MonitorMessage& operator=(MonitorMessage&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const MonitorMessage& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const MonitorMessage* internal_default_instance() { + return reinterpret_cast( + &_MonitorMessage_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(MonitorMessage* other); + friend void swap(MonitorMessage& a, MonitorMessage& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline MonitorMessage* New() const final { + return CreateMaybeMessage(NULL); + } + + MonitorMessage* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const MonitorMessage& from); + void MergeFrom(const MonitorMessage& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(MonitorMessage* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.common.monitor.MonitorMessageItem item = 2; + int item_size() const; + void clear_item(); + static const int kItemFieldNumber = 2; + ::apollo::common::monitor::MonitorMessageItem* mutable_item(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::common::monitor::MonitorMessageItem >* + mutable_item(); + const ::apollo::common::monitor::MonitorMessageItem& item(int index) const; + ::apollo::common::monitor::MonitorMessageItem* add_item(); + const ::google::protobuf::RepeatedPtrField< ::apollo::common::monitor::MonitorMessageItem >& + item() const; + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // @@protoc_insertion_point(class_scope:apollo.common.monitor.MonitorMessage) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::common::monitor::MonitorMessageItem > item_; + ::apollo::common::Header* header_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// MonitorMessageItem + +// .apollo.common.monitor.MonitorMessageItem.MessageSource source = 1; +inline void MonitorMessageItem::clear_source() { + source_ = 0; +} +inline ::apollo::common::monitor::MonitorMessageItem_MessageSource MonitorMessageItem::source() const { + // @@protoc_insertion_point(field_get:apollo.common.monitor.MonitorMessageItem.source) + return static_cast< ::apollo::common::monitor::MonitorMessageItem_MessageSource >(source_); +} +inline void MonitorMessageItem::set_source(::apollo::common::monitor::MonitorMessageItem_MessageSource value) { + + source_ = value; + // @@protoc_insertion_point(field_set:apollo.common.monitor.MonitorMessageItem.source) +} + +// string msg = 2; +inline void MonitorMessageItem::clear_msg() { + msg_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& MonitorMessageItem::msg() const { + // @@protoc_insertion_point(field_get:apollo.common.monitor.MonitorMessageItem.msg) + return msg_.GetNoArena(); +} +inline void MonitorMessageItem::set_msg(const ::std::string& value) { + + msg_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.common.monitor.MonitorMessageItem.msg) +} +#if LANG_CXX11 +inline void MonitorMessageItem::set_msg(::std::string&& value) { + + msg_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.common.monitor.MonitorMessageItem.msg) +} +#endif +inline void MonitorMessageItem::set_msg(const char* value) { + GOOGLE_DCHECK(value != NULL); + + msg_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.common.monitor.MonitorMessageItem.msg) +} +inline void MonitorMessageItem::set_msg(const char* value, size_t size) { + + msg_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.common.monitor.MonitorMessageItem.msg) +} +inline ::std::string* MonitorMessageItem::mutable_msg() { + + // @@protoc_insertion_point(field_mutable:apollo.common.monitor.MonitorMessageItem.msg) + return msg_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* MonitorMessageItem::release_msg() { + // @@protoc_insertion_point(field_release:apollo.common.monitor.MonitorMessageItem.msg) + + return msg_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void MonitorMessageItem::set_allocated_msg(::std::string* msg) { + if (msg != NULL) { + + } else { + + } + msg_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), msg); + // @@protoc_insertion_point(field_set_allocated:apollo.common.monitor.MonitorMessageItem.msg) +} + +// .apollo.common.monitor.MonitorMessageItem.LogLevel log_level = 3; +inline void MonitorMessageItem::clear_log_level() { + log_level_ = 0; +} +inline ::apollo::common::monitor::MonitorMessageItem_LogLevel MonitorMessageItem::log_level() const { + // @@protoc_insertion_point(field_get:apollo.common.monitor.MonitorMessageItem.log_level) + return static_cast< ::apollo::common::monitor::MonitorMessageItem_LogLevel >(log_level_); +} +inline void MonitorMessageItem::set_log_level(::apollo::common::monitor::MonitorMessageItem_LogLevel value) { + + log_level_ = value; + // @@protoc_insertion_point(field_set:apollo.common.monitor.MonitorMessageItem.log_level) +} + +// ------------------------------------------------------------------- + +// MonitorMessage + +// .apollo.common.Header header = 1; +inline bool MonitorMessage::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& MonitorMessage::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& MonitorMessage::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.common.monitor.MonitorMessage.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* MonitorMessage::release_header() { + // @@protoc_insertion_point(field_release:apollo.common.monitor.MonitorMessage.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* MonitorMessage::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.common.monitor.MonitorMessage.header) + return header_; +} +inline void MonitorMessage::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.common.monitor.MonitorMessage.header) +} + +// repeated .apollo.common.monitor.MonitorMessageItem item = 2; +inline int MonitorMessage::item_size() const { + return item_.size(); +} +inline void MonitorMessage::clear_item() { + item_.Clear(); +} +inline ::apollo::common::monitor::MonitorMessageItem* MonitorMessage::mutable_item(int index) { + // @@protoc_insertion_point(field_mutable:apollo.common.monitor.MonitorMessage.item) + return item_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::common::monitor::MonitorMessageItem >* +MonitorMessage::mutable_item() { + // @@protoc_insertion_point(field_mutable_list:apollo.common.monitor.MonitorMessage.item) + return &item_; +} +inline const ::apollo::common::monitor::MonitorMessageItem& MonitorMessage::item(int index) const { + // @@protoc_insertion_point(field_get:apollo.common.monitor.MonitorMessage.item) + return item_.Get(index); +} +inline ::apollo::common::monitor::MonitorMessageItem* MonitorMessage::add_item() { + // @@protoc_insertion_point(field_add:apollo.common.monitor.MonitorMessage.item) + return item_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::common::monitor::MonitorMessageItem >& +MonitorMessage::item() const { + // @@protoc_insertion_point(field_list:apollo.common.monitor.MonitorMessage.item) + return item_; +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace monitor +} // namespace common +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::common::monitor::MonitorMessageItem_MessageSource> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::common::monitor::MonitorMessageItem_MessageSource>() { + return ::apollo::common::monitor::MonitorMessageItem_MessageSource_descriptor(); +} +template <> struct is_proto_enum< ::apollo::common::monitor::MonitorMessageItem_LogLevel> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::common::monitor::MonitorMessageItem_LogLevel>() { + return ::apollo::common::monitor::MonitorMessageItem_LogLevel_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fmonitor_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/common/vehicle_config.pb.cc b/apollo_msgs/include/apollo_msgs/proto/common/vehicle_config.pb.cc new file mode 100644 index 0000000..7aeb113 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/vehicle_config.pb.cc @@ -0,0 +1,1254 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/vehicle_config.proto + +#include "apollo_msgs/proto/common/vehicle_config.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Extrinsics; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_VehicleParam; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto +namespace apollo { +namespace common { +namespace config { +class VehicleParamDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _VehicleParam_default_instance_; +class VehicleConfigDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _VehicleConfig_default_instance_; +} // namespace config +} // namespace common +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto { +static void InitDefaultsVehicleParam() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::config::_VehicleParam_default_instance_; + new (ptr) ::apollo::common::config::VehicleParam(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::config::VehicleParam::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_VehicleParam = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsVehicleParam}, {}}; + +static void InitDefaultsVehicleConfig() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::common::config::_VehicleConfig_default_instance_; + new (ptr) ::apollo::common::config::VehicleConfig(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::common::config::VehicleConfig::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<3> scc_info_VehicleConfig = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 3, InitDefaultsVehicleConfig}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base, + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::scc_info_VehicleParam.base, + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::scc_info_Extrinsics.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_VehicleParam.base); + ::google::protobuf::internal::InitSCC(&scc_info_VehicleConfig.base); +} + +::google::protobuf::Metadata file_level_metadata[2]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, front_edge_to_center_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, back_edge_to_center_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, left_edge_to_center_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, right_edge_to_center_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, length_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, width_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, height_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, min_turn_radius_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, max_acceleration_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, max_deceleration_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, max_steer_angle_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, max_steer_angle_rate_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, steer_ratio_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, wheel_base_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleParam, wheel_rolling_radius_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleConfig, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleConfig, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleConfig, vehicle_param_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::common::config::VehicleConfig, extrinsics_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::common::config::VehicleParam)}, + { 20, -1, sizeof(::apollo::common::config::VehicleConfig)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::common::config::_VehicleParam_default_instance_), + reinterpret_cast(&::apollo::common::config::_VehicleConfig_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/common/vehicle_config.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 2); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n-apollo_msgs/proto/common/vehicle_confi" + "g.proto\022\024apollo.common.config\032%apollo_ms" + "gs/proto/common/header.proto\0320apollo_msg" + "s/proto/common/config_extrinsics.proto\"\376" + "\002\n\014VehicleParam\022\034\n\024front_edge_to_center\030" + "\001 \001(\001\022\033\n\023back_edge_to_center\030\002 \001(\001\022\033\n\023le" + "ft_edge_to_center\030\003 \001(\001\022\034\n\024right_edge_to" + "_center\030\004 \001(\001\022\016\n\006length\030\005 \001(\001\022\r\n\005width\030\006" + " \001(\001\022\016\n\006height\030\007 \001(\001\022\027\n\017min_turn_radius\030" + "\010 \001(\001\022\030\n\020max_acceleration\030\t \001(\001\022\030\n\020max_d" + "eceleration\030\n \001(\001\022\027\n\017max_steer_angle\030\013 \001" + "(\001\022\034\n\024max_steer_angle_rate\030\014 \001(\001\022\023\n\013stee" + "r_ratio\030\r \001(\001\022\022\n\nwheel_base\030\016 \001(\001\022\034\n\024whe" + "el_rolling_radius\030\017 \001(\001\"\247\001\n\rVehicleConfi" + "g\022%\n\006header\030\001 \001(\0132\025.apollo.common.Header" + "\0229\n\rvehicle_param\030\002 \001(\0132\".apollo.common." + "config.VehicleParam\0224\n\nextrinsics\030\003 \001(\0132" + " .apollo.common.config.Extrinsicsb\006proto" + "3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 721); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/common/vehicle_config.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fconfig_5fextrinsics_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto +namespace apollo { +namespace common { +namespace config { + +// =================================================================== + +void VehicleParam::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int VehicleParam::kFrontEdgeToCenterFieldNumber; +const int VehicleParam::kBackEdgeToCenterFieldNumber; +const int VehicleParam::kLeftEdgeToCenterFieldNumber; +const int VehicleParam::kRightEdgeToCenterFieldNumber; +const int VehicleParam::kLengthFieldNumber; +const int VehicleParam::kWidthFieldNumber; +const int VehicleParam::kHeightFieldNumber; +const int VehicleParam::kMinTurnRadiusFieldNumber; +const int VehicleParam::kMaxAccelerationFieldNumber; +const int VehicleParam::kMaxDecelerationFieldNumber; +const int VehicleParam::kMaxSteerAngleFieldNumber; +const int VehicleParam::kMaxSteerAngleRateFieldNumber; +const int VehicleParam::kSteerRatioFieldNumber; +const int VehicleParam::kWheelBaseFieldNumber; +const int VehicleParam::kWheelRollingRadiusFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +VehicleParam::VehicleParam() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::scc_info_VehicleParam.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.config.VehicleParam) +} +VehicleParam::VehicleParam(const VehicleParam& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&front_edge_to_center_, &from.front_edge_to_center_, + static_cast(reinterpret_cast(&wheel_rolling_radius_) - + reinterpret_cast(&front_edge_to_center_)) + sizeof(wheel_rolling_radius_)); + // @@protoc_insertion_point(copy_constructor:apollo.common.config.VehicleParam) +} + +void VehicleParam::SharedCtor() { + ::memset(&front_edge_to_center_, 0, static_cast( + reinterpret_cast(&wheel_rolling_radius_) - + reinterpret_cast(&front_edge_to_center_)) + sizeof(wheel_rolling_radius_)); +} + +VehicleParam::~VehicleParam() { + // @@protoc_insertion_point(destructor:apollo.common.config.VehicleParam) + SharedDtor(); +} + +void VehicleParam::SharedDtor() { +} + +void VehicleParam::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* VehicleParam::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const VehicleParam& VehicleParam::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::scc_info_VehicleParam.base); + return *internal_default_instance(); +} + + +void VehicleParam::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.config.VehicleParam) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&front_edge_to_center_, 0, static_cast( + reinterpret_cast(&wheel_rolling_radius_) - + reinterpret_cast(&front_edge_to_center_)) + sizeof(wheel_rolling_radius_)); + _internal_metadata_.Clear(); +} + +bool VehicleParam::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.config.VehicleParam) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double front_edge_to_center = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &front_edge_to_center_))); + } else { + goto handle_unusual; + } + break; + } + + // double back_edge_to_center = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &back_edge_to_center_))); + } else { + goto handle_unusual; + } + break; + } + + // double left_edge_to_center = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &left_edge_to_center_))); + } else { + goto handle_unusual; + } + break; + } + + // double right_edge_to_center = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &right_edge_to_center_))); + } else { + goto handle_unusual; + } + break; + } + + // double length = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &length_))); + } else { + goto handle_unusual; + } + break; + } + + // double width = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &width_))); + } else { + goto handle_unusual; + } + break; + } + + // double height = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &height_))); + } else { + goto handle_unusual; + } + break; + } + + // double min_turn_radius = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(65u /* 65 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &min_turn_radius_))); + } else { + goto handle_unusual; + } + break; + } + + // double max_acceleration = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(73u /* 73 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &max_acceleration_))); + } else { + goto handle_unusual; + } + break; + } + + // double max_deceleration = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(81u /* 81 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &max_deceleration_))); + } else { + goto handle_unusual; + } + break; + } + + // double max_steer_angle = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(89u /* 89 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &max_steer_angle_))); + } else { + goto handle_unusual; + } + break; + } + + // double max_steer_angle_rate = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(97u /* 97 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &max_steer_angle_rate_))); + } else { + goto handle_unusual; + } + break; + } + + // double steer_ratio = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(105u /* 105 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steer_ratio_))); + } else { + goto handle_unusual; + } + break; + } + + // double wheel_base = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(113u /* 113 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &wheel_base_))); + } else { + goto handle_unusual; + } + break; + } + + // double wheel_rolling_radius = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(121u /* 121 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &wheel_rolling_radius_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.config.VehicleParam) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.config.VehicleParam) + return false; +#undef DO_ +} + +void VehicleParam::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.config.VehicleParam) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double front_edge_to_center = 1; + if (this->front_edge_to_center() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->front_edge_to_center(), output); + } + + // double back_edge_to_center = 2; + if (this->back_edge_to_center() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->back_edge_to_center(), output); + } + + // double left_edge_to_center = 3; + if (this->left_edge_to_center() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->left_edge_to_center(), output); + } + + // double right_edge_to_center = 4; + if (this->right_edge_to_center() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->right_edge_to_center(), output); + } + + // double length = 5; + if (this->length() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->length(), output); + } + + // double width = 6; + if (this->width() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->width(), output); + } + + // double height = 7; + if (this->height() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->height(), output); + } + + // double min_turn_radius = 8; + if (this->min_turn_radius() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(8, this->min_turn_radius(), output); + } + + // double max_acceleration = 9; + if (this->max_acceleration() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->max_acceleration(), output); + } + + // double max_deceleration = 10; + if (this->max_deceleration() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(10, this->max_deceleration(), output); + } + + // double max_steer_angle = 11; + if (this->max_steer_angle() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(11, this->max_steer_angle(), output); + } + + // double max_steer_angle_rate = 12; + if (this->max_steer_angle_rate() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(12, this->max_steer_angle_rate(), output); + } + + // double steer_ratio = 13; + if (this->steer_ratio() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(13, this->steer_ratio(), output); + } + + // double wheel_base = 14; + if (this->wheel_base() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(14, this->wheel_base(), output); + } + + // double wheel_rolling_radius = 15; + if (this->wheel_rolling_radius() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(15, this->wheel_rolling_radius(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.config.VehicleParam) +} + +::google::protobuf::uint8* VehicleParam::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.config.VehicleParam) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double front_edge_to_center = 1; + if (this->front_edge_to_center() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->front_edge_to_center(), target); + } + + // double back_edge_to_center = 2; + if (this->back_edge_to_center() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->back_edge_to_center(), target); + } + + // double left_edge_to_center = 3; + if (this->left_edge_to_center() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->left_edge_to_center(), target); + } + + // double right_edge_to_center = 4; + if (this->right_edge_to_center() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->right_edge_to_center(), target); + } + + // double length = 5; + if (this->length() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->length(), target); + } + + // double width = 6; + if (this->width() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->width(), target); + } + + // double height = 7; + if (this->height() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->height(), target); + } + + // double min_turn_radius = 8; + if (this->min_turn_radius() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(8, this->min_turn_radius(), target); + } + + // double max_acceleration = 9; + if (this->max_acceleration() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->max_acceleration(), target); + } + + // double max_deceleration = 10; + if (this->max_deceleration() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(10, this->max_deceleration(), target); + } + + // double max_steer_angle = 11; + if (this->max_steer_angle() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(11, this->max_steer_angle(), target); + } + + // double max_steer_angle_rate = 12; + if (this->max_steer_angle_rate() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(12, this->max_steer_angle_rate(), target); + } + + // double steer_ratio = 13; + if (this->steer_ratio() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(13, this->steer_ratio(), target); + } + + // double wheel_base = 14; + if (this->wheel_base() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(14, this->wheel_base(), target); + } + + // double wheel_rolling_radius = 15; + if (this->wheel_rolling_radius() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(15, this->wheel_rolling_radius(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.config.VehicleParam) + return target; +} + +size_t VehicleParam::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.config.VehicleParam) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double front_edge_to_center = 1; + if (this->front_edge_to_center() != 0) { + total_size += 1 + 8; + } + + // double back_edge_to_center = 2; + if (this->back_edge_to_center() != 0) { + total_size += 1 + 8; + } + + // double left_edge_to_center = 3; + if (this->left_edge_to_center() != 0) { + total_size += 1 + 8; + } + + // double right_edge_to_center = 4; + if (this->right_edge_to_center() != 0) { + total_size += 1 + 8; + } + + // double length = 5; + if (this->length() != 0) { + total_size += 1 + 8; + } + + // double width = 6; + if (this->width() != 0) { + total_size += 1 + 8; + } + + // double height = 7; + if (this->height() != 0) { + total_size += 1 + 8; + } + + // double min_turn_radius = 8; + if (this->min_turn_radius() != 0) { + total_size += 1 + 8; + } + + // double max_acceleration = 9; + if (this->max_acceleration() != 0) { + total_size += 1 + 8; + } + + // double max_deceleration = 10; + if (this->max_deceleration() != 0) { + total_size += 1 + 8; + } + + // double max_steer_angle = 11; + if (this->max_steer_angle() != 0) { + total_size += 1 + 8; + } + + // double max_steer_angle_rate = 12; + if (this->max_steer_angle_rate() != 0) { + total_size += 1 + 8; + } + + // double steer_ratio = 13; + if (this->steer_ratio() != 0) { + total_size += 1 + 8; + } + + // double wheel_base = 14; + if (this->wheel_base() != 0) { + total_size += 1 + 8; + } + + // double wheel_rolling_radius = 15; + if (this->wheel_rolling_radius() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void VehicleParam::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.config.VehicleParam) + GOOGLE_DCHECK_NE(&from, this); + const VehicleParam* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.config.VehicleParam) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.config.VehicleParam) + MergeFrom(*source); + } +} + +void VehicleParam::MergeFrom(const VehicleParam& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.config.VehicleParam) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.front_edge_to_center() != 0) { + set_front_edge_to_center(from.front_edge_to_center()); + } + if (from.back_edge_to_center() != 0) { + set_back_edge_to_center(from.back_edge_to_center()); + } + if (from.left_edge_to_center() != 0) { + set_left_edge_to_center(from.left_edge_to_center()); + } + if (from.right_edge_to_center() != 0) { + set_right_edge_to_center(from.right_edge_to_center()); + } + if (from.length() != 0) { + set_length(from.length()); + } + if (from.width() != 0) { + set_width(from.width()); + } + if (from.height() != 0) { + set_height(from.height()); + } + if (from.min_turn_radius() != 0) { + set_min_turn_radius(from.min_turn_radius()); + } + if (from.max_acceleration() != 0) { + set_max_acceleration(from.max_acceleration()); + } + if (from.max_deceleration() != 0) { + set_max_deceleration(from.max_deceleration()); + } + if (from.max_steer_angle() != 0) { + set_max_steer_angle(from.max_steer_angle()); + } + if (from.max_steer_angle_rate() != 0) { + set_max_steer_angle_rate(from.max_steer_angle_rate()); + } + if (from.steer_ratio() != 0) { + set_steer_ratio(from.steer_ratio()); + } + if (from.wheel_base() != 0) { + set_wheel_base(from.wheel_base()); + } + if (from.wheel_rolling_radius() != 0) { + set_wheel_rolling_radius(from.wheel_rolling_radius()); + } +} + +void VehicleParam::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.config.VehicleParam) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void VehicleParam::CopyFrom(const VehicleParam& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.config.VehicleParam) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool VehicleParam::IsInitialized() const { + return true; +} + +void VehicleParam::Swap(VehicleParam* other) { + if (other == this) return; + InternalSwap(other); +} +void VehicleParam::InternalSwap(VehicleParam* other) { + using std::swap; + swap(front_edge_to_center_, other->front_edge_to_center_); + swap(back_edge_to_center_, other->back_edge_to_center_); + swap(left_edge_to_center_, other->left_edge_to_center_); + swap(right_edge_to_center_, other->right_edge_to_center_); + swap(length_, other->length_); + swap(width_, other->width_); + swap(height_, other->height_); + swap(min_turn_radius_, other->min_turn_radius_); + swap(max_acceleration_, other->max_acceleration_); + swap(max_deceleration_, other->max_deceleration_); + swap(max_steer_angle_, other->max_steer_angle_); + swap(max_steer_angle_rate_, other->max_steer_angle_rate_); + swap(steer_ratio_, other->steer_ratio_); + swap(wheel_base_, other->wheel_base_); + swap(wheel_rolling_radius_, other->wheel_rolling_radius_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata VehicleParam::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void VehicleConfig::InitAsDefaultInstance() { + ::apollo::common::config::_VehicleConfig_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); + ::apollo::common::config::_VehicleConfig_default_instance_._instance.get_mutable()->vehicle_param_ = const_cast< ::apollo::common::config::VehicleParam*>( + ::apollo::common::config::VehicleParam::internal_default_instance()); + ::apollo::common::config::_VehicleConfig_default_instance_._instance.get_mutable()->extrinsics_ = const_cast< ::apollo::common::config::Extrinsics*>( + ::apollo::common::config::Extrinsics::internal_default_instance()); +} +void VehicleConfig::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +void VehicleConfig::clear_extrinsics() { + if (GetArenaNoVirtual() == NULL && extrinsics_ != NULL) { + delete extrinsics_; + } + extrinsics_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int VehicleConfig::kHeaderFieldNumber; +const int VehicleConfig::kVehicleParamFieldNumber; +const int VehicleConfig::kExtrinsicsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +VehicleConfig::VehicleConfig() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::scc_info_VehicleConfig.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.common.config.VehicleConfig) +} +VehicleConfig::VehicleConfig(const VehicleConfig& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + if (from.has_vehicle_param()) { + vehicle_param_ = new ::apollo::common::config::VehicleParam(*from.vehicle_param_); + } else { + vehicle_param_ = NULL; + } + if (from.has_extrinsics()) { + extrinsics_ = new ::apollo::common::config::Extrinsics(*from.extrinsics_); + } else { + extrinsics_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.common.config.VehicleConfig) +} + +void VehicleConfig::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&extrinsics_) - + reinterpret_cast(&header_)) + sizeof(extrinsics_)); +} + +VehicleConfig::~VehicleConfig() { + // @@protoc_insertion_point(destructor:apollo.common.config.VehicleConfig) + SharedDtor(); +} + +void VehicleConfig::SharedDtor() { + if (this != internal_default_instance()) delete header_; + if (this != internal_default_instance()) delete vehicle_param_; + if (this != internal_default_instance()) delete extrinsics_; +} + +void VehicleConfig::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* VehicleConfig::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const VehicleConfig& VehicleConfig::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::scc_info_VehicleConfig.base); + return *internal_default_instance(); +} + + +void VehicleConfig::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.common.config.VehicleConfig) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + if (GetArenaNoVirtual() == NULL && vehicle_param_ != NULL) { + delete vehicle_param_; + } + vehicle_param_ = NULL; + if (GetArenaNoVirtual() == NULL && extrinsics_ != NULL) { + delete extrinsics_; + } + extrinsics_ = NULL; + _internal_metadata_.Clear(); +} + +bool VehicleConfig::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.common.config.VehicleConfig) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.config.VehicleParam vehicle_param = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_vehicle_param())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.config.Extrinsics extrinsics = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_extrinsics())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.common.config.VehicleConfig) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.common.config.VehicleConfig) + return false; +#undef DO_ +} + +void VehicleConfig::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.common.config.VehicleConfig) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // .apollo.common.config.VehicleParam vehicle_param = 2; + if (this->has_vehicle_param()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_vehicle_param(), output); + } + + // .apollo.common.config.Extrinsics extrinsics = 3; + if (this->has_extrinsics()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_extrinsics(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.common.config.VehicleConfig) +} + +::google::protobuf::uint8* VehicleConfig::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.common.config.VehicleConfig) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // .apollo.common.config.VehicleParam vehicle_param = 2; + if (this->has_vehicle_param()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_vehicle_param(), deterministic, target); + } + + // .apollo.common.config.Extrinsics extrinsics = 3; + if (this->has_extrinsics()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_extrinsics(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.common.config.VehicleConfig) + return target; +} + +size_t VehicleConfig::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.common.config.VehicleConfig) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.common.config.VehicleParam vehicle_param = 2; + if (this->has_vehicle_param()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *vehicle_param_); + } + + // .apollo.common.config.Extrinsics extrinsics = 3; + if (this->has_extrinsics()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *extrinsics_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void VehicleConfig::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.common.config.VehicleConfig) + GOOGLE_DCHECK_NE(&from, this); + const VehicleConfig* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.common.config.VehicleConfig) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.common.config.VehicleConfig) + MergeFrom(*source); + } +} + +void VehicleConfig::MergeFrom(const VehicleConfig& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.common.config.VehicleConfig) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.has_vehicle_param()) { + mutable_vehicle_param()->::apollo::common::config::VehicleParam::MergeFrom(from.vehicle_param()); + } + if (from.has_extrinsics()) { + mutable_extrinsics()->::apollo::common::config::Extrinsics::MergeFrom(from.extrinsics()); + } +} + +void VehicleConfig::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.common.config.VehicleConfig) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void VehicleConfig::CopyFrom(const VehicleConfig& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.common.config.VehicleConfig) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool VehicleConfig::IsInitialized() const { + return true; +} + +void VehicleConfig::Swap(VehicleConfig* other) { + if (other == this) return; + InternalSwap(other); +} +void VehicleConfig::InternalSwap(VehicleConfig* other) { + using std::swap; + swap(header_, other->header_); + swap(vehicle_param_, other->vehicle_param_); + swap(extrinsics_, other->extrinsics_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata VehicleConfig::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace config +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::config::VehicleParam* Arena::CreateMaybeMessage< ::apollo::common::config::VehicleParam >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::config::VehicleParam >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::common::config::VehicleConfig* Arena::CreateMaybeMessage< ::apollo::common::config::VehicleConfig >(Arena* arena) { + return Arena::CreateInternal< ::apollo::common::config::VehicleConfig >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/common/vehicle_config.pb.h b/apollo_msgs/include/apollo_msgs/proto/common/vehicle_config.pb.h new file mode 100644 index 0000000..1275949 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/common/vehicle_config.pb.h @@ -0,0 +1,797 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/common/vehicle_config.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include "apollo_msgs/proto/common/header.pb.h" +#include "apollo_msgs/proto/common/config_extrinsics.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[2]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto +namespace apollo { +namespace common { +namespace config { +class VehicleConfig; +class VehicleConfigDefaultTypeInternal; +extern VehicleConfigDefaultTypeInternal _VehicleConfig_default_instance_; +class VehicleParam; +class VehicleParamDefaultTypeInternal; +extern VehicleParamDefaultTypeInternal _VehicleParam_default_instance_; +} // namespace config +} // namespace common +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::common::config::VehicleConfig* Arena::CreateMaybeMessage<::apollo::common::config::VehicleConfig>(Arena*); +template<> ::apollo::common::config::VehicleParam* Arena::CreateMaybeMessage<::apollo::common::config::VehicleParam>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace common { +namespace config { + +// =================================================================== + +class VehicleParam : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.config.VehicleParam) */ { + public: + VehicleParam(); + virtual ~VehicleParam(); + + VehicleParam(const VehicleParam& from); + + inline VehicleParam& operator=(const VehicleParam& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + VehicleParam(VehicleParam&& from) noexcept + : VehicleParam() { + *this = ::std::move(from); + } + + inline VehicleParam& operator=(VehicleParam&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const VehicleParam& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const VehicleParam* internal_default_instance() { + return reinterpret_cast( + &_VehicleParam_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(VehicleParam* other); + friend void swap(VehicleParam& a, VehicleParam& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline VehicleParam* New() const final { + return CreateMaybeMessage(NULL); + } + + VehicleParam* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const VehicleParam& from); + void MergeFrom(const VehicleParam& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(VehicleParam* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double front_edge_to_center = 1; + void clear_front_edge_to_center(); + static const int kFrontEdgeToCenterFieldNumber = 1; + double front_edge_to_center() const; + void set_front_edge_to_center(double value); + + // double back_edge_to_center = 2; + void clear_back_edge_to_center(); + static const int kBackEdgeToCenterFieldNumber = 2; + double back_edge_to_center() const; + void set_back_edge_to_center(double value); + + // double left_edge_to_center = 3; + void clear_left_edge_to_center(); + static const int kLeftEdgeToCenterFieldNumber = 3; + double left_edge_to_center() const; + void set_left_edge_to_center(double value); + + // double right_edge_to_center = 4; + void clear_right_edge_to_center(); + static const int kRightEdgeToCenterFieldNumber = 4; + double right_edge_to_center() const; + void set_right_edge_to_center(double value); + + // double length = 5; + void clear_length(); + static const int kLengthFieldNumber = 5; + double length() const; + void set_length(double value); + + // double width = 6; + void clear_width(); + static const int kWidthFieldNumber = 6; + double width() const; + void set_width(double value); + + // double height = 7; + void clear_height(); + static const int kHeightFieldNumber = 7; + double height() const; + void set_height(double value); + + // double min_turn_radius = 8; + void clear_min_turn_radius(); + static const int kMinTurnRadiusFieldNumber = 8; + double min_turn_radius() const; + void set_min_turn_radius(double value); + + // double max_acceleration = 9; + void clear_max_acceleration(); + static const int kMaxAccelerationFieldNumber = 9; + double max_acceleration() const; + void set_max_acceleration(double value); + + // double max_deceleration = 10; + void clear_max_deceleration(); + static const int kMaxDecelerationFieldNumber = 10; + double max_deceleration() const; + void set_max_deceleration(double value); + + // double max_steer_angle = 11; + void clear_max_steer_angle(); + static const int kMaxSteerAngleFieldNumber = 11; + double max_steer_angle() const; + void set_max_steer_angle(double value); + + // double max_steer_angle_rate = 12; + void clear_max_steer_angle_rate(); + static const int kMaxSteerAngleRateFieldNumber = 12; + double max_steer_angle_rate() const; + void set_max_steer_angle_rate(double value); + + // double steer_ratio = 13; + void clear_steer_ratio(); + static const int kSteerRatioFieldNumber = 13; + double steer_ratio() const; + void set_steer_ratio(double value); + + // double wheel_base = 14; + void clear_wheel_base(); + static const int kWheelBaseFieldNumber = 14; + double wheel_base() const; + void set_wheel_base(double value); + + // double wheel_rolling_radius = 15; + void clear_wheel_rolling_radius(); + static const int kWheelRollingRadiusFieldNumber = 15; + double wheel_rolling_radius() const; + void set_wheel_rolling_radius(double value); + + // @@protoc_insertion_point(class_scope:apollo.common.config.VehicleParam) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double front_edge_to_center_; + double back_edge_to_center_; + double left_edge_to_center_; + double right_edge_to_center_; + double length_; + double width_; + double height_; + double min_turn_radius_; + double max_acceleration_; + double max_deceleration_; + double max_steer_angle_; + double max_steer_angle_rate_; + double steer_ratio_; + double wheel_base_; + double wheel_rolling_radius_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class VehicleConfig : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.common.config.VehicleConfig) */ { + public: + VehicleConfig(); + virtual ~VehicleConfig(); + + VehicleConfig(const VehicleConfig& from); + + inline VehicleConfig& operator=(const VehicleConfig& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + VehicleConfig(VehicleConfig&& from) noexcept + : VehicleConfig() { + *this = ::std::move(from); + } + + inline VehicleConfig& operator=(VehicleConfig&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const VehicleConfig& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const VehicleConfig* internal_default_instance() { + return reinterpret_cast( + &_VehicleConfig_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(VehicleConfig* other); + friend void swap(VehicleConfig& a, VehicleConfig& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline VehicleConfig* New() const final { + return CreateMaybeMessage(NULL); + } + + VehicleConfig* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const VehicleConfig& from); + void MergeFrom(const VehicleConfig& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(VehicleConfig* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.common.config.VehicleParam vehicle_param = 2; + bool has_vehicle_param() const; + void clear_vehicle_param(); + static const int kVehicleParamFieldNumber = 2; + private: + const ::apollo::common::config::VehicleParam& _internal_vehicle_param() const; + public: + const ::apollo::common::config::VehicleParam& vehicle_param() const; + ::apollo::common::config::VehicleParam* release_vehicle_param(); + ::apollo::common::config::VehicleParam* mutable_vehicle_param(); + void set_allocated_vehicle_param(::apollo::common::config::VehicleParam* vehicle_param); + + // .apollo.common.config.Extrinsics extrinsics = 3; + bool has_extrinsics() const; + void clear_extrinsics(); + static const int kExtrinsicsFieldNumber = 3; + private: + const ::apollo::common::config::Extrinsics& _internal_extrinsics() const; + public: + const ::apollo::common::config::Extrinsics& extrinsics() const; + ::apollo::common::config::Extrinsics* release_extrinsics(); + ::apollo::common::config::Extrinsics* mutable_extrinsics(); + void set_allocated_extrinsics(::apollo::common::config::Extrinsics* extrinsics); + + // @@protoc_insertion_point(class_scope:apollo.common.config.VehicleConfig) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::Header* header_; + ::apollo::common::config::VehicleParam* vehicle_param_; + ::apollo::common::config::Extrinsics* extrinsics_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// VehicleParam + +// double front_edge_to_center = 1; +inline void VehicleParam::clear_front_edge_to_center() { + front_edge_to_center_ = 0; +} +inline double VehicleParam::front_edge_to_center() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.front_edge_to_center) + return front_edge_to_center_; +} +inline void VehicleParam::set_front_edge_to_center(double value) { + + front_edge_to_center_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.front_edge_to_center) +} + +// double back_edge_to_center = 2; +inline void VehicleParam::clear_back_edge_to_center() { + back_edge_to_center_ = 0; +} +inline double VehicleParam::back_edge_to_center() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.back_edge_to_center) + return back_edge_to_center_; +} +inline void VehicleParam::set_back_edge_to_center(double value) { + + back_edge_to_center_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.back_edge_to_center) +} + +// double left_edge_to_center = 3; +inline void VehicleParam::clear_left_edge_to_center() { + left_edge_to_center_ = 0; +} +inline double VehicleParam::left_edge_to_center() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.left_edge_to_center) + return left_edge_to_center_; +} +inline void VehicleParam::set_left_edge_to_center(double value) { + + left_edge_to_center_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.left_edge_to_center) +} + +// double right_edge_to_center = 4; +inline void VehicleParam::clear_right_edge_to_center() { + right_edge_to_center_ = 0; +} +inline double VehicleParam::right_edge_to_center() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.right_edge_to_center) + return right_edge_to_center_; +} +inline void VehicleParam::set_right_edge_to_center(double value) { + + right_edge_to_center_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.right_edge_to_center) +} + +// double length = 5; +inline void VehicleParam::clear_length() { + length_ = 0; +} +inline double VehicleParam::length() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.length) + return length_; +} +inline void VehicleParam::set_length(double value) { + + length_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.length) +} + +// double width = 6; +inline void VehicleParam::clear_width() { + width_ = 0; +} +inline double VehicleParam::width() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.width) + return width_; +} +inline void VehicleParam::set_width(double value) { + + width_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.width) +} + +// double height = 7; +inline void VehicleParam::clear_height() { + height_ = 0; +} +inline double VehicleParam::height() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.height) + return height_; +} +inline void VehicleParam::set_height(double value) { + + height_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.height) +} + +// double min_turn_radius = 8; +inline void VehicleParam::clear_min_turn_radius() { + min_turn_radius_ = 0; +} +inline double VehicleParam::min_turn_radius() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.min_turn_radius) + return min_turn_radius_; +} +inline void VehicleParam::set_min_turn_radius(double value) { + + min_turn_radius_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.min_turn_radius) +} + +// double max_acceleration = 9; +inline void VehicleParam::clear_max_acceleration() { + max_acceleration_ = 0; +} +inline double VehicleParam::max_acceleration() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.max_acceleration) + return max_acceleration_; +} +inline void VehicleParam::set_max_acceleration(double value) { + + max_acceleration_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.max_acceleration) +} + +// double max_deceleration = 10; +inline void VehicleParam::clear_max_deceleration() { + max_deceleration_ = 0; +} +inline double VehicleParam::max_deceleration() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.max_deceleration) + return max_deceleration_; +} +inline void VehicleParam::set_max_deceleration(double value) { + + max_deceleration_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.max_deceleration) +} + +// double max_steer_angle = 11; +inline void VehicleParam::clear_max_steer_angle() { + max_steer_angle_ = 0; +} +inline double VehicleParam::max_steer_angle() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.max_steer_angle) + return max_steer_angle_; +} +inline void VehicleParam::set_max_steer_angle(double value) { + + max_steer_angle_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.max_steer_angle) +} + +// double max_steer_angle_rate = 12; +inline void VehicleParam::clear_max_steer_angle_rate() { + max_steer_angle_rate_ = 0; +} +inline double VehicleParam::max_steer_angle_rate() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.max_steer_angle_rate) + return max_steer_angle_rate_; +} +inline void VehicleParam::set_max_steer_angle_rate(double value) { + + max_steer_angle_rate_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.max_steer_angle_rate) +} + +// double steer_ratio = 13; +inline void VehicleParam::clear_steer_ratio() { + steer_ratio_ = 0; +} +inline double VehicleParam::steer_ratio() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.steer_ratio) + return steer_ratio_; +} +inline void VehicleParam::set_steer_ratio(double value) { + + steer_ratio_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.steer_ratio) +} + +// double wheel_base = 14; +inline void VehicleParam::clear_wheel_base() { + wheel_base_ = 0; +} +inline double VehicleParam::wheel_base() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.wheel_base) + return wheel_base_; +} +inline void VehicleParam::set_wheel_base(double value) { + + wheel_base_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.wheel_base) +} + +// double wheel_rolling_radius = 15; +inline void VehicleParam::clear_wheel_rolling_radius() { + wheel_rolling_radius_ = 0; +} +inline double VehicleParam::wheel_rolling_radius() const { + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleParam.wheel_rolling_radius) + return wheel_rolling_radius_; +} +inline void VehicleParam::set_wheel_rolling_radius(double value) { + + wheel_rolling_radius_ = value; + // @@protoc_insertion_point(field_set:apollo.common.config.VehicleParam.wheel_rolling_radius) +} + +// ------------------------------------------------------------------- + +// VehicleConfig + +// .apollo.common.Header header = 1; +inline bool VehicleConfig::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& VehicleConfig::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& VehicleConfig::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleConfig.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* VehicleConfig::release_header() { + // @@protoc_insertion_point(field_release:apollo.common.config.VehicleConfig.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* VehicleConfig::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.common.config.VehicleConfig.header) + return header_; +} +inline void VehicleConfig::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.common.config.VehicleConfig.header) +} + +// .apollo.common.config.VehicleParam vehicle_param = 2; +inline bool VehicleConfig::has_vehicle_param() const { + return this != internal_default_instance() && vehicle_param_ != NULL; +} +inline void VehicleConfig::clear_vehicle_param() { + if (GetArenaNoVirtual() == NULL && vehicle_param_ != NULL) { + delete vehicle_param_; + } + vehicle_param_ = NULL; +} +inline const ::apollo::common::config::VehicleParam& VehicleConfig::_internal_vehicle_param() const { + return *vehicle_param_; +} +inline const ::apollo::common::config::VehicleParam& VehicleConfig::vehicle_param() const { + const ::apollo::common::config::VehicleParam* p = vehicle_param_; + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleConfig.vehicle_param) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::config::_VehicleParam_default_instance_); +} +inline ::apollo::common::config::VehicleParam* VehicleConfig::release_vehicle_param() { + // @@protoc_insertion_point(field_release:apollo.common.config.VehicleConfig.vehicle_param) + + ::apollo::common::config::VehicleParam* temp = vehicle_param_; + vehicle_param_ = NULL; + return temp; +} +inline ::apollo::common::config::VehicleParam* VehicleConfig::mutable_vehicle_param() { + + if (vehicle_param_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::config::VehicleParam>(GetArenaNoVirtual()); + vehicle_param_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.common.config.VehicleConfig.vehicle_param) + return vehicle_param_; +} +inline void VehicleConfig::set_allocated_vehicle_param(::apollo::common::config::VehicleParam* vehicle_param) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete vehicle_param_; + } + if (vehicle_param) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + vehicle_param = ::google::protobuf::internal::GetOwnedMessage( + message_arena, vehicle_param, submessage_arena); + } + + } else { + + } + vehicle_param_ = vehicle_param; + // @@protoc_insertion_point(field_set_allocated:apollo.common.config.VehicleConfig.vehicle_param) +} + +// .apollo.common.config.Extrinsics extrinsics = 3; +inline bool VehicleConfig::has_extrinsics() const { + return this != internal_default_instance() && extrinsics_ != NULL; +} +inline const ::apollo::common::config::Extrinsics& VehicleConfig::_internal_extrinsics() const { + return *extrinsics_; +} +inline const ::apollo::common::config::Extrinsics& VehicleConfig::extrinsics() const { + const ::apollo::common::config::Extrinsics* p = extrinsics_; + // @@protoc_insertion_point(field_get:apollo.common.config.VehicleConfig.extrinsics) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::config::_Extrinsics_default_instance_); +} +inline ::apollo::common::config::Extrinsics* VehicleConfig::release_extrinsics() { + // @@protoc_insertion_point(field_release:apollo.common.config.VehicleConfig.extrinsics) + + ::apollo::common::config::Extrinsics* temp = extrinsics_; + extrinsics_ = NULL; + return temp; +} +inline ::apollo::common::config::Extrinsics* VehicleConfig::mutable_extrinsics() { + + if (extrinsics_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::config::Extrinsics>(GetArenaNoVirtual()); + extrinsics_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.common.config.VehicleConfig.extrinsics) + return extrinsics_; +} +inline void VehicleConfig::set_allocated_extrinsics(::apollo::common::config::Extrinsics* extrinsics) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(extrinsics_); + } + if (extrinsics) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + extrinsics = ::google::protobuf::internal::GetOwnedMessage( + message_arena, extrinsics, submessage_arena); + } + + } else { + + } + extrinsics_ = extrinsics; + // @@protoc_insertion_point(field_set_allocated:apollo.common.config.VehicleConfig.extrinsics) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace config +} // namespace common +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcommon_2fvehicle_5fconfig_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/control/calibration_table.pb.cc b/apollo_msgs/include/apollo_msgs/proto/control/calibration_table.pb.cc new file mode 100644 index 0000000..a1aeef3 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/control/calibration_table.pb.cc @@ -0,0 +1,693 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/control/calibration_table.proto + +#include "apollo_msgs/proto/control/calibration_table.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_ControlCalibrationInfo; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto +namespace apollo { +namespace control { +namespace calibrationtable { +class ControlCalibrationTableDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ControlCalibrationTable_default_instance_; +class ControlCalibrationInfoDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ControlCalibrationInfo_default_instance_; +} // namespace calibrationtable +} // namespace control +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto { +static void InitDefaultsControlCalibrationTable() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::calibrationtable::_ControlCalibrationTable_default_instance_; + new (ptr) ::apollo::control::calibrationtable::ControlCalibrationTable(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::calibrationtable::ControlCalibrationTable::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_ControlCalibrationTable = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsControlCalibrationTable}, { + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::scc_info_ControlCalibrationInfo.base,}}; + +static void InitDefaultsControlCalibrationInfo() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::calibrationtable::_ControlCalibrationInfo_default_instance_; + new (ptr) ::apollo::control::calibrationtable::ControlCalibrationInfo(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::calibrationtable::ControlCalibrationInfo::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_ControlCalibrationInfo = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsControlCalibrationInfo}, {}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_ControlCalibrationTable.base); + ::google::protobuf::internal::InitSCC(&scc_info_ControlCalibrationInfo.base); +} + +::google::protobuf::Metadata file_level_metadata[2]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::calibrationtable::ControlCalibrationTable, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::calibrationtable::ControlCalibrationTable, calibration_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::calibrationtable::ControlCalibrationInfo, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::calibrationtable::ControlCalibrationInfo, speed_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::calibrationtable::ControlCalibrationInfo, acceleration_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::calibrationtable::ControlCalibrationInfo, command_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::control::calibrationtable::ControlCalibrationTable)}, + { 6, -1, sizeof(::apollo::control::calibrationtable::ControlCalibrationInfo)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::control::calibrationtable::_ControlCalibrationTable_default_instance_), + reinterpret_cast(&::apollo::control::calibrationtable::_ControlCalibrationInfo_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/control/calibration_table.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 2); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n1apollo_msgs/proto/control/calibration_" + "table.proto\022\037apollo.control.calibrationt" + "able\"g\n\027ControlCalibrationTable\022L\n\013calib" + "ration\030\001 \003(\01327.apollo.control.calibratio" + "ntable.ControlCalibrationInfo\"N\n\026Control" + "CalibrationInfo\022\r\n\005speed\030\001 \001(\001\022\024\n\014accele" + "ration\030\002 \001(\001\022\017\n\007command\030\003 \001(\001b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 277); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/control/calibration_table.proto", &protobuf_RegisterTypes); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto +namespace apollo { +namespace control { +namespace calibrationtable { + +// =================================================================== + +void ControlCalibrationTable::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ControlCalibrationTable::kCalibrationFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ControlCalibrationTable::ControlCalibrationTable() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::scc_info_ControlCalibrationTable.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.calibrationtable.ControlCalibrationTable) +} +ControlCalibrationTable::ControlCalibrationTable(const ControlCalibrationTable& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + calibration_(from.calibration_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:apollo.control.calibrationtable.ControlCalibrationTable) +} + +void ControlCalibrationTable::SharedCtor() { +} + +ControlCalibrationTable::~ControlCalibrationTable() { + // @@protoc_insertion_point(destructor:apollo.control.calibrationtable.ControlCalibrationTable) + SharedDtor(); +} + +void ControlCalibrationTable::SharedDtor() { +} + +void ControlCalibrationTable::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ControlCalibrationTable::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ControlCalibrationTable& ControlCalibrationTable::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::scc_info_ControlCalibrationTable.base); + return *internal_default_instance(); +} + + +void ControlCalibrationTable::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.calibrationtable.ControlCalibrationTable) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + calibration_.Clear(); + _internal_metadata_.Clear(); +} + +bool ControlCalibrationTable::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.calibrationtable.ControlCalibrationTable) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // repeated .apollo.control.calibrationtable.ControlCalibrationInfo calibration = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_calibration())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.calibrationtable.ControlCalibrationTable) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.calibrationtable.ControlCalibrationTable) + return false; +#undef DO_ +} + +void ControlCalibrationTable::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.calibrationtable.ControlCalibrationTable) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.control.calibrationtable.ControlCalibrationInfo calibration = 1; + for (unsigned int i = 0, + n = static_cast(this->calibration_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, + this->calibration(static_cast(i)), + output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.calibrationtable.ControlCalibrationTable) +} + +::google::protobuf::uint8* ControlCalibrationTable::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.calibrationtable.ControlCalibrationTable) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.control.calibrationtable.ControlCalibrationInfo calibration = 1; + for (unsigned int i = 0, + n = static_cast(this->calibration_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->calibration(static_cast(i)), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.calibrationtable.ControlCalibrationTable) + return target; +} + +size_t ControlCalibrationTable::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.calibrationtable.ControlCalibrationTable) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.control.calibrationtable.ControlCalibrationInfo calibration = 1; + { + unsigned int count = static_cast(this->calibration_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->calibration(static_cast(i))); + } + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ControlCalibrationTable::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.calibrationtable.ControlCalibrationTable) + GOOGLE_DCHECK_NE(&from, this); + const ControlCalibrationTable* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.calibrationtable.ControlCalibrationTable) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.calibrationtable.ControlCalibrationTable) + MergeFrom(*source); + } +} + +void ControlCalibrationTable::MergeFrom(const ControlCalibrationTable& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.calibrationtable.ControlCalibrationTable) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + calibration_.MergeFrom(from.calibration_); +} + +void ControlCalibrationTable::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.calibrationtable.ControlCalibrationTable) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ControlCalibrationTable::CopyFrom(const ControlCalibrationTable& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.calibrationtable.ControlCalibrationTable) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ControlCalibrationTable::IsInitialized() const { + return true; +} + +void ControlCalibrationTable::Swap(ControlCalibrationTable* other) { + if (other == this) return; + InternalSwap(other); +} +void ControlCalibrationTable::InternalSwap(ControlCalibrationTable* other) { + using std::swap; + CastToBase(&calibration_)->InternalSwap(CastToBase(&other->calibration_)); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ControlCalibrationTable::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ControlCalibrationInfo::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ControlCalibrationInfo::kSpeedFieldNumber; +const int ControlCalibrationInfo::kAccelerationFieldNumber; +const int ControlCalibrationInfo::kCommandFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ControlCalibrationInfo::ControlCalibrationInfo() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::scc_info_ControlCalibrationInfo.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.calibrationtable.ControlCalibrationInfo) +} +ControlCalibrationInfo::ControlCalibrationInfo(const ControlCalibrationInfo& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&speed_, &from.speed_, + static_cast(reinterpret_cast(&command_) - + reinterpret_cast(&speed_)) + sizeof(command_)); + // @@protoc_insertion_point(copy_constructor:apollo.control.calibrationtable.ControlCalibrationInfo) +} + +void ControlCalibrationInfo::SharedCtor() { + ::memset(&speed_, 0, static_cast( + reinterpret_cast(&command_) - + reinterpret_cast(&speed_)) + sizeof(command_)); +} + +ControlCalibrationInfo::~ControlCalibrationInfo() { + // @@protoc_insertion_point(destructor:apollo.control.calibrationtable.ControlCalibrationInfo) + SharedDtor(); +} + +void ControlCalibrationInfo::SharedDtor() { +} + +void ControlCalibrationInfo::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ControlCalibrationInfo::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ControlCalibrationInfo& ControlCalibrationInfo::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::scc_info_ControlCalibrationInfo.base); + return *internal_default_instance(); +} + + +void ControlCalibrationInfo::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.calibrationtable.ControlCalibrationInfo) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&speed_, 0, static_cast( + reinterpret_cast(&command_) - + reinterpret_cast(&speed_)) + sizeof(command_)); + _internal_metadata_.Clear(); +} + +bool ControlCalibrationInfo::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.calibrationtable.ControlCalibrationInfo) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double speed = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &speed_))); + } else { + goto handle_unusual; + } + break; + } + + // double acceleration = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &acceleration_))); + } else { + goto handle_unusual; + } + break; + } + + // double command = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &command_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.calibrationtable.ControlCalibrationInfo) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.calibrationtable.ControlCalibrationInfo) + return false; +#undef DO_ +} + +void ControlCalibrationInfo::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.calibrationtable.ControlCalibrationInfo) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double speed = 1; + if (this->speed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->speed(), output); + } + + // double acceleration = 2; + if (this->acceleration() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->acceleration(), output); + } + + // double command = 3; + if (this->command() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->command(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.calibrationtable.ControlCalibrationInfo) +} + +::google::protobuf::uint8* ControlCalibrationInfo::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.calibrationtable.ControlCalibrationInfo) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double speed = 1; + if (this->speed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->speed(), target); + } + + // double acceleration = 2; + if (this->acceleration() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->acceleration(), target); + } + + // double command = 3; + if (this->command() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->command(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.calibrationtable.ControlCalibrationInfo) + return target; +} + +size_t ControlCalibrationInfo::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.calibrationtable.ControlCalibrationInfo) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double speed = 1; + if (this->speed() != 0) { + total_size += 1 + 8; + } + + // double acceleration = 2; + if (this->acceleration() != 0) { + total_size += 1 + 8; + } + + // double command = 3; + if (this->command() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ControlCalibrationInfo::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.calibrationtable.ControlCalibrationInfo) + GOOGLE_DCHECK_NE(&from, this); + const ControlCalibrationInfo* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.calibrationtable.ControlCalibrationInfo) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.calibrationtable.ControlCalibrationInfo) + MergeFrom(*source); + } +} + +void ControlCalibrationInfo::MergeFrom(const ControlCalibrationInfo& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.calibrationtable.ControlCalibrationInfo) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.speed() != 0) { + set_speed(from.speed()); + } + if (from.acceleration() != 0) { + set_acceleration(from.acceleration()); + } + if (from.command() != 0) { + set_command(from.command()); + } +} + +void ControlCalibrationInfo::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.calibrationtable.ControlCalibrationInfo) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ControlCalibrationInfo::CopyFrom(const ControlCalibrationInfo& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.calibrationtable.ControlCalibrationInfo) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ControlCalibrationInfo::IsInitialized() const { + return true; +} + +void ControlCalibrationInfo::Swap(ControlCalibrationInfo* other) { + if (other == this) return; + InternalSwap(other); +} +void ControlCalibrationInfo::InternalSwap(ControlCalibrationInfo* other) { + using std::swap; + swap(speed_, other->speed_); + swap(acceleration_, other->acceleration_); + swap(command_, other->command_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ControlCalibrationInfo::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace calibrationtable +} // namespace control +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::calibrationtable::ControlCalibrationTable* Arena::CreateMaybeMessage< ::apollo::control::calibrationtable::ControlCalibrationTable >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::calibrationtable::ControlCalibrationTable >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::calibrationtable::ControlCalibrationInfo* Arena::CreateMaybeMessage< ::apollo::control::calibrationtable::ControlCalibrationInfo >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::calibrationtable::ControlCalibrationInfo >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/control/calibration_table.pb.h b/apollo_msgs/include/apollo_msgs/proto/control/calibration_table.pb.h new file mode 100644 index 0000000..4810494 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/control/calibration_table.pb.h @@ -0,0 +1,397 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/control/calibration_table.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[2]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto +namespace apollo { +namespace control { +namespace calibrationtable { +class ControlCalibrationInfo; +class ControlCalibrationInfoDefaultTypeInternal; +extern ControlCalibrationInfoDefaultTypeInternal _ControlCalibrationInfo_default_instance_; +class ControlCalibrationTable; +class ControlCalibrationTableDefaultTypeInternal; +extern ControlCalibrationTableDefaultTypeInternal _ControlCalibrationTable_default_instance_; +} // namespace calibrationtable +} // namespace control +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::control::calibrationtable::ControlCalibrationInfo* Arena::CreateMaybeMessage<::apollo::control::calibrationtable::ControlCalibrationInfo>(Arena*); +template<> ::apollo::control::calibrationtable::ControlCalibrationTable* Arena::CreateMaybeMessage<::apollo::control::calibrationtable::ControlCalibrationTable>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace control { +namespace calibrationtable { + +// =================================================================== + +class ControlCalibrationTable : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.calibrationtable.ControlCalibrationTable) */ { + public: + ControlCalibrationTable(); + virtual ~ControlCalibrationTable(); + + ControlCalibrationTable(const ControlCalibrationTable& from); + + inline ControlCalibrationTable& operator=(const ControlCalibrationTable& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ControlCalibrationTable(ControlCalibrationTable&& from) noexcept + : ControlCalibrationTable() { + *this = ::std::move(from); + } + + inline ControlCalibrationTable& operator=(ControlCalibrationTable&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ControlCalibrationTable& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ControlCalibrationTable* internal_default_instance() { + return reinterpret_cast( + &_ControlCalibrationTable_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(ControlCalibrationTable* other); + friend void swap(ControlCalibrationTable& a, ControlCalibrationTable& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ControlCalibrationTable* New() const final { + return CreateMaybeMessage(NULL); + } + + ControlCalibrationTable* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ControlCalibrationTable& from); + void MergeFrom(const ControlCalibrationTable& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ControlCalibrationTable* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.control.calibrationtable.ControlCalibrationInfo calibration = 1; + int calibration_size() const; + void clear_calibration(); + static const int kCalibrationFieldNumber = 1; + ::apollo::control::calibrationtable::ControlCalibrationInfo* mutable_calibration(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::control::calibrationtable::ControlCalibrationInfo >* + mutable_calibration(); + const ::apollo::control::calibrationtable::ControlCalibrationInfo& calibration(int index) const; + ::apollo::control::calibrationtable::ControlCalibrationInfo* add_calibration(); + const ::google::protobuf::RepeatedPtrField< ::apollo::control::calibrationtable::ControlCalibrationInfo >& + calibration() const; + + // @@protoc_insertion_point(class_scope:apollo.control.calibrationtable.ControlCalibrationTable) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::control::calibrationtable::ControlCalibrationInfo > calibration_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ControlCalibrationInfo : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.calibrationtable.ControlCalibrationInfo) */ { + public: + ControlCalibrationInfo(); + virtual ~ControlCalibrationInfo(); + + ControlCalibrationInfo(const ControlCalibrationInfo& from); + + inline ControlCalibrationInfo& operator=(const ControlCalibrationInfo& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ControlCalibrationInfo(ControlCalibrationInfo&& from) noexcept + : ControlCalibrationInfo() { + *this = ::std::move(from); + } + + inline ControlCalibrationInfo& operator=(ControlCalibrationInfo&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ControlCalibrationInfo& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ControlCalibrationInfo* internal_default_instance() { + return reinterpret_cast( + &_ControlCalibrationInfo_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(ControlCalibrationInfo* other); + friend void swap(ControlCalibrationInfo& a, ControlCalibrationInfo& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ControlCalibrationInfo* New() const final { + return CreateMaybeMessage(NULL); + } + + ControlCalibrationInfo* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ControlCalibrationInfo& from); + void MergeFrom(const ControlCalibrationInfo& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ControlCalibrationInfo* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double speed = 1; + void clear_speed(); + static const int kSpeedFieldNumber = 1; + double speed() const; + void set_speed(double value); + + // double acceleration = 2; + void clear_acceleration(); + static const int kAccelerationFieldNumber = 2; + double acceleration() const; + void set_acceleration(double value); + + // double command = 3; + void clear_command(); + static const int kCommandFieldNumber = 3; + double command() const; + void set_command(double value); + + // @@protoc_insertion_point(class_scope:apollo.control.calibrationtable.ControlCalibrationInfo) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double speed_; + double acceleration_; + double command_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// ControlCalibrationTable + +// repeated .apollo.control.calibrationtable.ControlCalibrationInfo calibration = 1; +inline int ControlCalibrationTable::calibration_size() const { + return calibration_.size(); +} +inline void ControlCalibrationTable::clear_calibration() { + calibration_.Clear(); +} +inline ::apollo::control::calibrationtable::ControlCalibrationInfo* ControlCalibrationTable::mutable_calibration(int index) { + // @@protoc_insertion_point(field_mutable:apollo.control.calibrationtable.ControlCalibrationTable.calibration) + return calibration_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::control::calibrationtable::ControlCalibrationInfo >* +ControlCalibrationTable::mutable_calibration() { + // @@protoc_insertion_point(field_mutable_list:apollo.control.calibrationtable.ControlCalibrationTable.calibration) + return &calibration_; +} +inline const ::apollo::control::calibrationtable::ControlCalibrationInfo& ControlCalibrationTable::calibration(int index) const { + // @@protoc_insertion_point(field_get:apollo.control.calibrationtable.ControlCalibrationTable.calibration) + return calibration_.Get(index); +} +inline ::apollo::control::calibrationtable::ControlCalibrationInfo* ControlCalibrationTable::add_calibration() { + // @@protoc_insertion_point(field_add:apollo.control.calibrationtable.ControlCalibrationTable.calibration) + return calibration_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::control::calibrationtable::ControlCalibrationInfo >& +ControlCalibrationTable::calibration() const { + // @@protoc_insertion_point(field_list:apollo.control.calibrationtable.ControlCalibrationTable.calibration) + return calibration_; +} + +// ------------------------------------------------------------------- + +// ControlCalibrationInfo + +// double speed = 1; +inline void ControlCalibrationInfo::clear_speed() { + speed_ = 0; +} +inline double ControlCalibrationInfo::speed() const { + // @@protoc_insertion_point(field_get:apollo.control.calibrationtable.ControlCalibrationInfo.speed) + return speed_; +} +inline void ControlCalibrationInfo::set_speed(double value) { + + speed_ = value; + // @@protoc_insertion_point(field_set:apollo.control.calibrationtable.ControlCalibrationInfo.speed) +} + +// double acceleration = 2; +inline void ControlCalibrationInfo::clear_acceleration() { + acceleration_ = 0; +} +inline double ControlCalibrationInfo::acceleration() const { + // @@protoc_insertion_point(field_get:apollo.control.calibrationtable.ControlCalibrationInfo.acceleration) + return acceleration_; +} +inline void ControlCalibrationInfo::set_acceleration(double value) { + + acceleration_ = value; + // @@protoc_insertion_point(field_set:apollo.control.calibrationtable.ControlCalibrationInfo.acceleration) +} + +// double command = 3; +inline void ControlCalibrationInfo::clear_command() { + command_ = 0; +} +inline double ControlCalibrationInfo::command() const { + // @@protoc_insertion_point(field_get:apollo.control.calibrationtable.ControlCalibrationInfo.command) + return command_; +} +inline void ControlCalibrationInfo::set_command(double value) { + + command_ = value; + // @@protoc_insertion_point(field_set:apollo.control.calibrationtable.ControlCalibrationInfo.command) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace calibrationtable +} // namespace control +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/control/control_cmd.pb.cc b/apollo_msgs/include/apollo_msgs/proto/control/control_cmd.pb.cc new file mode 100644 index 0000000..ea2a65f --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/control/control_cmd.pb.cc @@ -0,0 +1,4030 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/control/control_cmd.proto + +#include "apollo_msgs/proto/control/control_cmd.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Signal; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_LatencyStats; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_SimpleLateralDebug; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_SimpleLongitudinalDebug; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_InputDebug; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto ::google::protobuf::internal::SCCInfo<3> scc_info_Debug; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_PadMessage; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto +namespace apollo { +namespace control { +class LatencyStatsDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _LatencyStats_default_instance_; +class ControlCommandDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ControlCommand_default_instance_; +class SimpleLongitudinalDebugDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _SimpleLongitudinalDebug_default_instance_; +class SimpleLateralDebugDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _SimpleLateralDebug_default_instance_; +class InputDebugDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _InputDebug_default_instance_; +class DebugDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Debug_default_instance_; +} // namespace control +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto { +static void InitDefaultsLatencyStats() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::_LatencyStats_default_instance_; + new (ptr) ::apollo::control::LatencyStats(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::LatencyStats::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_LatencyStats = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsLatencyStats}, {}}; + +static void InitDefaultsControlCommand() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::_ControlCommand_default_instance_; + new (ptr) ::apollo::control::ControlCommand(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::ControlCommand::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<5> scc_info_ControlCommand = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 5, InitDefaultsControlCommand}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base, + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_Debug.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::scc_info_Signal.base, + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_LatencyStats.base, + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto::scc_info_PadMessage.base,}}; + +static void InitDefaultsSimpleLongitudinalDebug() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::_SimpleLongitudinalDebug_default_instance_; + new (ptr) ::apollo::control::SimpleLongitudinalDebug(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::SimpleLongitudinalDebug::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_SimpleLongitudinalDebug = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsSimpleLongitudinalDebug}, {}}; + +static void InitDefaultsSimpleLateralDebug() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::_SimpleLateralDebug_default_instance_; + new (ptr) ::apollo::control::SimpleLateralDebug(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::SimpleLateralDebug::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_SimpleLateralDebug = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsSimpleLateralDebug}, {}}; + +static void InitDefaultsInputDebug() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::_InputDebug_default_instance_; + new (ptr) ::apollo::control::InputDebug(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::InputDebug::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_InputDebug = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsInputDebug}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base,}}; + +static void InitDefaultsDebug() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::_Debug_default_instance_; + new (ptr) ::apollo::control::Debug(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::Debug::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<3> scc_info_Debug = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 3, InitDefaultsDebug}, { + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_SimpleLongitudinalDebug.base, + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_SimpleLateralDebug.base, + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_InputDebug.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_LatencyStats.base); + ::google::protobuf::internal::InitSCC(&scc_info_ControlCommand.base); + ::google::protobuf::internal::InitSCC(&scc_info_SimpleLongitudinalDebug.base); + ::google::protobuf::internal::InitSCC(&scc_info_SimpleLateralDebug.base); + ::google::protobuf::internal::InitSCC(&scc_info_InputDebug.base); + ::google::protobuf::internal::InitSCC(&scc_info_Debug.base); +} + +::google::protobuf::Metadata file_level_metadata[6]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatencyStats, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatencyStats, total_time_ms_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatencyStats, controller_time_ms_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, throttle_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, brake_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, steering_rate_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, steering_target_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, parking_brake_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, speed_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, acceleration_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, reset_model_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, engine_on_off_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, trajectory_fraction_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, driving_mode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, gear_location_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, debug_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, signal_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, latency_stats_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, pad_msg_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, left_turn_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, right_turn_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, high_beam_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, low_beam_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, horn_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlCommand, turnsignal_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, station_reference_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, station_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, station_error_limited_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, preview_station_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, speed_reference_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, speed_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, speed_controller_input_limited_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, preview_speed_reference_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, preview_speed_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, preview_acceleration_reference_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, acceleration_cmd_closeloop_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, acceleration_cmd_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, acceleration_lookup_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, speed_lookup_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, calibration_value_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, throttle_cmd_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, brake_cmd_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLongitudinalDebug, is_full_stop_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, lateral_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, ref_heading_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, heading_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, heading_error_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, heading_error_rate_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, lateral_error_rate_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, curvature_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, steer_angle_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, steer_angle_feedforward_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, steer_angle_lateral_contribution_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, steer_angle_lateral_rate_contribution_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, steer_angle_heading_contribution_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, steer_angle_heading_rate_contribution_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, steer_angle_feedback_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, steering_position_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::SimpleLateralDebug, ref_speed_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::InputDebug, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::InputDebug, localization_header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::InputDebug, canbus_header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::InputDebug, trajectory_header_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::Debug, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::Debug, simple_lon_debug_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::Debug, simple_lat_debug_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::Debug, input_debug_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::control::LatencyStats)}, + { 7, -1, sizeof(::apollo::control::ControlCommand)}, + { 35, -1, sizeof(::apollo::control::SimpleLongitudinalDebug)}, + { 58, -1, sizeof(::apollo::control::SimpleLateralDebug)}, + { 79, -1, sizeof(::apollo::control::InputDebug)}, + { 87, -1, sizeof(::apollo::control::Debug)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::control::_LatencyStats_default_instance_), + reinterpret_cast(&::apollo::control::_ControlCommand_default_instance_), + reinterpret_cast(&::apollo::control::_SimpleLongitudinalDebug_default_instance_), + reinterpret_cast(&::apollo::control::_SimpleLateralDebug_default_instance_), + reinterpret_cast(&::apollo::control::_InputDebug_default_instance_), + reinterpret_cast(&::apollo::control::_Debug_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/control/control_cmd.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 6); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n+apollo_msgs/proto/control/control_cmd." + "proto\022\016apollo.control\032&apollo_msgs/proto" + "/canbus/chassis.proto\032%apollo_msgs/proto" + "/common/header.proto\032\'apollo_msgs/proto/" + "control/pad_msg.proto\"A\n\014LatencyStats\022\025\n" + "\rtotal_time_ms\030\001 \001(\001\022\032\n\022controller_time_" + "ms\030\002 \003(\001\"\274\005\n\016ControlCommand\022%\n\006header\030\001 " + "\001(\0132\025.apollo.common.Header\022\020\n\010throttle\030\003" + " \001(\001\022\r\n\005brake\030\004 \001(\001\022\025\n\rsteering_rate\030\006 \001" + "(\001\022\027\n\017steering_target\030\007 \001(\001\022\025\n\rparking_b" + "rake\030\010 \001(\010\022\r\n\005speed\030\t \001(\001\022\024\n\014acceleratio" + "n\030\n \001(\001\022\023\n\013reset_model\030\020 \001(\010\022\025\n\rengine_o" + "n_off\030\021 \001(\010\022\033\n\023trajectory_fraction\030\022 \001(\001" + "\0228\n\014driving_mode\030\023 \001(\0162\".apollo.canbus.C" + "hassis.DrivingMode\022:\n\rgear_location\030\024 \001(" + "\0162#.apollo.canbus.Chassis.GearPosition\022$" + "\n\005debug\030\026 \001(\0132\025.apollo.control.Debug\022%\n\006" + "signal\030\027 \001(\0132\025.apollo.canbus.Signal\0223\n\rl" + "atency_stats\030\030 \001(\0132\034.apollo.control.Late" + "ncyStats\022+\n\007pad_msg\030\031 \001(\0132\032.apollo.contr" + "ol.PadMessage\022\021\n\tleft_turn\030\r \001(\010\022\022\n\nrigh" + "t_turn\030\016 \001(\010\022\021\n\thigh_beam\030\013 \001(\010\022\020\n\010low_b" + "eam\030\014 \001(\010\022\014\n\004horn\030\017 \001(\010\022.\n\nturnsignal\030\025 " + "\001(\0162\032.apollo.control.TurnSignal\"\220\004\n\027Simp" + "leLongitudinalDebug\022\031\n\021station_reference" + "\030\001 \001(\001\022\025\n\rstation_error\030\002 \001(\001\022\035\n\025station" + "_error_limited\030\003 \001(\001\022\035\n\025preview_station_" + "error\030\004 \001(\001\022\027\n\017speed_reference\030\005 \001(\001\022\023\n\013" + "speed_error\030\006 \001(\001\022&\n\036speed_controller_in" + "put_limited\030\007 \001(\001\022\037\n\027preview_speed_refer" + "ence\030\010 \001(\001\022\033\n\023preview_speed_error\030\t \001(\001\022" + "&\n\036preview_acceleration_reference\030\n \001(\001\022" + "\"\n\032acceleration_cmd_closeloop\030\013 \001(\001\022\030\n\020a" + "cceleration_cmd\030\014 \001(\001\022\033\n\023acceleration_lo" + "okup\030\r \001(\001\022\024\n\014speed_lookup\030\016 \001(\001\022\031\n\021cali" + "bration_value\030\017 \001(\001\022\024\n\014throttle_cmd\030\020 \001(" + "\001\022\021\n\tbrake_cmd\030\021 \001(\001\022\024\n\014is_full_stop\030\022 \001" + "(\010\"\347\003\n\022SimpleLateralDebug\022\025\n\rlateral_err" + "or\030\001 \001(\001\022\023\n\013ref_heading\030\002 \001(\001\022\017\n\007heading" + "\030\003 \001(\001\022\025\n\rheading_error\030\004 \001(\001\022\032\n\022heading" + "_error_rate\030\005 \001(\001\022\032\n\022lateral_error_rate\030" + "\006 \001(\001\022\021\n\tcurvature\030\007 \001(\001\022\023\n\013steer_angle\030" + "\010 \001(\001\022\037\n\027steer_angle_feedforward\030\t \001(\001\022(" + "\n steer_angle_lateral_contribution\030\n \001(\001" + "\022-\n%steer_angle_lateral_rate_contributio" + "n\030\013 \001(\001\022(\n steer_angle_heading_contribut" + "ion\030\014 \001(\001\022-\n%steer_angle_heading_rate_co" + "ntribution\030\r \001(\001\022\034\n\024steer_angle_feedback" + "\030\016 \001(\001\022\031\n\021steering_position\030\017 \001(\001\022\021\n\tref" + "_speed\030\020 \001(\001\"\240\001\n\nInputDebug\0222\n\023localizat" + "ion_header\030\001 \001(\0132\025.apollo.common.Header\022" + ",\n\rcanbus_header\030\002 \001(\0132\025.apollo.common.H" + "eader\0220\n\021trajectory_header\030\003 \001(\0132\025.apoll" + "o.common.Header\"\271\001\n\005Debug\022A\n\020simple_lon_" + "debug\030\001 \001(\0132\'.apollo.control.SimpleLongi" + "tudinalDebug\022<\n\020simple_lat_debug\030\002 \001(\0132\"" + ".apollo.control.SimpleLateralDebug\022/\n\013in" + "put_debug\030\003 \001(\0132\032.apollo.control.InputDe" + "bug*:\n\nTurnSignal\022\r\n\tTURN_NONE\020\000\022\r\n\tTURN" + "_LEFT\020\001\022\016\n\nTURN_RIGHT\020\002b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 2391); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/control/control_cmd.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto +namespace apollo { +namespace control { +const ::google::protobuf::EnumDescriptor* TurnSignal_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::file_level_enum_descriptors[0]; +} +bool TurnSignal_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + return true; + default: + return false; + } +} + + +// =================================================================== + +void LatencyStats::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int LatencyStats::kTotalTimeMsFieldNumber; +const int LatencyStats::kControllerTimeMsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +LatencyStats::LatencyStats() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_LatencyStats.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.LatencyStats) +} +LatencyStats::LatencyStats(const LatencyStats& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + controller_time_ms_(from.controller_time_ms_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + total_time_ms_ = from.total_time_ms_; + // @@protoc_insertion_point(copy_constructor:apollo.control.LatencyStats) +} + +void LatencyStats::SharedCtor() { + total_time_ms_ = 0; +} + +LatencyStats::~LatencyStats() { + // @@protoc_insertion_point(destructor:apollo.control.LatencyStats) + SharedDtor(); +} + +void LatencyStats::SharedDtor() { +} + +void LatencyStats::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* LatencyStats::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const LatencyStats& LatencyStats::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_LatencyStats.base); + return *internal_default_instance(); +} + + +void LatencyStats::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.LatencyStats) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + controller_time_ms_.Clear(); + total_time_ms_ = 0; + _internal_metadata_.Clear(); +} + +bool LatencyStats::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.LatencyStats) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double total_time_ms = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &total_time_ms_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double controller_time_ms = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_controller_time_ms()))); + } else if ( + static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 18u, input, this->mutable_controller_time_ms()))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.LatencyStats) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.LatencyStats) + return false; +#undef DO_ +} + +void LatencyStats::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.LatencyStats) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double total_time_ms = 1; + if (this->total_time_ms() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->total_time_ms(), output); + } + + // repeated double controller_time_ms = 2; + if (this->controller_time_ms_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(2, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(static_cast< ::google::protobuf::uint32>( + _controller_time_ms_cached_byte_size_)); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->controller_time_ms().data(), this->controller_time_ms_size(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.LatencyStats) +} + +::google::protobuf::uint8* LatencyStats::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.LatencyStats) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double total_time_ms = 1; + if (this->total_time_ms() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->total_time_ms(), target); + } + + // repeated double controller_time_ms = 2; + if (this->controller_time_ms_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 2, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + static_cast< ::google::protobuf::int32>( + _controller_time_ms_cached_byte_size_), target); + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->controller_time_ms_, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.LatencyStats) + return target; +} + +size_t LatencyStats::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.LatencyStats) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated double controller_time_ms = 2; + { + unsigned int count = static_cast(this->controller_time_ms_size()); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + static_cast< ::google::protobuf::int32>(data_size)); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _controller_time_ms_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // double total_time_ms = 1; + if (this->total_time_ms() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void LatencyStats::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.LatencyStats) + GOOGLE_DCHECK_NE(&from, this); + const LatencyStats* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.LatencyStats) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.LatencyStats) + MergeFrom(*source); + } +} + +void LatencyStats::MergeFrom(const LatencyStats& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.LatencyStats) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + controller_time_ms_.MergeFrom(from.controller_time_ms_); + if (from.total_time_ms() != 0) { + set_total_time_ms(from.total_time_ms()); + } +} + +void LatencyStats::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.LatencyStats) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void LatencyStats::CopyFrom(const LatencyStats& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.LatencyStats) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool LatencyStats::IsInitialized() const { + return true; +} + +void LatencyStats::Swap(LatencyStats* other) { + if (other == this) return; + InternalSwap(other); +} +void LatencyStats::InternalSwap(LatencyStats* other) { + using std::swap; + controller_time_ms_.InternalSwap(&other->controller_time_ms_); + swap(total_time_ms_, other->total_time_ms_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata LatencyStats::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ControlCommand::InitAsDefaultInstance() { + ::apollo::control::_ControlCommand_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); + ::apollo::control::_ControlCommand_default_instance_._instance.get_mutable()->debug_ = const_cast< ::apollo::control::Debug*>( + ::apollo::control::Debug::internal_default_instance()); + ::apollo::control::_ControlCommand_default_instance_._instance.get_mutable()->signal_ = const_cast< ::apollo::canbus::Signal*>( + ::apollo::canbus::Signal::internal_default_instance()); + ::apollo::control::_ControlCommand_default_instance_._instance.get_mutable()->latency_stats_ = const_cast< ::apollo::control::LatencyStats*>( + ::apollo::control::LatencyStats::internal_default_instance()); + ::apollo::control::_ControlCommand_default_instance_._instance.get_mutable()->pad_msg_ = const_cast< ::apollo::control::PadMessage*>( + ::apollo::control::PadMessage::internal_default_instance()); +} +void ControlCommand::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +void ControlCommand::clear_signal() { + if (GetArenaNoVirtual() == NULL && signal_ != NULL) { + delete signal_; + } + signal_ = NULL; +} +void ControlCommand::clear_pad_msg() { + if (GetArenaNoVirtual() == NULL && pad_msg_ != NULL) { + delete pad_msg_; + } + pad_msg_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ControlCommand::kHeaderFieldNumber; +const int ControlCommand::kThrottleFieldNumber; +const int ControlCommand::kBrakeFieldNumber; +const int ControlCommand::kSteeringRateFieldNumber; +const int ControlCommand::kSteeringTargetFieldNumber; +const int ControlCommand::kParkingBrakeFieldNumber; +const int ControlCommand::kSpeedFieldNumber; +const int ControlCommand::kAccelerationFieldNumber; +const int ControlCommand::kResetModelFieldNumber; +const int ControlCommand::kEngineOnOffFieldNumber; +const int ControlCommand::kTrajectoryFractionFieldNumber; +const int ControlCommand::kDrivingModeFieldNumber; +const int ControlCommand::kGearLocationFieldNumber; +const int ControlCommand::kDebugFieldNumber; +const int ControlCommand::kSignalFieldNumber; +const int ControlCommand::kLatencyStatsFieldNumber; +const int ControlCommand::kPadMsgFieldNumber; +const int ControlCommand::kLeftTurnFieldNumber; +const int ControlCommand::kRightTurnFieldNumber; +const int ControlCommand::kHighBeamFieldNumber; +const int ControlCommand::kLowBeamFieldNumber; +const int ControlCommand::kHornFieldNumber; +const int ControlCommand::kTurnsignalFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ControlCommand::ControlCommand() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_ControlCommand.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.ControlCommand) +} +ControlCommand::ControlCommand(const ControlCommand& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + if (from.has_debug()) { + debug_ = new ::apollo::control::Debug(*from.debug_); + } else { + debug_ = NULL; + } + if (from.has_signal()) { + signal_ = new ::apollo::canbus::Signal(*from.signal_); + } else { + signal_ = NULL; + } + if (from.has_latency_stats()) { + latency_stats_ = new ::apollo::control::LatencyStats(*from.latency_stats_); + } else { + latency_stats_ = NULL; + } + if (from.has_pad_msg()) { + pad_msg_ = new ::apollo::control::PadMessage(*from.pad_msg_); + } else { + pad_msg_ = NULL; + } + ::memcpy(&throttle_, &from.throttle_, + static_cast(reinterpret_cast(&turnsignal_) - + reinterpret_cast(&throttle_)) + sizeof(turnsignal_)); + // @@protoc_insertion_point(copy_constructor:apollo.control.ControlCommand) +} + +void ControlCommand::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&turnsignal_) - + reinterpret_cast(&header_)) + sizeof(turnsignal_)); +} + +ControlCommand::~ControlCommand() { + // @@protoc_insertion_point(destructor:apollo.control.ControlCommand) + SharedDtor(); +} + +void ControlCommand::SharedDtor() { + if (this != internal_default_instance()) delete header_; + if (this != internal_default_instance()) delete debug_; + if (this != internal_default_instance()) delete signal_; + if (this != internal_default_instance()) delete latency_stats_; + if (this != internal_default_instance()) delete pad_msg_; +} + +void ControlCommand::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ControlCommand::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ControlCommand& ControlCommand::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_ControlCommand.base); + return *internal_default_instance(); +} + + +void ControlCommand::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.ControlCommand) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + if (GetArenaNoVirtual() == NULL && debug_ != NULL) { + delete debug_; + } + debug_ = NULL; + if (GetArenaNoVirtual() == NULL && signal_ != NULL) { + delete signal_; + } + signal_ = NULL; + if (GetArenaNoVirtual() == NULL && latency_stats_ != NULL) { + delete latency_stats_; + } + latency_stats_ = NULL; + if (GetArenaNoVirtual() == NULL && pad_msg_ != NULL) { + delete pad_msg_; + } + pad_msg_ = NULL; + ::memset(&throttle_, 0, static_cast( + reinterpret_cast(&turnsignal_) - + reinterpret_cast(&throttle_)) + sizeof(turnsignal_)); + _internal_metadata_.Clear(); +} + +bool ControlCommand::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.ControlCommand) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // double throttle = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &throttle_))); + } else { + goto handle_unusual; + } + break; + } + + // double brake = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &brake_))); + } else { + goto handle_unusual; + } + break; + } + + // double steering_rate = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steering_rate_))); + } else { + goto handle_unusual; + } + break; + } + + // double steering_target = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steering_target_))); + } else { + goto handle_unusual; + } + break; + } + + // bool parking_brake = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(64u /* 64 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &parking_brake_))); + } else { + goto handle_unusual; + } + break; + } + + // double speed = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(73u /* 73 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &speed_))); + } else { + goto handle_unusual; + } + break; + } + + // double acceleration = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(81u /* 81 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &acceleration_))); + } else { + goto handle_unusual; + } + break; + } + + // bool high_beam = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(88u /* 88 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &high_beam_))); + } else { + goto handle_unusual; + } + break; + } + + // bool low_beam = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(96u /* 96 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &low_beam_))); + } else { + goto handle_unusual; + } + break; + } + + // bool left_turn = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(104u /* 104 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &left_turn_))); + } else { + goto handle_unusual; + } + break; + } + + // bool right_turn = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(112u /* 112 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &right_turn_))); + } else { + goto handle_unusual; + } + break; + } + + // bool horn = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(120u /* 120 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &horn_))); + } else { + goto handle_unusual; + } + break; + } + + // bool reset_model = 16; + case 16: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(128u /* 128 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &reset_model_))); + } else { + goto handle_unusual; + } + break; + } + + // bool engine_on_off = 17; + case 17: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(136u /* 136 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &engine_on_off_))); + } else { + goto handle_unusual; + } + break; + } + + // double trajectory_fraction = 18; + case 18: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(145u /* 145 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &trajectory_fraction_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 19; + case 19: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(152u /* 152 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_driving_mode(static_cast< ::apollo::canbus::Chassis_DrivingMode >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Chassis.GearPosition gear_location = 20; + case 20: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(160u /* 160 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_gear_location(static_cast< ::apollo::canbus::Chassis_GearPosition >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.TurnSignal turnsignal = 21; + case 21: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(168u /* 168 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_turnsignal(static_cast< ::apollo::control::TurnSignal >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.Debug debug = 22; + case 22: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(178u /* 178 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_debug())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Signal signal = 23; + case 23: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(186u /* 186 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_signal())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.LatencyStats latency_stats = 24; + case 24: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(194u /* 194 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_latency_stats())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.PadMessage pad_msg = 25; + case 25: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(202u /* 202 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_pad_msg())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.ControlCommand) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.ControlCommand) + return false; +#undef DO_ +} + +void ControlCommand::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.ControlCommand) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // double throttle = 3; + if (this->throttle() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->throttle(), output); + } + + // double brake = 4; + if (this->brake() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->brake(), output); + } + + // double steering_rate = 6; + if (this->steering_rate() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->steering_rate(), output); + } + + // double steering_target = 7; + if (this->steering_target() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->steering_target(), output); + } + + // bool parking_brake = 8; + if (this->parking_brake() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(8, this->parking_brake(), output); + } + + // double speed = 9; + if (this->speed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->speed(), output); + } + + // double acceleration = 10; + if (this->acceleration() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(10, this->acceleration(), output); + } + + // bool high_beam = 11; + if (this->high_beam() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(11, this->high_beam(), output); + } + + // bool low_beam = 12; + if (this->low_beam() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(12, this->low_beam(), output); + } + + // bool left_turn = 13; + if (this->left_turn() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(13, this->left_turn(), output); + } + + // bool right_turn = 14; + if (this->right_turn() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(14, this->right_turn(), output); + } + + // bool horn = 15; + if (this->horn() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(15, this->horn(), output); + } + + // bool reset_model = 16; + if (this->reset_model() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(16, this->reset_model(), output); + } + + // bool engine_on_off = 17; + if (this->engine_on_off() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(17, this->engine_on_off(), output); + } + + // double trajectory_fraction = 18; + if (this->trajectory_fraction() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(18, this->trajectory_fraction(), output); + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 19; + if (this->driving_mode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 19, this->driving_mode(), output); + } + + // .apollo.canbus.Chassis.GearPosition gear_location = 20; + if (this->gear_location() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 20, this->gear_location(), output); + } + + // .apollo.control.TurnSignal turnsignal = 21; + if (this->turnsignal() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 21, this->turnsignal(), output); + } + + // .apollo.control.Debug debug = 22; + if (this->has_debug()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 22, this->_internal_debug(), output); + } + + // .apollo.canbus.Signal signal = 23; + if (this->has_signal()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 23, this->_internal_signal(), output); + } + + // .apollo.control.LatencyStats latency_stats = 24; + if (this->has_latency_stats()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 24, this->_internal_latency_stats(), output); + } + + // .apollo.control.PadMessage pad_msg = 25; + if (this->has_pad_msg()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 25, this->_internal_pad_msg(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.ControlCommand) +} + +::google::protobuf::uint8* ControlCommand::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.ControlCommand) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // double throttle = 3; + if (this->throttle() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->throttle(), target); + } + + // double brake = 4; + if (this->brake() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->brake(), target); + } + + // double steering_rate = 6; + if (this->steering_rate() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->steering_rate(), target); + } + + // double steering_target = 7; + if (this->steering_target() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->steering_target(), target); + } + + // bool parking_brake = 8; + if (this->parking_brake() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(8, this->parking_brake(), target); + } + + // double speed = 9; + if (this->speed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->speed(), target); + } + + // double acceleration = 10; + if (this->acceleration() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(10, this->acceleration(), target); + } + + // bool high_beam = 11; + if (this->high_beam() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(11, this->high_beam(), target); + } + + // bool low_beam = 12; + if (this->low_beam() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(12, this->low_beam(), target); + } + + // bool left_turn = 13; + if (this->left_turn() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(13, this->left_turn(), target); + } + + // bool right_turn = 14; + if (this->right_turn() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(14, this->right_turn(), target); + } + + // bool horn = 15; + if (this->horn() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(15, this->horn(), target); + } + + // bool reset_model = 16; + if (this->reset_model() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(16, this->reset_model(), target); + } + + // bool engine_on_off = 17; + if (this->engine_on_off() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(17, this->engine_on_off(), target); + } + + // double trajectory_fraction = 18; + if (this->trajectory_fraction() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(18, this->trajectory_fraction(), target); + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 19; + if (this->driving_mode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 19, this->driving_mode(), target); + } + + // .apollo.canbus.Chassis.GearPosition gear_location = 20; + if (this->gear_location() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 20, this->gear_location(), target); + } + + // .apollo.control.TurnSignal turnsignal = 21; + if (this->turnsignal() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 21, this->turnsignal(), target); + } + + // .apollo.control.Debug debug = 22; + if (this->has_debug()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 22, this->_internal_debug(), deterministic, target); + } + + // .apollo.canbus.Signal signal = 23; + if (this->has_signal()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 23, this->_internal_signal(), deterministic, target); + } + + // .apollo.control.LatencyStats latency_stats = 24; + if (this->has_latency_stats()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 24, this->_internal_latency_stats(), deterministic, target); + } + + // .apollo.control.PadMessage pad_msg = 25; + if (this->has_pad_msg()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 25, this->_internal_pad_msg(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.ControlCommand) + return target; +} + +size_t ControlCommand::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.ControlCommand) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.control.Debug debug = 22; + if (this->has_debug()) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *debug_); + } + + // .apollo.canbus.Signal signal = 23; + if (this->has_signal()) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *signal_); + } + + // .apollo.control.LatencyStats latency_stats = 24; + if (this->has_latency_stats()) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *latency_stats_); + } + + // .apollo.control.PadMessage pad_msg = 25; + if (this->has_pad_msg()) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *pad_msg_); + } + + // double throttle = 3; + if (this->throttle() != 0) { + total_size += 1 + 8; + } + + // double brake = 4; + if (this->brake() != 0) { + total_size += 1 + 8; + } + + // double steering_rate = 6; + if (this->steering_rate() != 0) { + total_size += 1 + 8; + } + + // double steering_target = 7; + if (this->steering_target() != 0) { + total_size += 1 + 8; + } + + // double speed = 9; + if (this->speed() != 0) { + total_size += 1 + 8; + } + + // double acceleration = 10; + if (this->acceleration() != 0) { + total_size += 1 + 8; + } + + // bool right_turn = 14; + if (this->right_turn() != 0) { + total_size += 1 + 1; + } + + // bool high_beam = 11; + if (this->high_beam() != 0) { + total_size += 1 + 1; + } + + // bool low_beam = 12; + if (this->low_beam() != 0) { + total_size += 1 + 1; + } + + // bool horn = 15; + if (this->horn() != 0) { + total_size += 1 + 1; + } + + // bool parking_brake = 8; + if (this->parking_brake() != 0) { + total_size += 1 + 1; + } + + // bool reset_model = 16; + if (this->reset_model() != 0) { + total_size += 2 + 1; + } + + // bool engine_on_off = 17; + if (this->engine_on_off() != 0) { + total_size += 2 + 1; + } + + // bool left_turn = 13; + if (this->left_turn() != 0) { + total_size += 1 + 1; + } + + // double trajectory_fraction = 18; + if (this->trajectory_fraction() != 0) { + total_size += 2 + 8; + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 19; + if (this->driving_mode() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->driving_mode()); + } + + // .apollo.canbus.Chassis.GearPosition gear_location = 20; + if (this->gear_location() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->gear_location()); + } + + // .apollo.control.TurnSignal turnsignal = 21; + if (this->turnsignal() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->turnsignal()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ControlCommand::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.ControlCommand) + GOOGLE_DCHECK_NE(&from, this); + const ControlCommand* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.ControlCommand) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.ControlCommand) + MergeFrom(*source); + } +} + +void ControlCommand::MergeFrom(const ControlCommand& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.ControlCommand) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.has_debug()) { + mutable_debug()->::apollo::control::Debug::MergeFrom(from.debug()); + } + if (from.has_signal()) { + mutable_signal()->::apollo::canbus::Signal::MergeFrom(from.signal()); + } + if (from.has_latency_stats()) { + mutable_latency_stats()->::apollo::control::LatencyStats::MergeFrom(from.latency_stats()); + } + if (from.has_pad_msg()) { + mutable_pad_msg()->::apollo::control::PadMessage::MergeFrom(from.pad_msg()); + } + if (from.throttle() != 0) { + set_throttle(from.throttle()); + } + if (from.brake() != 0) { + set_brake(from.brake()); + } + if (from.steering_rate() != 0) { + set_steering_rate(from.steering_rate()); + } + if (from.steering_target() != 0) { + set_steering_target(from.steering_target()); + } + if (from.speed() != 0) { + set_speed(from.speed()); + } + if (from.acceleration() != 0) { + set_acceleration(from.acceleration()); + } + if (from.right_turn() != 0) { + set_right_turn(from.right_turn()); + } + if (from.high_beam() != 0) { + set_high_beam(from.high_beam()); + } + if (from.low_beam() != 0) { + set_low_beam(from.low_beam()); + } + if (from.horn() != 0) { + set_horn(from.horn()); + } + if (from.parking_brake() != 0) { + set_parking_brake(from.parking_brake()); + } + if (from.reset_model() != 0) { + set_reset_model(from.reset_model()); + } + if (from.engine_on_off() != 0) { + set_engine_on_off(from.engine_on_off()); + } + if (from.left_turn() != 0) { + set_left_turn(from.left_turn()); + } + if (from.trajectory_fraction() != 0) { + set_trajectory_fraction(from.trajectory_fraction()); + } + if (from.driving_mode() != 0) { + set_driving_mode(from.driving_mode()); + } + if (from.gear_location() != 0) { + set_gear_location(from.gear_location()); + } + if (from.turnsignal() != 0) { + set_turnsignal(from.turnsignal()); + } +} + +void ControlCommand::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.ControlCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ControlCommand::CopyFrom(const ControlCommand& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.ControlCommand) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ControlCommand::IsInitialized() const { + return true; +} + +void ControlCommand::Swap(ControlCommand* other) { + if (other == this) return; + InternalSwap(other); +} +void ControlCommand::InternalSwap(ControlCommand* other) { + using std::swap; + swap(header_, other->header_); + swap(debug_, other->debug_); + swap(signal_, other->signal_); + swap(latency_stats_, other->latency_stats_); + swap(pad_msg_, other->pad_msg_); + swap(throttle_, other->throttle_); + swap(brake_, other->brake_); + swap(steering_rate_, other->steering_rate_); + swap(steering_target_, other->steering_target_); + swap(speed_, other->speed_); + swap(acceleration_, other->acceleration_); + swap(right_turn_, other->right_turn_); + swap(high_beam_, other->high_beam_); + swap(low_beam_, other->low_beam_); + swap(horn_, other->horn_); + swap(parking_brake_, other->parking_brake_); + swap(reset_model_, other->reset_model_); + swap(engine_on_off_, other->engine_on_off_); + swap(left_turn_, other->left_turn_); + swap(trajectory_fraction_, other->trajectory_fraction_); + swap(driving_mode_, other->driving_mode_); + swap(gear_location_, other->gear_location_); + swap(turnsignal_, other->turnsignal_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ControlCommand::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void SimpleLongitudinalDebug::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int SimpleLongitudinalDebug::kStationReferenceFieldNumber; +const int SimpleLongitudinalDebug::kStationErrorFieldNumber; +const int SimpleLongitudinalDebug::kStationErrorLimitedFieldNumber; +const int SimpleLongitudinalDebug::kPreviewStationErrorFieldNumber; +const int SimpleLongitudinalDebug::kSpeedReferenceFieldNumber; +const int SimpleLongitudinalDebug::kSpeedErrorFieldNumber; +const int SimpleLongitudinalDebug::kSpeedControllerInputLimitedFieldNumber; +const int SimpleLongitudinalDebug::kPreviewSpeedReferenceFieldNumber; +const int SimpleLongitudinalDebug::kPreviewSpeedErrorFieldNumber; +const int SimpleLongitudinalDebug::kPreviewAccelerationReferenceFieldNumber; +const int SimpleLongitudinalDebug::kAccelerationCmdCloseloopFieldNumber; +const int SimpleLongitudinalDebug::kAccelerationCmdFieldNumber; +const int SimpleLongitudinalDebug::kAccelerationLookupFieldNumber; +const int SimpleLongitudinalDebug::kSpeedLookupFieldNumber; +const int SimpleLongitudinalDebug::kCalibrationValueFieldNumber; +const int SimpleLongitudinalDebug::kThrottleCmdFieldNumber; +const int SimpleLongitudinalDebug::kBrakeCmdFieldNumber; +const int SimpleLongitudinalDebug::kIsFullStopFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +SimpleLongitudinalDebug::SimpleLongitudinalDebug() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_SimpleLongitudinalDebug.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.SimpleLongitudinalDebug) +} +SimpleLongitudinalDebug::SimpleLongitudinalDebug(const SimpleLongitudinalDebug& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&station_reference_, &from.station_reference_, + static_cast(reinterpret_cast(&is_full_stop_) - + reinterpret_cast(&station_reference_)) + sizeof(is_full_stop_)); + // @@protoc_insertion_point(copy_constructor:apollo.control.SimpleLongitudinalDebug) +} + +void SimpleLongitudinalDebug::SharedCtor() { + ::memset(&station_reference_, 0, static_cast( + reinterpret_cast(&is_full_stop_) - + reinterpret_cast(&station_reference_)) + sizeof(is_full_stop_)); +} + +SimpleLongitudinalDebug::~SimpleLongitudinalDebug() { + // @@protoc_insertion_point(destructor:apollo.control.SimpleLongitudinalDebug) + SharedDtor(); +} + +void SimpleLongitudinalDebug::SharedDtor() { +} + +void SimpleLongitudinalDebug::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* SimpleLongitudinalDebug::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const SimpleLongitudinalDebug& SimpleLongitudinalDebug::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_SimpleLongitudinalDebug.base); + return *internal_default_instance(); +} + + +void SimpleLongitudinalDebug::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.SimpleLongitudinalDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&station_reference_, 0, static_cast( + reinterpret_cast(&is_full_stop_) - + reinterpret_cast(&station_reference_)) + sizeof(is_full_stop_)); + _internal_metadata_.Clear(); +} + +bool SimpleLongitudinalDebug::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.SimpleLongitudinalDebug) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double station_reference = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &station_reference_))); + } else { + goto handle_unusual; + } + break; + } + + // double station_error = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &station_error_))); + } else { + goto handle_unusual; + } + break; + } + + // double station_error_limited = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &station_error_limited_))); + } else { + goto handle_unusual; + } + break; + } + + // double preview_station_error = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &preview_station_error_))); + } else { + goto handle_unusual; + } + break; + } + + // double speed_reference = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &speed_reference_))); + } else { + goto handle_unusual; + } + break; + } + + // double speed_error = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &speed_error_))); + } else { + goto handle_unusual; + } + break; + } + + // double speed_controller_input_limited = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &speed_controller_input_limited_))); + } else { + goto handle_unusual; + } + break; + } + + // double preview_speed_reference = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(65u /* 65 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &preview_speed_reference_))); + } else { + goto handle_unusual; + } + break; + } + + // double preview_speed_error = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(73u /* 73 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &preview_speed_error_))); + } else { + goto handle_unusual; + } + break; + } + + // double preview_acceleration_reference = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(81u /* 81 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &preview_acceleration_reference_))); + } else { + goto handle_unusual; + } + break; + } + + // double acceleration_cmd_closeloop = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(89u /* 89 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &acceleration_cmd_closeloop_))); + } else { + goto handle_unusual; + } + break; + } + + // double acceleration_cmd = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(97u /* 97 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &acceleration_cmd_))); + } else { + goto handle_unusual; + } + break; + } + + // double acceleration_lookup = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(105u /* 105 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &acceleration_lookup_))); + } else { + goto handle_unusual; + } + break; + } + + // double speed_lookup = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(113u /* 113 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &speed_lookup_))); + } else { + goto handle_unusual; + } + break; + } + + // double calibration_value = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(121u /* 121 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &calibration_value_))); + } else { + goto handle_unusual; + } + break; + } + + // double throttle_cmd = 16; + case 16: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(129u /* 129 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &throttle_cmd_))); + } else { + goto handle_unusual; + } + break; + } + + // double brake_cmd = 17; + case 17: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(137u /* 137 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &brake_cmd_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_full_stop = 18; + case 18: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(144u /* 144 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_full_stop_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.SimpleLongitudinalDebug) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.SimpleLongitudinalDebug) + return false; +#undef DO_ +} + +void SimpleLongitudinalDebug::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.SimpleLongitudinalDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double station_reference = 1; + if (this->station_reference() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->station_reference(), output); + } + + // double station_error = 2; + if (this->station_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->station_error(), output); + } + + // double station_error_limited = 3; + if (this->station_error_limited() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->station_error_limited(), output); + } + + // double preview_station_error = 4; + if (this->preview_station_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->preview_station_error(), output); + } + + // double speed_reference = 5; + if (this->speed_reference() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->speed_reference(), output); + } + + // double speed_error = 6; + if (this->speed_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->speed_error(), output); + } + + // double speed_controller_input_limited = 7; + if (this->speed_controller_input_limited() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->speed_controller_input_limited(), output); + } + + // double preview_speed_reference = 8; + if (this->preview_speed_reference() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(8, this->preview_speed_reference(), output); + } + + // double preview_speed_error = 9; + if (this->preview_speed_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->preview_speed_error(), output); + } + + // double preview_acceleration_reference = 10; + if (this->preview_acceleration_reference() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(10, this->preview_acceleration_reference(), output); + } + + // double acceleration_cmd_closeloop = 11; + if (this->acceleration_cmd_closeloop() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(11, this->acceleration_cmd_closeloop(), output); + } + + // double acceleration_cmd = 12; + if (this->acceleration_cmd() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(12, this->acceleration_cmd(), output); + } + + // double acceleration_lookup = 13; + if (this->acceleration_lookup() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(13, this->acceleration_lookup(), output); + } + + // double speed_lookup = 14; + if (this->speed_lookup() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(14, this->speed_lookup(), output); + } + + // double calibration_value = 15; + if (this->calibration_value() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(15, this->calibration_value(), output); + } + + // double throttle_cmd = 16; + if (this->throttle_cmd() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(16, this->throttle_cmd(), output); + } + + // double brake_cmd = 17; + if (this->brake_cmd() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(17, this->brake_cmd(), output); + } + + // bool is_full_stop = 18; + if (this->is_full_stop() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(18, this->is_full_stop(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.SimpleLongitudinalDebug) +} + +::google::protobuf::uint8* SimpleLongitudinalDebug::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.SimpleLongitudinalDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double station_reference = 1; + if (this->station_reference() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->station_reference(), target); + } + + // double station_error = 2; + if (this->station_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->station_error(), target); + } + + // double station_error_limited = 3; + if (this->station_error_limited() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->station_error_limited(), target); + } + + // double preview_station_error = 4; + if (this->preview_station_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->preview_station_error(), target); + } + + // double speed_reference = 5; + if (this->speed_reference() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->speed_reference(), target); + } + + // double speed_error = 6; + if (this->speed_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->speed_error(), target); + } + + // double speed_controller_input_limited = 7; + if (this->speed_controller_input_limited() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->speed_controller_input_limited(), target); + } + + // double preview_speed_reference = 8; + if (this->preview_speed_reference() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(8, this->preview_speed_reference(), target); + } + + // double preview_speed_error = 9; + if (this->preview_speed_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->preview_speed_error(), target); + } + + // double preview_acceleration_reference = 10; + if (this->preview_acceleration_reference() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(10, this->preview_acceleration_reference(), target); + } + + // double acceleration_cmd_closeloop = 11; + if (this->acceleration_cmd_closeloop() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(11, this->acceleration_cmd_closeloop(), target); + } + + // double acceleration_cmd = 12; + if (this->acceleration_cmd() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(12, this->acceleration_cmd(), target); + } + + // double acceleration_lookup = 13; + if (this->acceleration_lookup() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(13, this->acceleration_lookup(), target); + } + + // double speed_lookup = 14; + if (this->speed_lookup() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(14, this->speed_lookup(), target); + } + + // double calibration_value = 15; + if (this->calibration_value() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(15, this->calibration_value(), target); + } + + // double throttle_cmd = 16; + if (this->throttle_cmd() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(16, this->throttle_cmd(), target); + } + + // double brake_cmd = 17; + if (this->brake_cmd() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(17, this->brake_cmd(), target); + } + + // bool is_full_stop = 18; + if (this->is_full_stop() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(18, this->is_full_stop(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.SimpleLongitudinalDebug) + return target; +} + +size_t SimpleLongitudinalDebug::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.SimpleLongitudinalDebug) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double station_reference = 1; + if (this->station_reference() != 0) { + total_size += 1 + 8; + } + + // double station_error = 2; + if (this->station_error() != 0) { + total_size += 1 + 8; + } + + // double station_error_limited = 3; + if (this->station_error_limited() != 0) { + total_size += 1 + 8; + } + + // double preview_station_error = 4; + if (this->preview_station_error() != 0) { + total_size += 1 + 8; + } + + // double speed_reference = 5; + if (this->speed_reference() != 0) { + total_size += 1 + 8; + } + + // double speed_error = 6; + if (this->speed_error() != 0) { + total_size += 1 + 8; + } + + // double speed_controller_input_limited = 7; + if (this->speed_controller_input_limited() != 0) { + total_size += 1 + 8; + } + + // double preview_speed_reference = 8; + if (this->preview_speed_reference() != 0) { + total_size += 1 + 8; + } + + // double preview_speed_error = 9; + if (this->preview_speed_error() != 0) { + total_size += 1 + 8; + } + + // double preview_acceleration_reference = 10; + if (this->preview_acceleration_reference() != 0) { + total_size += 1 + 8; + } + + // double acceleration_cmd_closeloop = 11; + if (this->acceleration_cmd_closeloop() != 0) { + total_size += 1 + 8; + } + + // double acceleration_cmd = 12; + if (this->acceleration_cmd() != 0) { + total_size += 1 + 8; + } + + // double acceleration_lookup = 13; + if (this->acceleration_lookup() != 0) { + total_size += 1 + 8; + } + + // double speed_lookup = 14; + if (this->speed_lookup() != 0) { + total_size += 1 + 8; + } + + // double calibration_value = 15; + if (this->calibration_value() != 0) { + total_size += 1 + 8; + } + + // double throttle_cmd = 16; + if (this->throttle_cmd() != 0) { + total_size += 2 + 8; + } + + // double brake_cmd = 17; + if (this->brake_cmd() != 0) { + total_size += 2 + 8; + } + + // bool is_full_stop = 18; + if (this->is_full_stop() != 0) { + total_size += 2 + 1; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void SimpleLongitudinalDebug::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.SimpleLongitudinalDebug) + GOOGLE_DCHECK_NE(&from, this); + const SimpleLongitudinalDebug* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.SimpleLongitudinalDebug) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.SimpleLongitudinalDebug) + MergeFrom(*source); + } +} + +void SimpleLongitudinalDebug::MergeFrom(const SimpleLongitudinalDebug& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.SimpleLongitudinalDebug) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.station_reference() != 0) { + set_station_reference(from.station_reference()); + } + if (from.station_error() != 0) { + set_station_error(from.station_error()); + } + if (from.station_error_limited() != 0) { + set_station_error_limited(from.station_error_limited()); + } + if (from.preview_station_error() != 0) { + set_preview_station_error(from.preview_station_error()); + } + if (from.speed_reference() != 0) { + set_speed_reference(from.speed_reference()); + } + if (from.speed_error() != 0) { + set_speed_error(from.speed_error()); + } + if (from.speed_controller_input_limited() != 0) { + set_speed_controller_input_limited(from.speed_controller_input_limited()); + } + if (from.preview_speed_reference() != 0) { + set_preview_speed_reference(from.preview_speed_reference()); + } + if (from.preview_speed_error() != 0) { + set_preview_speed_error(from.preview_speed_error()); + } + if (from.preview_acceleration_reference() != 0) { + set_preview_acceleration_reference(from.preview_acceleration_reference()); + } + if (from.acceleration_cmd_closeloop() != 0) { + set_acceleration_cmd_closeloop(from.acceleration_cmd_closeloop()); + } + if (from.acceleration_cmd() != 0) { + set_acceleration_cmd(from.acceleration_cmd()); + } + if (from.acceleration_lookup() != 0) { + set_acceleration_lookup(from.acceleration_lookup()); + } + if (from.speed_lookup() != 0) { + set_speed_lookup(from.speed_lookup()); + } + if (from.calibration_value() != 0) { + set_calibration_value(from.calibration_value()); + } + if (from.throttle_cmd() != 0) { + set_throttle_cmd(from.throttle_cmd()); + } + if (from.brake_cmd() != 0) { + set_brake_cmd(from.brake_cmd()); + } + if (from.is_full_stop() != 0) { + set_is_full_stop(from.is_full_stop()); + } +} + +void SimpleLongitudinalDebug::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.SimpleLongitudinalDebug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void SimpleLongitudinalDebug::CopyFrom(const SimpleLongitudinalDebug& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.SimpleLongitudinalDebug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SimpleLongitudinalDebug::IsInitialized() const { + return true; +} + +void SimpleLongitudinalDebug::Swap(SimpleLongitudinalDebug* other) { + if (other == this) return; + InternalSwap(other); +} +void SimpleLongitudinalDebug::InternalSwap(SimpleLongitudinalDebug* other) { + using std::swap; + swap(station_reference_, other->station_reference_); + swap(station_error_, other->station_error_); + swap(station_error_limited_, other->station_error_limited_); + swap(preview_station_error_, other->preview_station_error_); + swap(speed_reference_, other->speed_reference_); + swap(speed_error_, other->speed_error_); + swap(speed_controller_input_limited_, other->speed_controller_input_limited_); + swap(preview_speed_reference_, other->preview_speed_reference_); + swap(preview_speed_error_, other->preview_speed_error_); + swap(preview_acceleration_reference_, other->preview_acceleration_reference_); + swap(acceleration_cmd_closeloop_, other->acceleration_cmd_closeloop_); + swap(acceleration_cmd_, other->acceleration_cmd_); + swap(acceleration_lookup_, other->acceleration_lookup_); + swap(speed_lookup_, other->speed_lookup_); + swap(calibration_value_, other->calibration_value_); + swap(throttle_cmd_, other->throttle_cmd_); + swap(brake_cmd_, other->brake_cmd_); + swap(is_full_stop_, other->is_full_stop_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata SimpleLongitudinalDebug::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void SimpleLateralDebug::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int SimpleLateralDebug::kLateralErrorFieldNumber; +const int SimpleLateralDebug::kRefHeadingFieldNumber; +const int SimpleLateralDebug::kHeadingFieldNumber; +const int SimpleLateralDebug::kHeadingErrorFieldNumber; +const int SimpleLateralDebug::kHeadingErrorRateFieldNumber; +const int SimpleLateralDebug::kLateralErrorRateFieldNumber; +const int SimpleLateralDebug::kCurvatureFieldNumber; +const int SimpleLateralDebug::kSteerAngleFieldNumber; +const int SimpleLateralDebug::kSteerAngleFeedforwardFieldNumber; +const int SimpleLateralDebug::kSteerAngleLateralContributionFieldNumber; +const int SimpleLateralDebug::kSteerAngleLateralRateContributionFieldNumber; +const int SimpleLateralDebug::kSteerAngleHeadingContributionFieldNumber; +const int SimpleLateralDebug::kSteerAngleHeadingRateContributionFieldNumber; +const int SimpleLateralDebug::kSteerAngleFeedbackFieldNumber; +const int SimpleLateralDebug::kSteeringPositionFieldNumber; +const int SimpleLateralDebug::kRefSpeedFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +SimpleLateralDebug::SimpleLateralDebug() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_SimpleLateralDebug.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.SimpleLateralDebug) +} +SimpleLateralDebug::SimpleLateralDebug(const SimpleLateralDebug& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&lateral_error_, &from.lateral_error_, + static_cast(reinterpret_cast(&ref_speed_) - + reinterpret_cast(&lateral_error_)) + sizeof(ref_speed_)); + // @@protoc_insertion_point(copy_constructor:apollo.control.SimpleLateralDebug) +} + +void SimpleLateralDebug::SharedCtor() { + ::memset(&lateral_error_, 0, static_cast( + reinterpret_cast(&ref_speed_) - + reinterpret_cast(&lateral_error_)) + sizeof(ref_speed_)); +} + +SimpleLateralDebug::~SimpleLateralDebug() { + // @@protoc_insertion_point(destructor:apollo.control.SimpleLateralDebug) + SharedDtor(); +} + +void SimpleLateralDebug::SharedDtor() { +} + +void SimpleLateralDebug::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* SimpleLateralDebug::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const SimpleLateralDebug& SimpleLateralDebug::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_SimpleLateralDebug.base); + return *internal_default_instance(); +} + + +void SimpleLateralDebug::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.SimpleLateralDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&lateral_error_, 0, static_cast( + reinterpret_cast(&ref_speed_) - + reinterpret_cast(&lateral_error_)) + sizeof(ref_speed_)); + _internal_metadata_.Clear(); +} + +bool SimpleLateralDebug::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.SimpleLateralDebug) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double lateral_error = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lateral_error_))); + } else { + goto handle_unusual; + } + break; + } + + // double ref_heading = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &ref_heading_))); + } else { + goto handle_unusual; + } + break; + } + + // double heading = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &heading_))); + } else { + goto handle_unusual; + } + break; + } + + // double heading_error = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &heading_error_))); + } else { + goto handle_unusual; + } + break; + } + + // double heading_error_rate = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &heading_error_rate_))); + } else { + goto handle_unusual; + } + break; + } + + // double lateral_error_rate = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lateral_error_rate_))); + } else { + goto handle_unusual; + } + break; + } + + // double curvature = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &curvature_))); + } else { + goto handle_unusual; + } + break; + } + + // double steer_angle = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(65u /* 65 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steer_angle_))); + } else { + goto handle_unusual; + } + break; + } + + // double steer_angle_feedforward = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(73u /* 73 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steer_angle_feedforward_))); + } else { + goto handle_unusual; + } + break; + } + + // double steer_angle_lateral_contribution = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(81u /* 81 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steer_angle_lateral_contribution_))); + } else { + goto handle_unusual; + } + break; + } + + // double steer_angle_lateral_rate_contribution = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(89u /* 89 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steer_angle_lateral_rate_contribution_))); + } else { + goto handle_unusual; + } + break; + } + + // double steer_angle_heading_contribution = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(97u /* 97 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steer_angle_heading_contribution_))); + } else { + goto handle_unusual; + } + break; + } + + // double steer_angle_heading_rate_contribution = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(105u /* 105 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steer_angle_heading_rate_contribution_))); + } else { + goto handle_unusual; + } + break; + } + + // double steer_angle_feedback = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(113u /* 113 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steer_angle_feedback_))); + } else { + goto handle_unusual; + } + break; + } + + // double steering_position = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(121u /* 121 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &steering_position_))); + } else { + goto handle_unusual; + } + break; + } + + // double ref_speed = 16; + case 16: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(129u /* 129 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &ref_speed_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.SimpleLateralDebug) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.SimpleLateralDebug) + return false; +#undef DO_ +} + +void SimpleLateralDebug::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.SimpleLateralDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double lateral_error = 1; + if (this->lateral_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->lateral_error(), output); + } + + // double ref_heading = 2; + if (this->ref_heading() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->ref_heading(), output); + } + + // double heading = 3; + if (this->heading() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->heading(), output); + } + + // double heading_error = 4; + if (this->heading_error() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->heading_error(), output); + } + + // double heading_error_rate = 5; + if (this->heading_error_rate() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->heading_error_rate(), output); + } + + // double lateral_error_rate = 6; + if (this->lateral_error_rate() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->lateral_error_rate(), output); + } + + // double curvature = 7; + if (this->curvature() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->curvature(), output); + } + + // double steer_angle = 8; + if (this->steer_angle() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(8, this->steer_angle(), output); + } + + // double steer_angle_feedforward = 9; + if (this->steer_angle_feedforward() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->steer_angle_feedforward(), output); + } + + // double steer_angle_lateral_contribution = 10; + if (this->steer_angle_lateral_contribution() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(10, this->steer_angle_lateral_contribution(), output); + } + + // double steer_angle_lateral_rate_contribution = 11; + if (this->steer_angle_lateral_rate_contribution() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(11, this->steer_angle_lateral_rate_contribution(), output); + } + + // double steer_angle_heading_contribution = 12; + if (this->steer_angle_heading_contribution() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(12, this->steer_angle_heading_contribution(), output); + } + + // double steer_angle_heading_rate_contribution = 13; + if (this->steer_angle_heading_rate_contribution() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(13, this->steer_angle_heading_rate_contribution(), output); + } + + // double steer_angle_feedback = 14; + if (this->steer_angle_feedback() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(14, this->steer_angle_feedback(), output); + } + + // double steering_position = 15; + if (this->steering_position() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(15, this->steering_position(), output); + } + + // double ref_speed = 16; + if (this->ref_speed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(16, this->ref_speed(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.SimpleLateralDebug) +} + +::google::protobuf::uint8* SimpleLateralDebug::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.SimpleLateralDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double lateral_error = 1; + if (this->lateral_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->lateral_error(), target); + } + + // double ref_heading = 2; + if (this->ref_heading() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->ref_heading(), target); + } + + // double heading = 3; + if (this->heading() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->heading(), target); + } + + // double heading_error = 4; + if (this->heading_error() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->heading_error(), target); + } + + // double heading_error_rate = 5; + if (this->heading_error_rate() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->heading_error_rate(), target); + } + + // double lateral_error_rate = 6; + if (this->lateral_error_rate() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->lateral_error_rate(), target); + } + + // double curvature = 7; + if (this->curvature() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->curvature(), target); + } + + // double steer_angle = 8; + if (this->steer_angle() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(8, this->steer_angle(), target); + } + + // double steer_angle_feedforward = 9; + if (this->steer_angle_feedforward() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->steer_angle_feedforward(), target); + } + + // double steer_angle_lateral_contribution = 10; + if (this->steer_angle_lateral_contribution() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(10, this->steer_angle_lateral_contribution(), target); + } + + // double steer_angle_lateral_rate_contribution = 11; + if (this->steer_angle_lateral_rate_contribution() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(11, this->steer_angle_lateral_rate_contribution(), target); + } + + // double steer_angle_heading_contribution = 12; + if (this->steer_angle_heading_contribution() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(12, this->steer_angle_heading_contribution(), target); + } + + // double steer_angle_heading_rate_contribution = 13; + if (this->steer_angle_heading_rate_contribution() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(13, this->steer_angle_heading_rate_contribution(), target); + } + + // double steer_angle_feedback = 14; + if (this->steer_angle_feedback() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(14, this->steer_angle_feedback(), target); + } + + // double steering_position = 15; + if (this->steering_position() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(15, this->steering_position(), target); + } + + // double ref_speed = 16; + if (this->ref_speed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(16, this->ref_speed(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.SimpleLateralDebug) + return target; +} + +size_t SimpleLateralDebug::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.SimpleLateralDebug) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double lateral_error = 1; + if (this->lateral_error() != 0) { + total_size += 1 + 8; + } + + // double ref_heading = 2; + if (this->ref_heading() != 0) { + total_size += 1 + 8; + } + + // double heading = 3; + if (this->heading() != 0) { + total_size += 1 + 8; + } + + // double heading_error = 4; + if (this->heading_error() != 0) { + total_size += 1 + 8; + } + + // double heading_error_rate = 5; + if (this->heading_error_rate() != 0) { + total_size += 1 + 8; + } + + // double lateral_error_rate = 6; + if (this->lateral_error_rate() != 0) { + total_size += 1 + 8; + } + + // double curvature = 7; + if (this->curvature() != 0) { + total_size += 1 + 8; + } + + // double steer_angle = 8; + if (this->steer_angle() != 0) { + total_size += 1 + 8; + } + + // double steer_angle_feedforward = 9; + if (this->steer_angle_feedforward() != 0) { + total_size += 1 + 8; + } + + // double steer_angle_lateral_contribution = 10; + if (this->steer_angle_lateral_contribution() != 0) { + total_size += 1 + 8; + } + + // double steer_angle_lateral_rate_contribution = 11; + if (this->steer_angle_lateral_rate_contribution() != 0) { + total_size += 1 + 8; + } + + // double steer_angle_heading_contribution = 12; + if (this->steer_angle_heading_contribution() != 0) { + total_size += 1 + 8; + } + + // double steer_angle_heading_rate_contribution = 13; + if (this->steer_angle_heading_rate_contribution() != 0) { + total_size += 1 + 8; + } + + // double steer_angle_feedback = 14; + if (this->steer_angle_feedback() != 0) { + total_size += 1 + 8; + } + + // double steering_position = 15; + if (this->steering_position() != 0) { + total_size += 1 + 8; + } + + // double ref_speed = 16; + if (this->ref_speed() != 0) { + total_size += 2 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void SimpleLateralDebug::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.SimpleLateralDebug) + GOOGLE_DCHECK_NE(&from, this); + const SimpleLateralDebug* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.SimpleLateralDebug) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.SimpleLateralDebug) + MergeFrom(*source); + } +} + +void SimpleLateralDebug::MergeFrom(const SimpleLateralDebug& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.SimpleLateralDebug) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.lateral_error() != 0) { + set_lateral_error(from.lateral_error()); + } + if (from.ref_heading() != 0) { + set_ref_heading(from.ref_heading()); + } + if (from.heading() != 0) { + set_heading(from.heading()); + } + if (from.heading_error() != 0) { + set_heading_error(from.heading_error()); + } + if (from.heading_error_rate() != 0) { + set_heading_error_rate(from.heading_error_rate()); + } + if (from.lateral_error_rate() != 0) { + set_lateral_error_rate(from.lateral_error_rate()); + } + if (from.curvature() != 0) { + set_curvature(from.curvature()); + } + if (from.steer_angle() != 0) { + set_steer_angle(from.steer_angle()); + } + if (from.steer_angle_feedforward() != 0) { + set_steer_angle_feedforward(from.steer_angle_feedforward()); + } + if (from.steer_angle_lateral_contribution() != 0) { + set_steer_angle_lateral_contribution(from.steer_angle_lateral_contribution()); + } + if (from.steer_angle_lateral_rate_contribution() != 0) { + set_steer_angle_lateral_rate_contribution(from.steer_angle_lateral_rate_contribution()); + } + if (from.steer_angle_heading_contribution() != 0) { + set_steer_angle_heading_contribution(from.steer_angle_heading_contribution()); + } + if (from.steer_angle_heading_rate_contribution() != 0) { + set_steer_angle_heading_rate_contribution(from.steer_angle_heading_rate_contribution()); + } + if (from.steer_angle_feedback() != 0) { + set_steer_angle_feedback(from.steer_angle_feedback()); + } + if (from.steering_position() != 0) { + set_steering_position(from.steering_position()); + } + if (from.ref_speed() != 0) { + set_ref_speed(from.ref_speed()); + } +} + +void SimpleLateralDebug::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.SimpleLateralDebug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void SimpleLateralDebug::CopyFrom(const SimpleLateralDebug& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.SimpleLateralDebug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SimpleLateralDebug::IsInitialized() const { + return true; +} + +void SimpleLateralDebug::Swap(SimpleLateralDebug* other) { + if (other == this) return; + InternalSwap(other); +} +void SimpleLateralDebug::InternalSwap(SimpleLateralDebug* other) { + using std::swap; + swap(lateral_error_, other->lateral_error_); + swap(ref_heading_, other->ref_heading_); + swap(heading_, other->heading_); + swap(heading_error_, other->heading_error_); + swap(heading_error_rate_, other->heading_error_rate_); + swap(lateral_error_rate_, other->lateral_error_rate_); + swap(curvature_, other->curvature_); + swap(steer_angle_, other->steer_angle_); + swap(steer_angle_feedforward_, other->steer_angle_feedforward_); + swap(steer_angle_lateral_contribution_, other->steer_angle_lateral_contribution_); + swap(steer_angle_lateral_rate_contribution_, other->steer_angle_lateral_rate_contribution_); + swap(steer_angle_heading_contribution_, other->steer_angle_heading_contribution_); + swap(steer_angle_heading_rate_contribution_, other->steer_angle_heading_rate_contribution_); + swap(steer_angle_feedback_, other->steer_angle_feedback_); + swap(steering_position_, other->steering_position_); + swap(ref_speed_, other->ref_speed_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata SimpleLateralDebug::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void InputDebug::InitAsDefaultInstance() { + ::apollo::control::_InputDebug_default_instance_._instance.get_mutable()->localization_header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); + ::apollo::control::_InputDebug_default_instance_._instance.get_mutable()->canbus_header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); + ::apollo::control::_InputDebug_default_instance_._instance.get_mutable()->trajectory_header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); +} +void InputDebug::clear_localization_header() { + if (GetArenaNoVirtual() == NULL && localization_header_ != NULL) { + delete localization_header_; + } + localization_header_ = NULL; +} +void InputDebug::clear_canbus_header() { + if (GetArenaNoVirtual() == NULL && canbus_header_ != NULL) { + delete canbus_header_; + } + canbus_header_ = NULL; +} +void InputDebug::clear_trajectory_header() { + if (GetArenaNoVirtual() == NULL && trajectory_header_ != NULL) { + delete trajectory_header_; + } + trajectory_header_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int InputDebug::kLocalizationHeaderFieldNumber; +const int InputDebug::kCanbusHeaderFieldNumber; +const int InputDebug::kTrajectoryHeaderFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +InputDebug::InputDebug() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_InputDebug.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.InputDebug) +} +InputDebug::InputDebug(const InputDebug& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_localization_header()) { + localization_header_ = new ::apollo::common::Header(*from.localization_header_); + } else { + localization_header_ = NULL; + } + if (from.has_canbus_header()) { + canbus_header_ = new ::apollo::common::Header(*from.canbus_header_); + } else { + canbus_header_ = NULL; + } + if (from.has_trajectory_header()) { + trajectory_header_ = new ::apollo::common::Header(*from.trajectory_header_); + } else { + trajectory_header_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.control.InputDebug) +} + +void InputDebug::SharedCtor() { + ::memset(&localization_header_, 0, static_cast( + reinterpret_cast(&trajectory_header_) - + reinterpret_cast(&localization_header_)) + sizeof(trajectory_header_)); +} + +InputDebug::~InputDebug() { + // @@protoc_insertion_point(destructor:apollo.control.InputDebug) + SharedDtor(); +} + +void InputDebug::SharedDtor() { + if (this != internal_default_instance()) delete localization_header_; + if (this != internal_default_instance()) delete canbus_header_; + if (this != internal_default_instance()) delete trajectory_header_; +} + +void InputDebug::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* InputDebug::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const InputDebug& InputDebug::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_InputDebug.base); + return *internal_default_instance(); +} + + +void InputDebug::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.InputDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && localization_header_ != NULL) { + delete localization_header_; + } + localization_header_ = NULL; + if (GetArenaNoVirtual() == NULL && canbus_header_ != NULL) { + delete canbus_header_; + } + canbus_header_ = NULL; + if (GetArenaNoVirtual() == NULL && trajectory_header_ != NULL) { + delete trajectory_header_; + } + trajectory_header_ = NULL; + _internal_metadata_.Clear(); +} + +bool InputDebug::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.InputDebug) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header localization_header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_localization_header())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Header canbus_header = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_canbus_header())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Header trajectory_header = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_trajectory_header())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.InputDebug) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.InputDebug) + return false; +#undef DO_ +} + +void InputDebug::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.InputDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header localization_header = 1; + if (this->has_localization_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_localization_header(), output); + } + + // .apollo.common.Header canbus_header = 2; + if (this->has_canbus_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_canbus_header(), output); + } + + // .apollo.common.Header trajectory_header = 3; + if (this->has_trajectory_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_trajectory_header(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.InputDebug) +} + +::google::protobuf::uint8* InputDebug::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.InputDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header localization_header = 1; + if (this->has_localization_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_localization_header(), deterministic, target); + } + + // .apollo.common.Header canbus_header = 2; + if (this->has_canbus_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_canbus_header(), deterministic, target); + } + + // .apollo.common.Header trajectory_header = 3; + if (this->has_trajectory_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_trajectory_header(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.InputDebug) + return target; +} + +size_t InputDebug::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.InputDebug) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.Header localization_header = 1; + if (this->has_localization_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *localization_header_); + } + + // .apollo.common.Header canbus_header = 2; + if (this->has_canbus_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *canbus_header_); + } + + // .apollo.common.Header trajectory_header = 3; + if (this->has_trajectory_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *trajectory_header_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void InputDebug::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.InputDebug) + GOOGLE_DCHECK_NE(&from, this); + const InputDebug* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.InputDebug) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.InputDebug) + MergeFrom(*source); + } +} + +void InputDebug::MergeFrom(const InputDebug& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.InputDebug) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_localization_header()) { + mutable_localization_header()->::apollo::common::Header::MergeFrom(from.localization_header()); + } + if (from.has_canbus_header()) { + mutable_canbus_header()->::apollo::common::Header::MergeFrom(from.canbus_header()); + } + if (from.has_trajectory_header()) { + mutable_trajectory_header()->::apollo::common::Header::MergeFrom(from.trajectory_header()); + } +} + +void InputDebug::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.InputDebug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void InputDebug::CopyFrom(const InputDebug& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.InputDebug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool InputDebug::IsInitialized() const { + return true; +} + +void InputDebug::Swap(InputDebug* other) { + if (other == this) return; + InternalSwap(other); +} +void InputDebug::InternalSwap(InputDebug* other) { + using std::swap; + swap(localization_header_, other->localization_header_); + swap(canbus_header_, other->canbus_header_); + swap(trajectory_header_, other->trajectory_header_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata InputDebug::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Debug::InitAsDefaultInstance() { + ::apollo::control::_Debug_default_instance_._instance.get_mutable()->simple_lon_debug_ = const_cast< ::apollo::control::SimpleLongitudinalDebug*>( + ::apollo::control::SimpleLongitudinalDebug::internal_default_instance()); + ::apollo::control::_Debug_default_instance_._instance.get_mutable()->simple_lat_debug_ = const_cast< ::apollo::control::SimpleLateralDebug*>( + ::apollo::control::SimpleLateralDebug::internal_default_instance()); + ::apollo::control::_Debug_default_instance_._instance.get_mutable()->input_debug_ = const_cast< ::apollo::control::InputDebug*>( + ::apollo::control::InputDebug::internal_default_instance()); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Debug::kSimpleLonDebugFieldNumber; +const int Debug::kSimpleLatDebugFieldNumber; +const int Debug::kInputDebugFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Debug::Debug() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_Debug.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.Debug) +} +Debug::Debug(const Debug& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_simple_lon_debug()) { + simple_lon_debug_ = new ::apollo::control::SimpleLongitudinalDebug(*from.simple_lon_debug_); + } else { + simple_lon_debug_ = NULL; + } + if (from.has_simple_lat_debug()) { + simple_lat_debug_ = new ::apollo::control::SimpleLateralDebug(*from.simple_lat_debug_); + } else { + simple_lat_debug_ = NULL; + } + if (from.has_input_debug()) { + input_debug_ = new ::apollo::control::InputDebug(*from.input_debug_); + } else { + input_debug_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.control.Debug) +} + +void Debug::SharedCtor() { + ::memset(&simple_lon_debug_, 0, static_cast( + reinterpret_cast(&input_debug_) - + reinterpret_cast(&simple_lon_debug_)) + sizeof(input_debug_)); +} + +Debug::~Debug() { + // @@protoc_insertion_point(destructor:apollo.control.Debug) + SharedDtor(); +} + +void Debug::SharedDtor() { + if (this != internal_default_instance()) delete simple_lon_debug_; + if (this != internal_default_instance()) delete simple_lat_debug_; + if (this != internal_default_instance()) delete input_debug_; +} + +void Debug::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Debug::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Debug& Debug::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::scc_info_Debug.base); + return *internal_default_instance(); +} + + +void Debug::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.Debug) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && simple_lon_debug_ != NULL) { + delete simple_lon_debug_; + } + simple_lon_debug_ = NULL; + if (GetArenaNoVirtual() == NULL && simple_lat_debug_ != NULL) { + delete simple_lat_debug_; + } + simple_lat_debug_ = NULL; + if (GetArenaNoVirtual() == NULL && input_debug_ != NULL) { + delete input_debug_; + } + input_debug_ = NULL; + _internal_metadata_.Clear(); +} + +bool Debug::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.Debug) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.control.SimpleLongitudinalDebug simple_lon_debug = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_simple_lon_debug())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.SimpleLateralDebug simple_lat_debug = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_simple_lat_debug())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.InputDebug input_debug = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_input_debug())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.Debug) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.Debug) + return false; +#undef DO_ +} + +void Debug::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.Debug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.control.SimpleLongitudinalDebug simple_lon_debug = 1; + if (this->has_simple_lon_debug()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_simple_lon_debug(), output); + } + + // .apollo.control.SimpleLateralDebug simple_lat_debug = 2; + if (this->has_simple_lat_debug()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_simple_lat_debug(), output); + } + + // .apollo.control.InputDebug input_debug = 3; + if (this->has_input_debug()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_input_debug(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.Debug) +} + +::google::protobuf::uint8* Debug::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.Debug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.control.SimpleLongitudinalDebug simple_lon_debug = 1; + if (this->has_simple_lon_debug()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_simple_lon_debug(), deterministic, target); + } + + // .apollo.control.SimpleLateralDebug simple_lat_debug = 2; + if (this->has_simple_lat_debug()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_simple_lat_debug(), deterministic, target); + } + + // .apollo.control.InputDebug input_debug = 3; + if (this->has_input_debug()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_input_debug(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.Debug) + return target; +} + +size_t Debug::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.Debug) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.control.SimpleLongitudinalDebug simple_lon_debug = 1; + if (this->has_simple_lon_debug()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *simple_lon_debug_); + } + + // .apollo.control.SimpleLateralDebug simple_lat_debug = 2; + if (this->has_simple_lat_debug()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *simple_lat_debug_); + } + + // .apollo.control.InputDebug input_debug = 3; + if (this->has_input_debug()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *input_debug_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Debug::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.Debug) + GOOGLE_DCHECK_NE(&from, this); + const Debug* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.Debug) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.Debug) + MergeFrom(*source); + } +} + +void Debug::MergeFrom(const Debug& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.Debug) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_simple_lon_debug()) { + mutable_simple_lon_debug()->::apollo::control::SimpleLongitudinalDebug::MergeFrom(from.simple_lon_debug()); + } + if (from.has_simple_lat_debug()) { + mutable_simple_lat_debug()->::apollo::control::SimpleLateralDebug::MergeFrom(from.simple_lat_debug()); + } + if (from.has_input_debug()) { + mutable_input_debug()->::apollo::control::InputDebug::MergeFrom(from.input_debug()); + } +} + +void Debug::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.Debug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Debug::CopyFrom(const Debug& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.Debug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Debug::IsInitialized() const { + return true; +} + +void Debug::Swap(Debug* other) { + if (other == this) return; + InternalSwap(other); +} +void Debug::InternalSwap(Debug* other) { + using std::swap; + swap(simple_lon_debug_, other->simple_lon_debug_); + swap(simple_lat_debug_, other->simple_lat_debug_); + swap(input_debug_, other->input_debug_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Debug::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace control +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::LatencyStats* Arena::CreateMaybeMessage< ::apollo::control::LatencyStats >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::LatencyStats >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::ControlCommand* Arena::CreateMaybeMessage< ::apollo::control::ControlCommand >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::ControlCommand >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::SimpleLongitudinalDebug* Arena::CreateMaybeMessage< ::apollo::control::SimpleLongitudinalDebug >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::SimpleLongitudinalDebug >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::SimpleLateralDebug* Arena::CreateMaybeMessage< ::apollo::control::SimpleLateralDebug >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::SimpleLateralDebug >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::InputDebug* Arena::CreateMaybeMessage< ::apollo::control::InputDebug >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::InputDebug >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::Debug* Arena::CreateMaybeMessage< ::apollo::control::Debug >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::Debug >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/control/control_cmd.pb.h b/apollo_msgs/include/apollo_msgs/proto/control/control_cmd.pb.h new file mode 100644 index 0000000..e9107ca --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/control/control_cmd.pb.h @@ -0,0 +1,2607 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/control/control_cmd.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "apollo_msgs/proto/canbus/chassis.pb.h" +#include "apollo_msgs/proto/common/header.pb.h" +#include "apollo_msgs/proto/control/pad_msg.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[6]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto +namespace apollo { +namespace control { +class ControlCommand; +class ControlCommandDefaultTypeInternal; +extern ControlCommandDefaultTypeInternal _ControlCommand_default_instance_; +class Debug; +class DebugDefaultTypeInternal; +extern DebugDefaultTypeInternal _Debug_default_instance_; +class InputDebug; +class InputDebugDefaultTypeInternal; +extern InputDebugDefaultTypeInternal _InputDebug_default_instance_; +class LatencyStats; +class LatencyStatsDefaultTypeInternal; +extern LatencyStatsDefaultTypeInternal _LatencyStats_default_instance_; +class SimpleLateralDebug; +class SimpleLateralDebugDefaultTypeInternal; +extern SimpleLateralDebugDefaultTypeInternal _SimpleLateralDebug_default_instance_; +class SimpleLongitudinalDebug; +class SimpleLongitudinalDebugDefaultTypeInternal; +extern SimpleLongitudinalDebugDefaultTypeInternal _SimpleLongitudinalDebug_default_instance_; +} // namespace control +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::control::ControlCommand* Arena::CreateMaybeMessage<::apollo::control::ControlCommand>(Arena*); +template<> ::apollo::control::Debug* Arena::CreateMaybeMessage<::apollo::control::Debug>(Arena*); +template<> ::apollo::control::InputDebug* Arena::CreateMaybeMessage<::apollo::control::InputDebug>(Arena*); +template<> ::apollo::control::LatencyStats* Arena::CreateMaybeMessage<::apollo::control::LatencyStats>(Arena*); +template<> ::apollo::control::SimpleLateralDebug* Arena::CreateMaybeMessage<::apollo::control::SimpleLateralDebug>(Arena*); +template<> ::apollo::control::SimpleLongitudinalDebug* Arena::CreateMaybeMessage<::apollo::control::SimpleLongitudinalDebug>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace control { + +enum TurnSignal { + TURN_NONE = 0, + TURN_LEFT = 1, + TURN_RIGHT = 2, + TurnSignal_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + TurnSignal_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool TurnSignal_IsValid(int value); +const TurnSignal TurnSignal_MIN = TURN_NONE; +const TurnSignal TurnSignal_MAX = TURN_RIGHT; +const int TurnSignal_ARRAYSIZE = TurnSignal_MAX + 1; + +const ::google::protobuf::EnumDescriptor* TurnSignal_descriptor(); +inline const ::std::string& TurnSignal_Name(TurnSignal value) { + return ::google::protobuf::internal::NameOfEnum( + TurnSignal_descriptor(), value); +} +inline bool TurnSignal_Parse( + const ::std::string& name, TurnSignal* value) { + return ::google::protobuf::internal::ParseNamedEnum( + TurnSignal_descriptor(), name, value); +} +// =================================================================== + +class LatencyStats : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.LatencyStats) */ { + public: + LatencyStats(); + virtual ~LatencyStats(); + + LatencyStats(const LatencyStats& from); + + inline LatencyStats& operator=(const LatencyStats& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + LatencyStats(LatencyStats&& from) noexcept + : LatencyStats() { + *this = ::std::move(from); + } + + inline LatencyStats& operator=(LatencyStats&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const LatencyStats& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const LatencyStats* internal_default_instance() { + return reinterpret_cast( + &_LatencyStats_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(LatencyStats* other); + friend void swap(LatencyStats& a, LatencyStats& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline LatencyStats* New() const final { + return CreateMaybeMessage(NULL); + } + + LatencyStats* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const LatencyStats& from); + void MergeFrom(const LatencyStats& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(LatencyStats* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated double controller_time_ms = 2; + int controller_time_ms_size() const; + void clear_controller_time_ms(); + static const int kControllerTimeMsFieldNumber = 2; + double controller_time_ms(int index) const; + void set_controller_time_ms(int index, double value); + void add_controller_time_ms(double value); + const ::google::protobuf::RepeatedField< double >& + controller_time_ms() const; + ::google::protobuf::RepeatedField< double >* + mutable_controller_time_ms(); + + // double total_time_ms = 1; + void clear_total_time_ms(); + static const int kTotalTimeMsFieldNumber = 1; + double total_time_ms() const; + void set_total_time_ms(double value); + + // @@protoc_insertion_point(class_scope:apollo.control.LatencyStats) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedField< double > controller_time_ms_; + mutable int _controller_time_ms_cached_byte_size_; + double total_time_ms_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ControlCommand : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.ControlCommand) */ { + public: + ControlCommand(); + virtual ~ControlCommand(); + + ControlCommand(const ControlCommand& from); + + inline ControlCommand& operator=(const ControlCommand& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ControlCommand(ControlCommand&& from) noexcept + : ControlCommand() { + *this = ::std::move(from); + } + + inline ControlCommand& operator=(ControlCommand&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ControlCommand& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ControlCommand* internal_default_instance() { + return reinterpret_cast( + &_ControlCommand_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(ControlCommand* other); + friend void swap(ControlCommand& a, ControlCommand& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ControlCommand* New() const final { + return CreateMaybeMessage(NULL); + } + + ControlCommand* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ControlCommand& from); + void MergeFrom(const ControlCommand& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ControlCommand* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.control.Debug debug = 22; + bool has_debug() const; + void clear_debug(); + static const int kDebugFieldNumber = 22; + private: + const ::apollo::control::Debug& _internal_debug() const; + public: + const ::apollo::control::Debug& debug() const; + ::apollo::control::Debug* release_debug(); + ::apollo::control::Debug* mutable_debug(); + void set_allocated_debug(::apollo::control::Debug* debug); + + // .apollo.canbus.Signal signal = 23; + bool has_signal() const; + void clear_signal(); + static const int kSignalFieldNumber = 23; + private: + const ::apollo::canbus::Signal& _internal_signal() const; + public: + const ::apollo::canbus::Signal& signal() const; + ::apollo::canbus::Signal* release_signal(); + ::apollo::canbus::Signal* mutable_signal(); + void set_allocated_signal(::apollo::canbus::Signal* signal); + + // .apollo.control.LatencyStats latency_stats = 24; + bool has_latency_stats() const; + void clear_latency_stats(); + static const int kLatencyStatsFieldNumber = 24; + private: + const ::apollo::control::LatencyStats& _internal_latency_stats() const; + public: + const ::apollo::control::LatencyStats& latency_stats() const; + ::apollo::control::LatencyStats* release_latency_stats(); + ::apollo::control::LatencyStats* mutable_latency_stats(); + void set_allocated_latency_stats(::apollo::control::LatencyStats* latency_stats); + + // .apollo.control.PadMessage pad_msg = 25; + bool has_pad_msg() const; + void clear_pad_msg(); + static const int kPadMsgFieldNumber = 25; + private: + const ::apollo::control::PadMessage& _internal_pad_msg() const; + public: + const ::apollo::control::PadMessage& pad_msg() const; + ::apollo::control::PadMessage* release_pad_msg(); + ::apollo::control::PadMessage* mutable_pad_msg(); + void set_allocated_pad_msg(::apollo::control::PadMessage* pad_msg); + + // double throttle = 3; + void clear_throttle(); + static const int kThrottleFieldNumber = 3; + double throttle() const; + void set_throttle(double value); + + // double brake = 4; + void clear_brake(); + static const int kBrakeFieldNumber = 4; + double brake() const; + void set_brake(double value); + + // double steering_rate = 6; + void clear_steering_rate(); + static const int kSteeringRateFieldNumber = 6; + double steering_rate() const; + void set_steering_rate(double value); + + // double steering_target = 7; + void clear_steering_target(); + static const int kSteeringTargetFieldNumber = 7; + double steering_target() const; + void set_steering_target(double value); + + // double speed = 9; + void clear_speed(); + static const int kSpeedFieldNumber = 9; + double speed() const; + void set_speed(double value); + + // double acceleration = 10; + void clear_acceleration(); + static const int kAccelerationFieldNumber = 10; + double acceleration() const; + void set_acceleration(double value); + + // bool right_turn = 14; + void clear_right_turn(); + static const int kRightTurnFieldNumber = 14; + bool right_turn() const; + void set_right_turn(bool value); + + // bool high_beam = 11; + void clear_high_beam(); + static const int kHighBeamFieldNumber = 11; + bool high_beam() const; + void set_high_beam(bool value); + + // bool low_beam = 12; + void clear_low_beam(); + static const int kLowBeamFieldNumber = 12; + bool low_beam() const; + void set_low_beam(bool value); + + // bool horn = 15; + void clear_horn(); + static const int kHornFieldNumber = 15; + bool horn() const; + void set_horn(bool value); + + // bool parking_brake = 8; + void clear_parking_brake(); + static const int kParkingBrakeFieldNumber = 8; + bool parking_brake() const; + void set_parking_brake(bool value); + + // bool reset_model = 16; + void clear_reset_model(); + static const int kResetModelFieldNumber = 16; + bool reset_model() const; + void set_reset_model(bool value); + + // bool engine_on_off = 17; + void clear_engine_on_off(); + static const int kEngineOnOffFieldNumber = 17; + bool engine_on_off() const; + void set_engine_on_off(bool value); + + // bool left_turn = 13; + void clear_left_turn(); + static const int kLeftTurnFieldNumber = 13; + bool left_turn() const; + void set_left_turn(bool value); + + // double trajectory_fraction = 18; + void clear_trajectory_fraction(); + static const int kTrajectoryFractionFieldNumber = 18; + double trajectory_fraction() const; + void set_trajectory_fraction(double value); + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 19; + void clear_driving_mode(); + static const int kDrivingModeFieldNumber = 19; + ::apollo::canbus::Chassis_DrivingMode driving_mode() const; + void set_driving_mode(::apollo::canbus::Chassis_DrivingMode value); + + // .apollo.canbus.Chassis.GearPosition gear_location = 20; + void clear_gear_location(); + static const int kGearLocationFieldNumber = 20; + ::apollo::canbus::Chassis_GearPosition gear_location() const; + void set_gear_location(::apollo::canbus::Chassis_GearPosition value); + + // .apollo.control.TurnSignal turnsignal = 21; + void clear_turnsignal(); + static const int kTurnsignalFieldNumber = 21; + ::apollo::control::TurnSignal turnsignal() const; + void set_turnsignal(::apollo::control::TurnSignal value); + + // @@protoc_insertion_point(class_scope:apollo.control.ControlCommand) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::Header* header_; + ::apollo::control::Debug* debug_; + ::apollo::canbus::Signal* signal_; + ::apollo::control::LatencyStats* latency_stats_; + ::apollo::control::PadMessage* pad_msg_; + double throttle_; + double brake_; + double steering_rate_; + double steering_target_; + double speed_; + double acceleration_; + bool right_turn_; + bool high_beam_; + bool low_beam_; + bool horn_; + bool parking_brake_; + bool reset_model_; + bool engine_on_off_; + bool left_turn_; + double trajectory_fraction_; + int driving_mode_; + int gear_location_; + int turnsignal_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class SimpleLongitudinalDebug : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.SimpleLongitudinalDebug) */ { + public: + SimpleLongitudinalDebug(); + virtual ~SimpleLongitudinalDebug(); + + SimpleLongitudinalDebug(const SimpleLongitudinalDebug& from); + + inline SimpleLongitudinalDebug& operator=(const SimpleLongitudinalDebug& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + SimpleLongitudinalDebug(SimpleLongitudinalDebug&& from) noexcept + : SimpleLongitudinalDebug() { + *this = ::std::move(from); + } + + inline SimpleLongitudinalDebug& operator=(SimpleLongitudinalDebug&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const SimpleLongitudinalDebug& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const SimpleLongitudinalDebug* internal_default_instance() { + return reinterpret_cast( + &_SimpleLongitudinalDebug_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + void Swap(SimpleLongitudinalDebug* other); + friend void swap(SimpleLongitudinalDebug& a, SimpleLongitudinalDebug& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline SimpleLongitudinalDebug* New() const final { + return CreateMaybeMessage(NULL); + } + + SimpleLongitudinalDebug* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const SimpleLongitudinalDebug& from); + void MergeFrom(const SimpleLongitudinalDebug& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SimpleLongitudinalDebug* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double station_reference = 1; + void clear_station_reference(); + static const int kStationReferenceFieldNumber = 1; + double station_reference() const; + void set_station_reference(double value); + + // double station_error = 2; + void clear_station_error(); + static const int kStationErrorFieldNumber = 2; + double station_error() const; + void set_station_error(double value); + + // double station_error_limited = 3; + void clear_station_error_limited(); + static const int kStationErrorLimitedFieldNumber = 3; + double station_error_limited() const; + void set_station_error_limited(double value); + + // double preview_station_error = 4; + void clear_preview_station_error(); + static const int kPreviewStationErrorFieldNumber = 4; + double preview_station_error() const; + void set_preview_station_error(double value); + + // double speed_reference = 5; + void clear_speed_reference(); + static const int kSpeedReferenceFieldNumber = 5; + double speed_reference() const; + void set_speed_reference(double value); + + // double speed_error = 6; + void clear_speed_error(); + static const int kSpeedErrorFieldNumber = 6; + double speed_error() const; + void set_speed_error(double value); + + // double speed_controller_input_limited = 7; + void clear_speed_controller_input_limited(); + static const int kSpeedControllerInputLimitedFieldNumber = 7; + double speed_controller_input_limited() const; + void set_speed_controller_input_limited(double value); + + // double preview_speed_reference = 8; + void clear_preview_speed_reference(); + static const int kPreviewSpeedReferenceFieldNumber = 8; + double preview_speed_reference() const; + void set_preview_speed_reference(double value); + + // double preview_speed_error = 9; + void clear_preview_speed_error(); + static const int kPreviewSpeedErrorFieldNumber = 9; + double preview_speed_error() const; + void set_preview_speed_error(double value); + + // double preview_acceleration_reference = 10; + void clear_preview_acceleration_reference(); + static const int kPreviewAccelerationReferenceFieldNumber = 10; + double preview_acceleration_reference() const; + void set_preview_acceleration_reference(double value); + + // double acceleration_cmd_closeloop = 11; + void clear_acceleration_cmd_closeloop(); + static const int kAccelerationCmdCloseloopFieldNumber = 11; + double acceleration_cmd_closeloop() const; + void set_acceleration_cmd_closeloop(double value); + + // double acceleration_cmd = 12; + void clear_acceleration_cmd(); + static const int kAccelerationCmdFieldNumber = 12; + double acceleration_cmd() const; + void set_acceleration_cmd(double value); + + // double acceleration_lookup = 13; + void clear_acceleration_lookup(); + static const int kAccelerationLookupFieldNumber = 13; + double acceleration_lookup() const; + void set_acceleration_lookup(double value); + + // double speed_lookup = 14; + void clear_speed_lookup(); + static const int kSpeedLookupFieldNumber = 14; + double speed_lookup() const; + void set_speed_lookup(double value); + + // double calibration_value = 15; + void clear_calibration_value(); + static const int kCalibrationValueFieldNumber = 15; + double calibration_value() const; + void set_calibration_value(double value); + + // double throttle_cmd = 16; + void clear_throttle_cmd(); + static const int kThrottleCmdFieldNumber = 16; + double throttle_cmd() const; + void set_throttle_cmd(double value); + + // double brake_cmd = 17; + void clear_brake_cmd(); + static const int kBrakeCmdFieldNumber = 17; + double brake_cmd() const; + void set_brake_cmd(double value); + + // bool is_full_stop = 18; + void clear_is_full_stop(); + static const int kIsFullStopFieldNumber = 18; + bool is_full_stop() const; + void set_is_full_stop(bool value); + + // @@protoc_insertion_point(class_scope:apollo.control.SimpleLongitudinalDebug) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double station_reference_; + double station_error_; + double station_error_limited_; + double preview_station_error_; + double speed_reference_; + double speed_error_; + double speed_controller_input_limited_; + double preview_speed_reference_; + double preview_speed_error_; + double preview_acceleration_reference_; + double acceleration_cmd_closeloop_; + double acceleration_cmd_; + double acceleration_lookup_; + double speed_lookup_; + double calibration_value_; + double throttle_cmd_; + double brake_cmd_; + bool is_full_stop_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class SimpleLateralDebug : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.SimpleLateralDebug) */ { + public: + SimpleLateralDebug(); + virtual ~SimpleLateralDebug(); + + SimpleLateralDebug(const SimpleLateralDebug& from); + + inline SimpleLateralDebug& operator=(const SimpleLateralDebug& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + SimpleLateralDebug(SimpleLateralDebug&& from) noexcept + : SimpleLateralDebug() { + *this = ::std::move(from); + } + + inline SimpleLateralDebug& operator=(SimpleLateralDebug&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const SimpleLateralDebug& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const SimpleLateralDebug* internal_default_instance() { + return reinterpret_cast( + &_SimpleLateralDebug_default_instance_); + } + static constexpr int kIndexInFileMessages = + 3; + + void Swap(SimpleLateralDebug* other); + friend void swap(SimpleLateralDebug& a, SimpleLateralDebug& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline SimpleLateralDebug* New() const final { + return CreateMaybeMessage(NULL); + } + + SimpleLateralDebug* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const SimpleLateralDebug& from); + void MergeFrom(const SimpleLateralDebug& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SimpleLateralDebug* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double lateral_error = 1; + void clear_lateral_error(); + static const int kLateralErrorFieldNumber = 1; + double lateral_error() const; + void set_lateral_error(double value); + + // double ref_heading = 2; + void clear_ref_heading(); + static const int kRefHeadingFieldNumber = 2; + double ref_heading() const; + void set_ref_heading(double value); + + // double heading = 3; + void clear_heading(); + static const int kHeadingFieldNumber = 3; + double heading() const; + void set_heading(double value); + + // double heading_error = 4; + void clear_heading_error(); + static const int kHeadingErrorFieldNumber = 4; + double heading_error() const; + void set_heading_error(double value); + + // double heading_error_rate = 5; + void clear_heading_error_rate(); + static const int kHeadingErrorRateFieldNumber = 5; + double heading_error_rate() const; + void set_heading_error_rate(double value); + + // double lateral_error_rate = 6; + void clear_lateral_error_rate(); + static const int kLateralErrorRateFieldNumber = 6; + double lateral_error_rate() const; + void set_lateral_error_rate(double value); + + // double curvature = 7; + void clear_curvature(); + static const int kCurvatureFieldNumber = 7; + double curvature() const; + void set_curvature(double value); + + // double steer_angle = 8; + void clear_steer_angle(); + static const int kSteerAngleFieldNumber = 8; + double steer_angle() const; + void set_steer_angle(double value); + + // double steer_angle_feedforward = 9; + void clear_steer_angle_feedforward(); + static const int kSteerAngleFeedforwardFieldNumber = 9; + double steer_angle_feedforward() const; + void set_steer_angle_feedforward(double value); + + // double steer_angle_lateral_contribution = 10; + void clear_steer_angle_lateral_contribution(); + static const int kSteerAngleLateralContributionFieldNumber = 10; + double steer_angle_lateral_contribution() const; + void set_steer_angle_lateral_contribution(double value); + + // double steer_angle_lateral_rate_contribution = 11; + void clear_steer_angle_lateral_rate_contribution(); + static const int kSteerAngleLateralRateContributionFieldNumber = 11; + double steer_angle_lateral_rate_contribution() const; + void set_steer_angle_lateral_rate_contribution(double value); + + // double steer_angle_heading_contribution = 12; + void clear_steer_angle_heading_contribution(); + static const int kSteerAngleHeadingContributionFieldNumber = 12; + double steer_angle_heading_contribution() const; + void set_steer_angle_heading_contribution(double value); + + // double steer_angle_heading_rate_contribution = 13; + void clear_steer_angle_heading_rate_contribution(); + static const int kSteerAngleHeadingRateContributionFieldNumber = 13; + double steer_angle_heading_rate_contribution() const; + void set_steer_angle_heading_rate_contribution(double value); + + // double steer_angle_feedback = 14; + void clear_steer_angle_feedback(); + static const int kSteerAngleFeedbackFieldNumber = 14; + double steer_angle_feedback() const; + void set_steer_angle_feedback(double value); + + // double steering_position = 15; + void clear_steering_position(); + static const int kSteeringPositionFieldNumber = 15; + double steering_position() const; + void set_steering_position(double value); + + // double ref_speed = 16; + void clear_ref_speed(); + static const int kRefSpeedFieldNumber = 16; + double ref_speed() const; + void set_ref_speed(double value); + + // @@protoc_insertion_point(class_scope:apollo.control.SimpleLateralDebug) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double lateral_error_; + double ref_heading_; + double heading_; + double heading_error_; + double heading_error_rate_; + double lateral_error_rate_; + double curvature_; + double steer_angle_; + double steer_angle_feedforward_; + double steer_angle_lateral_contribution_; + double steer_angle_lateral_rate_contribution_; + double steer_angle_heading_contribution_; + double steer_angle_heading_rate_contribution_; + double steer_angle_feedback_; + double steering_position_; + double ref_speed_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class InputDebug : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.InputDebug) */ { + public: + InputDebug(); + virtual ~InputDebug(); + + InputDebug(const InputDebug& from); + + inline InputDebug& operator=(const InputDebug& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + InputDebug(InputDebug&& from) noexcept + : InputDebug() { + *this = ::std::move(from); + } + + inline InputDebug& operator=(InputDebug&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const InputDebug& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const InputDebug* internal_default_instance() { + return reinterpret_cast( + &_InputDebug_default_instance_); + } + static constexpr int kIndexInFileMessages = + 4; + + void Swap(InputDebug* other); + friend void swap(InputDebug& a, InputDebug& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline InputDebug* New() const final { + return CreateMaybeMessage(NULL); + } + + InputDebug* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const InputDebug& from); + void MergeFrom(const InputDebug& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(InputDebug* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.common.Header localization_header = 1; + bool has_localization_header() const; + void clear_localization_header(); + static const int kLocalizationHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_localization_header() const; + public: + const ::apollo::common::Header& localization_header() const; + ::apollo::common::Header* release_localization_header(); + ::apollo::common::Header* mutable_localization_header(); + void set_allocated_localization_header(::apollo::common::Header* localization_header); + + // .apollo.common.Header canbus_header = 2; + bool has_canbus_header() const; + void clear_canbus_header(); + static const int kCanbusHeaderFieldNumber = 2; + private: + const ::apollo::common::Header& _internal_canbus_header() const; + public: + const ::apollo::common::Header& canbus_header() const; + ::apollo::common::Header* release_canbus_header(); + ::apollo::common::Header* mutable_canbus_header(); + void set_allocated_canbus_header(::apollo::common::Header* canbus_header); + + // .apollo.common.Header trajectory_header = 3; + bool has_trajectory_header() const; + void clear_trajectory_header(); + static const int kTrajectoryHeaderFieldNumber = 3; + private: + const ::apollo::common::Header& _internal_trajectory_header() const; + public: + const ::apollo::common::Header& trajectory_header() const; + ::apollo::common::Header* release_trajectory_header(); + ::apollo::common::Header* mutable_trajectory_header(); + void set_allocated_trajectory_header(::apollo::common::Header* trajectory_header); + + // @@protoc_insertion_point(class_scope:apollo.control.InputDebug) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::Header* localization_header_; + ::apollo::common::Header* canbus_header_; + ::apollo::common::Header* trajectory_header_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Debug : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.Debug) */ { + public: + Debug(); + virtual ~Debug(); + + Debug(const Debug& from); + + inline Debug& operator=(const Debug& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Debug(Debug&& from) noexcept + : Debug() { + *this = ::std::move(from); + } + + inline Debug& operator=(Debug&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Debug& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Debug* internal_default_instance() { + return reinterpret_cast( + &_Debug_default_instance_); + } + static constexpr int kIndexInFileMessages = + 5; + + void Swap(Debug* other); + friend void swap(Debug& a, Debug& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Debug* New() const final { + return CreateMaybeMessage(NULL); + } + + Debug* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Debug& from); + void MergeFrom(const Debug& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Debug* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.control.SimpleLongitudinalDebug simple_lon_debug = 1; + bool has_simple_lon_debug() const; + void clear_simple_lon_debug(); + static const int kSimpleLonDebugFieldNumber = 1; + private: + const ::apollo::control::SimpleLongitudinalDebug& _internal_simple_lon_debug() const; + public: + const ::apollo::control::SimpleLongitudinalDebug& simple_lon_debug() const; + ::apollo::control::SimpleLongitudinalDebug* release_simple_lon_debug(); + ::apollo::control::SimpleLongitudinalDebug* mutable_simple_lon_debug(); + void set_allocated_simple_lon_debug(::apollo::control::SimpleLongitudinalDebug* simple_lon_debug); + + // .apollo.control.SimpleLateralDebug simple_lat_debug = 2; + bool has_simple_lat_debug() const; + void clear_simple_lat_debug(); + static const int kSimpleLatDebugFieldNumber = 2; + private: + const ::apollo::control::SimpleLateralDebug& _internal_simple_lat_debug() const; + public: + const ::apollo::control::SimpleLateralDebug& simple_lat_debug() const; + ::apollo::control::SimpleLateralDebug* release_simple_lat_debug(); + ::apollo::control::SimpleLateralDebug* mutable_simple_lat_debug(); + void set_allocated_simple_lat_debug(::apollo::control::SimpleLateralDebug* simple_lat_debug); + + // .apollo.control.InputDebug input_debug = 3; + bool has_input_debug() const; + void clear_input_debug(); + static const int kInputDebugFieldNumber = 3; + private: + const ::apollo::control::InputDebug& _internal_input_debug() const; + public: + const ::apollo::control::InputDebug& input_debug() const; + ::apollo::control::InputDebug* release_input_debug(); + ::apollo::control::InputDebug* mutable_input_debug(); + void set_allocated_input_debug(::apollo::control::InputDebug* input_debug); + + // @@protoc_insertion_point(class_scope:apollo.control.Debug) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::control::SimpleLongitudinalDebug* simple_lon_debug_; + ::apollo::control::SimpleLateralDebug* simple_lat_debug_; + ::apollo::control::InputDebug* input_debug_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// LatencyStats + +// double total_time_ms = 1; +inline void LatencyStats::clear_total_time_ms() { + total_time_ms_ = 0; +} +inline double LatencyStats::total_time_ms() const { + // @@protoc_insertion_point(field_get:apollo.control.LatencyStats.total_time_ms) + return total_time_ms_; +} +inline void LatencyStats::set_total_time_ms(double value) { + + total_time_ms_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatencyStats.total_time_ms) +} + +// repeated double controller_time_ms = 2; +inline int LatencyStats::controller_time_ms_size() const { + return controller_time_ms_.size(); +} +inline void LatencyStats::clear_controller_time_ms() { + controller_time_ms_.Clear(); +} +inline double LatencyStats::controller_time_ms(int index) const { + // @@protoc_insertion_point(field_get:apollo.control.LatencyStats.controller_time_ms) + return controller_time_ms_.Get(index); +} +inline void LatencyStats::set_controller_time_ms(int index, double value) { + controller_time_ms_.Set(index, value); + // @@protoc_insertion_point(field_set:apollo.control.LatencyStats.controller_time_ms) +} +inline void LatencyStats::add_controller_time_ms(double value) { + controller_time_ms_.Add(value); + // @@protoc_insertion_point(field_add:apollo.control.LatencyStats.controller_time_ms) +} +inline const ::google::protobuf::RepeatedField< double >& +LatencyStats::controller_time_ms() const { + // @@protoc_insertion_point(field_list:apollo.control.LatencyStats.controller_time_ms) + return controller_time_ms_; +} +inline ::google::protobuf::RepeatedField< double >* +LatencyStats::mutable_controller_time_ms() { + // @@protoc_insertion_point(field_mutable_list:apollo.control.LatencyStats.controller_time_ms) + return &controller_time_ms_; +} + +// ------------------------------------------------------------------- + +// ControlCommand + +// .apollo.common.Header header = 1; +inline bool ControlCommand::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& ControlCommand::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& ControlCommand::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* ControlCommand::release_header() { + // @@protoc_insertion_point(field_release:apollo.control.ControlCommand.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* ControlCommand::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.ControlCommand.header) + return header_; +} +inline void ControlCommand::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.control.ControlCommand.header) +} + +// double throttle = 3; +inline void ControlCommand::clear_throttle() { + throttle_ = 0; +} +inline double ControlCommand::throttle() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.throttle) + return throttle_; +} +inline void ControlCommand::set_throttle(double value) { + + throttle_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.throttle) +} + +// double brake = 4; +inline void ControlCommand::clear_brake() { + brake_ = 0; +} +inline double ControlCommand::brake() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.brake) + return brake_; +} +inline void ControlCommand::set_brake(double value) { + + brake_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.brake) +} + +// double steering_rate = 6; +inline void ControlCommand::clear_steering_rate() { + steering_rate_ = 0; +} +inline double ControlCommand::steering_rate() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.steering_rate) + return steering_rate_; +} +inline void ControlCommand::set_steering_rate(double value) { + + steering_rate_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.steering_rate) +} + +// double steering_target = 7; +inline void ControlCommand::clear_steering_target() { + steering_target_ = 0; +} +inline double ControlCommand::steering_target() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.steering_target) + return steering_target_; +} +inline void ControlCommand::set_steering_target(double value) { + + steering_target_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.steering_target) +} + +// bool parking_brake = 8; +inline void ControlCommand::clear_parking_brake() { + parking_brake_ = false; +} +inline bool ControlCommand::parking_brake() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.parking_brake) + return parking_brake_; +} +inline void ControlCommand::set_parking_brake(bool value) { + + parking_brake_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.parking_brake) +} + +// double speed = 9; +inline void ControlCommand::clear_speed() { + speed_ = 0; +} +inline double ControlCommand::speed() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.speed) + return speed_; +} +inline void ControlCommand::set_speed(double value) { + + speed_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.speed) +} + +// double acceleration = 10; +inline void ControlCommand::clear_acceleration() { + acceleration_ = 0; +} +inline double ControlCommand::acceleration() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.acceleration) + return acceleration_; +} +inline void ControlCommand::set_acceleration(double value) { + + acceleration_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.acceleration) +} + +// bool reset_model = 16; +inline void ControlCommand::clear_reset_model() { + reset_model_ = false; +} +inline bool ControlCommand::reset_model() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.reset_model) + return reset_model_; +} +inline void ControlCommand::set_reset_model(bool value) { + + reset_model_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.reset_model) +} + +// bool engine_on_off = 17; +inline void ControlCommand::clear_engine_on_off() { + engine_on_off_ = false; +} +inline bool ControlCommand::engine_on_off() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.engine_on_off) + return engine_on_off_; +} +inline void ControlCommand::set_engine_on_off(bool value) { + + engine_on_off_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.engine_on_off) +} + +// double trajectory_fraction = 18; +inline void ControlCommand::clear_trajectory_fraction() { + trajectory_fraction_ = 0; +} +inline double ControlCommand::trajectory_fraction() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.trajectory_fraction) + return trajectory_fraction_; +} +inline void ControlCommand::set_trajectory_fraction(double value) { + + trajectory_fraction_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.trajectory_fraction) +} + +// .apollo.canbus.Chassis.DrivingMode driving_mode = 19; +inline void ControlCommand::clear_driving_mode() { + driving_mode_ = 0; +} +inline ::apollo::canbus::Chassis_DrivingMode ControlCommand::driving_mode() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.driving_mode) + return static_cast< ::apollo::canbus::Chassis_DrivingMode >(driving_mode_); +} +inline void ControlCommand::set_driving_mode(::apollo::canbus::Chassis_DrivingMode value) { + + driving_mode_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.driving_mode) +} + +// .apollo.canbus.Chassis.GearPosition gear_location = 20; +inline void ControlCommand::clear_gear_location() { + gear_location_ = 0; +} +inline ::apollo::canbus::Chassis_GearPosition ControlCommand::gear_location() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.gear_location) + return static_cast< ::apollo::canbus::Chassis_GearPosition >(gear_location_); +} +inline void ControlCommand::set_gear_location(::apollo::canbus::Chassis_GearPosition value) { + + gear_location_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.gear_location) +} + +// .apollo.control.Debug debug = 22; +inline bool ControlCommand::has_debug() const { + return this != internal_default_instance() && debug_ != NULL; +} +inline void ControlCommand::clear_debug() { + if (GetArenaNoVirtual() == NULL && debug_ != NULL) { + delete debug_; + } + debug_ = NULL; +} +inline const ::apollo::control::Debug& ControlCommand::_internal_debug() const { + return *debug_; +} +inline const ::apollo::control::Debug& ControlCommand::debug() const { + const ::apollo::control::Debug* p = debug_; + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.debug) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_Debug_default_instance_); +} +inline ::apollo::control::Debug* ControlCommand::release_debug() { + // @@protoc_insertion_point(field_release:apollo.control.ControlCommand.debug) + + ::apollo::control::Debug* temp = debug_; + debug_ = NULL; + return temp; +} +inline ::apollo::control::Debug* ControlCommand::mutable_debug() { + + if (debug_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::Debug>(GetArenaNoVirtual()); + debug_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.ControlCommand.debug) + return debug_; +} +inline void ControlCommand::set_allocated_debug(::apollo::control::Debug* debug) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete debug_; + } + if (debug) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + debug = ::google::protobuf::internal::GetOwnedMessage( + message_arena, debug, submessage_arena); + } + + } else { + + } + debug_ = debug; + // @@protoc_insertion_point(field_set_allocated:apollo.control.ControlCommand.debug) +} + +// .apollo.canbus.Signal signal = 23; +inline bool ControlCommand::has_signal() const { + return this != internal_default_instance() && signal_ != NULL; +} +inline const ::apollo::canbus::Signal& ControlCommand::_internal_signal() const { + return *signal_; +} +inline const ::apollo::canbus::Signal& ControlCommand::signal() const { + const ::apollo::canbus::Signal* p = signal_; + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.signal) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Signal_default_instance_); +} +inline ::apollo::canbus::Signal* ControlCommand::release_signal() { + // @@protoc_insertion_point(field_release:apollo.control.ControlCommand.signal) + + ::apollo::canbus::Signal* temp = signal_; + signal_ = NULL; + return temp; +} +inline ::apollo::canbus::Signal* ControlCommand::mutable_signal() { + + if (signal_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Signal>(GetArenaNoVirtual()); + signal_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.ControlCommand.signal) + return signal_; +} +inline void ControlCommand::set_allocated_signal(::apollo::canbus::Signal* signal) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(signal_); + } + if (signal) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + signal = ::google::protobuf::internal::GetOwnedMessage( + message_arena, signal, submessage_arena); + } + + } else { + + } + signal_ = signal; + // @@protoc_insertion_point(field_set_allocated:apollo.control.ControlCommand.signal) +} + +// .apollo.control.LatencyStats latency_stats = 24; +inline bool ControlCommand::has_latency_stats() const { + return this != internal_default_instance() && latency_stats_ != NULL; +} +inline void ControlCommand::clear_latency_stats() { + if (GetArenaNoVirtual() == NULL && latency_stats_ != NULL) { + delete latency_stats_; + } + latency_stats_ = NULL; +} +inline const ::apollo::control::LatencyStats& ControlCommand::_internal_latency_stats() const { + return *latency_stats_; +} +inline const ::apollo::control::LatencyStats& ControlCommand::latency_stats() const { + const ::apollo::control::LatencyStats* p = latency_stats_; + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.latency_stats) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_LatencyStats_default_instance_); +} +inline ::apollo::control::LatencyStats* ControlCommand::release_latency_stats() { + // @@protoc_insertion_point(field_release:apollo.control.ControlCommand.latency_stats) + + ::apollo::control::LatencyStats* temp = latency_stats_; + latency_stats_ = NULL; + return temp; +} +inline ::apollo::control::LatencyStats* ControlCommand::mutable_latency_stats() { + + if (latency_stats_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::LatencyStats>(GetArenaNoVirtual()); + latency_stats_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.ControlCommand.latency_stats) + return latency_stats_; +} +inline void ControlCommand::set_allocated_latency_stats(::apollo::control::LatencyStats* latency_stats) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete latency_stats_; + } + if (latency_stats) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + latency_stats = ::google::protobuf::internal::GetOwnedMessage( + message_arena, latency_stats, submessage_arena); + } + + } else { + + } + latency_stats_ = latency_stats; + // @@protoc_insertion_point(field_set_allocated:apollo.control.ControlCommand.latency_stats) +} + +// .apollo.control.PadMessage pad_msg = 25; +inline bool ControlCommand::has_pad_msg() const { + return this != internal_default_instance() && pad_msg_ != NULL; +} +inline const ::apollo::control::PadMessage& ControlCommand::_internal_pad_msg() const { + return *pad_msg_; +} +inline const ::apollo::control::PadMessage& ControlCommand::pad_msg() const { + const ::apollo::control::PadMessage* p = pad_msg_; + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.pad_msg) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_PadMessage_default_instance_); +} +inline ::apollo::control::PadMessage* ControlCommand::release_pad_msg() { + // @@protoc_insertion_point(field_release:apollo.control.ControlCommand.pad_msg) + + ::apollo::control::PadMessage* temp = pad_msg_; + pad_msg_ = NULL; + return temp; +} +inline ::apollo::control::PadMessage* ControlCommand::mutable_pad_msg() { + + if (pad_msg_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::PadMessage>(GetArenaNoVirtual()); + pad_msg_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.ControlCommand.pad_msg) + return pad_msg_; +} +inline void ControlCommand::set_allocated_pad_msg(::apollo::control::PadMessage* pad_msg) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(pad_msg_); + } + if (pad_msg) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + pad_msg = ::google::protobuf::internal::GetOwnedMessage( + message_arena, pad_msg, submessage_arena); + } + + } else { + + } + pad_msg_ = pad_msg; + // @@protoc_insertion_point(field_set_allocated:apollo.control.ControlCommand.pad_msg) +} + +// bool left_turn = 13; +inline void ControlCommand::clear_left_turn() { + left_turn_ = false; +} +inline bool ControlCommand::left_turn() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.left_turn) + return left_turn_; +} +inline void ControlCommand::set_left_turn(bool value) { + + left_turn_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.left_turn) +} + +// bool right_turn = 14; +inline void ControlCommand::clear_right_turn() { + right_turn_ = false; +} +inline bool ControlCommand::right_turn() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.right_turn) + return right_turn_; +} +inline void ControlCommand::set_right_turn(bool value) { + + right_turn_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.right_turn) +} + +// bool high_beam = 11; +inline void ControlCommand::clear_high_beam() { + high_beam_ = false; +} +inline bool ControlCommand::high_beam() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.high_beam) + return high_beam_; +} +inline void ControlCommand::set_high_beam(bool value) { + + high_beam_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.high_beam) +} + +// bool low_beam = 12; +inline void ControlCommand::clear_low_beam() { + low_beam_ = false; +} +inline bool ControlCommand::low_beam() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.low_beam) + return low_beam_; +} +inline void ControlCommand::set_low_beam(bool value) { + + low_beam_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.low_beam) +} + +// bool horn = 15; +inline void ControlCommand::clear_horn() { + horn_ = false; +} +inline bool ControlCommand::horn() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.horn) + return horn_; +} +inline void ControlCommand::set_horn(bool value) { + + horn_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.horn) +} + +// .apollo.control.TurnSignal turnsignal = 21; +inline void ControlCommand::clear_turnsignal() { + turnsignal_ = 0; +} +inline ::apollo::control::TurnSignal ControlCommand::turnsignal() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlCommand.turnsignal) + return static_cast< ::apollo::control::TurnSignal >(turnsignal_); +} +inline void ControlCommand::set_turnsignal(::apollo::control::TurnSignal value) { + + turnsignal_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlCommand.turnsignal) +} + +// ------------------------------------------------------------------- + +// SimpleLongitudinalDebug + +// double station_reference = 1; +inline void SimpleLongitudinalDebug::clear_station_reference() { + station_reference_ = 0; +} +inline double SimpleLongitudinalDebug::station_reference() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.station_reference) + return station_reference_; +} +inline void SimpleLongitudinalDebug::set_station_reference(double value) { + + station_reference_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.station_reference) +} + +// double station_error = 2; +inline void SimpleLongitudinalDebug::clear_station_error() { + station_error_ = 0; +} +inline double SimpleLongitudinalDebug::station_error() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.station_error) + return station_error_; +} +inline void SimpleLongitudinalDebug::set_station_error(double value) { + + station_error_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.station_error) +} + +// double station_error_limited = 3; +inline void SimpleLongitudinalDebug::clear_station_error_limited() { + station_error_limited_ = 0; +} +inline double SimpleLongitudinalDebug::station_error_limited() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.station_error_limited) + return station_error_limited_; +} +inline void SimpleLongitudinalDebug::set_station_error_limited(double value) { + + station_error_limited_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.station_error_limited) +} + +// double preview_station_error = 4; +inline void SimpleLongitudinalDebug::clear_preview_station_error() { + preview_station_error_ = 0; +} +inline double SimpleLongitudinalDebug::preview_station_error() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.preview_station_error) + return preview_station_error_; +} +inline void SimpleLongitudinalDebug::set_preview_station_error(double value) { + + preview_station_error_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.preview_station_error) +} + +// double speed_reference = 5; +inline void SimpleLongitudinalDebug::clear_speed_reference() { + speed_reference_ = 0; +} +inline double SimpleLongitudinalDebug::speed_reference() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.speed_reference) + return speed_reference_; +} +inline void SimpleLongitudinalDebug::set_speed_reference(double value) { + + speed_reference_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.speed_reference) +} + +// double speed_error = 6; +inline void SimpleLongitudinalDebug::clear_speed_error() { + speed_error_ = 0; +} +inline double SimpleLongitudinalDebug::speed_error() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.speed_error) + return speed_error_; +} +inline void SimpleLongitudinalDebug::set_speed_error(double value) { + + speed_error_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.speed_error) +} + +// double speed_controller_input_limited = 7; +inline void SimpleLongitudinalDebug::clear_speed_controller_input_limited() { + speed_controller_input_limited_ = 0; +} +inline double SimpleLongitudinalDebug::speed_controller_input_limited() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.speed_controller_input_limited) + return speed_controller_input_limited_; +} +inline void SimpleLongitudinalDebug::set_speed_controller_input_limited(double value) { + + speed_controller_input_limited_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.speed_controller_input_limited) +} + +// double preview_speed_reference = 8; +inline void SimpleLongitudinalDebug::clear_preview_speed_reference() { + preview_speed_reference_ = 0; +} +inline double SimpleLongitudinalDebug::preview_speed_reference() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.preview_speed_reference) + return preview_speed_reference_; +} +inline void SimpleLongitudinalDebug::set_preview_speed_reference(double value) { + + preview_speed_reference_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.preview_speed_reference) +} + +// double preview_speed_error = 9; +inline void SimpleLongitudinalDebug::clear_preview_speed_error() { + preview_speed_error_ = 0; +} +inline double SimpleLongitudinalDebug::preview_speed_error() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.preview_speed_error) + return preview_speed_error_; +} +inline void SimpleLongitudinalDebug::set_preview_speed_error(double value) { + + preview_speed_error_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.preview_speed_error) +} + +// double preview_acceleration_reference = 10; +inline void SimpleLongitudinalDebug::clear_preview_acceleration_reference() { + preview_acceleration_reference_ = 0; +} +inline double SimpleLongitudinalDebug::preview_acceleration_reference() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.preview_acceleration_reference) + return preview_acceleration_reference_; +} +inline void SimpleLongitudinalDebug::set_preview_acceleration_reference(double value) { + + preview_acceleration_reference_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.preview_acceleration_reference) +} + +// double acceleration_cmd_closeloop = 11; +inline void SimpleLongitudinalDebug::clear_acceleration_cmd_closeloop() { + acceleration_cmd_closeloop_ = 0; +} +inline double SimpleLongitudinalDebug::acceleration_cmd_closeloop() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.acceleration_cmd_closeloop) + return acceleration_cmd_closeloop_; +} +inline void SimpleLongitudinalDebug::set_acceleration_cmd_closeloop(double value) { + + acceleration_cmd_closeloop_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.acceleration_cmd_closeloop) +} + +// double acceleration_cmd = 12; +inline void SimpleLongitudinalDebug::clear_acceleration_cmd() { + acceleration_cmd_ = 0; +} +inline double SimpleLongitudinalDebug::acceleration_cmd() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.acceleration_cmd) + return acceleration_cmd_; +} +inline void SimpleLongitudinalDebug::set_acceleration_cmd(double value) { + + acceleration_cmd_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.acceleration_cmd) +} + +// double acceleration_lookup = 13; +inline void SimpleLongitudinalDebug::clear_acceleration_lookup() { + acceleration_lookup_ = 0; +} +inline double SimpleLongitudinalDebug::acceleration_lookup() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.acceleration_lookup) + return acceleration_lookup_; +} +inline void SimpleLongitudinalDebug::set_acceleration_lookup(double value) { + + acceleration_lookup_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.acceleration_lookup) +} + +// double speed_lookup = 14; +inline void SimpleLongitudinalDebug::clear_speed_lookup() { + speed_lookup_ = 0; +} +inline double SimpleLongitudinalDebug::speed_lookup() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.speed_lookup) + return speed_lookup_; +} +inline void SimpleLongitudinalDebug::set_speed_lookup(double value) { + + speed_lookup_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.speed_lookup) +} + +// double calibration_value = 15; +inline void SimpleLongitudinalDebug::clear_calibration_value() { + calibration_value_ = 0; +} +inline double SimpleLongitudinalDebug::calibration_value() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.calibration_value) + return calibration_value_; +} +inline void SimpleLongitudinalDebug::set_calibration_value(double value) { + + calibration_value_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.calibration_value) +} + +// double throttle_cmd = 16; +inline void SimpleLongitudinalDebug::clear_throttle_cmd() { + throttle_cmd_ = 0; +} +inline double SimpleLongitudinalDebug::throttle_cmd() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.throttle_cmd) + return throttle_cmd_; +} +inline void SimpleLongitudinalDebug::set_throttle_cmd(double value) { + + throttle_cmd_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.throttle_cmd) +} + +// double brake_cmd = 17; +inline void SimpleLongitudinalDebug::clear_brake_cmd() { + brake_cmd_ = 0; +} +inline double SimpleLongitudinalDebug::brake_cmd() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.brake_cmd) + return brake_cmd_; +} +inline void SimpleLongitudinalDebug::set_brake_cmd(double value) { + + brake_cmd_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.brake_cmd) +} + +// bool is_full_stop = 18; +inline void SimpleLongitudinalDebug::clear_is_full_stop() { + is_full_stop_ = false; +} +inline bool SimpleLongitudinalDebug::is_full_stop() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLongitudinalDebug.is_full_stop) + return is_full_stop_; +} +inline void SimpleLongitudinalDebug::set_is_full_stop(bool value) { + + is_full_stop_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLongitudinalDebug.is_full_stop) +} + +// ------------------------------------------------------------------- + +// SimpleLateralDebug + +// double lateral_error = 1; +inline void SimpleLateralDebug::clear_lateral_error() { + lateral_error_ = 0; +} +inline double SimpleLateralDebug::lateral_error() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.lateral_error) + return lateral_error_; +} +inline void SimpleLateralDebug::set_lateral_error(double value) { + + lateral_error_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.lateral_error) +} + +// double ref_heading = 2; +inline void SimpleLateralDebug::clear_ref_heading() { + ref_heading_ = 0; +} +inline double SimpleLateralDebug::ref_heading() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.ref_heading) + return ref_heading_; +} +inline void SimpleLateralDebug::set_ref_heading(double value) { + + ref_heading_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.ref_heading) +} + +// double heading = 3; +inline void SimpleLateralDebug::clear_heading() { + heading_ = 0; +} +inline double SimpleLateralDebug::heading() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.heading) + return heading_; +} +inline void SimpleLateralDebug::set_heading(double value) { + + heading_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.heading) +} + +// double heading_error = 4; +inline void SimpleLateralDebug::clear_heading_error() { + heading_error_ = 0; +} +inline double SimpleLateralDebug::heading_error() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.heading_error) + return heading_error_; +} +inline void SimpleLateralDebug::set_heading_error(double value) { + + heading_error_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.heading_error) +} + +// double heading_error_rate = 5; +inline void SimpleLateralDebug::clear_heading_error_rate() { + heading_error_rate_ = 0; +} +inline double SimpleLateralDebug::heading_error_rate() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.heading_error_rate) + return heading_error_rate_; +} +inline void SimpleLateralDebug::set_heading_error_rate(double value) { + + heading_error_rate_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.heading_error_rate) +} + +// double lateral_error_rate = 6; +inline void SimpleLateralDebug::clear_lateral_error_rate() { + lateral_error_rate_ = 0; +} +inline double SimpleLateralDebug::lateral_error_rate() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.lateral_error_rate) + return lateral_error_rate_; +} +inline void SimpleLateralDebug::set_lateral_error_rate(double value) { + + lateral_error_rate_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.lateral_error_rate) +} + +// double curvature = 7; +inline void SimpleLateralDebug::clear_curvature() { + curvature_ = 0; +} +inline double SimpleLateralDebug::curvature() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.curvature) + return curvature_; +} +inline void SimpleLateralDebug::set_curvature(double value) { + + curvature_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.curvature) +} + +// double steer_angle = 8; +inline void SimpleLateralDebug::clear_steer_angle() { + steer_angle_ = 0; +} +inline double SimpleLateralDebug::steer_angle() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.steer_angle) + return steer_angle_; +} +inline void SimpleLateralDebug::set_steer_angle(double value) { + + steer_angle_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.steer_angle) +} + +// double steer_angle_feedforward = 9; +inline void SimpleLateralDebug::clear_steer_angle_feedforward() { + steer_angle_feedforward_ = 0; +} +inline double SimpleLateralDebug::steer_angle_feedforward() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.steer_angle_feedforward) + return steer_angle_feedforward_; +} +inline void SimpleLateralDebug::set_steer_angle_feedforward(double value) { + + steer_angle_feedforward_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.steer_angle_feedforward) +} + +// double steer_angle_lateral_contribution = 10; +inline void SimpleLateralDebug::clear_steer_angle_lateral_contribution() { + steer_angle_lateral_contribution_ = 0; +} +inline double SimpleLateralDebug::steer_angle_lateral_contribution() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.steer_angle_lateral_contribution) + return steer_angle_lateral_contribution_; +} +inline void SimpleLateralDebug::set_steer_angle_lateral_contribution(double value) { + + steer_angle_lateral_contribution_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.steer_angle_lateral_contribution) +} + +// double steer_angle_lateral_rate_contribution = 11; +inline void SimpleLateralDebug::clear_steer_angle_lateral_rate_contribution() { + steer_angle_lateral_rate_contribution_ = 0; +} +inline double SimpleLateralDebug::steer_angle_lateral_rate_contribution() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.steer_angle_lateral_rate_contribution) + return steer_angle_lateral_rate_contribution_; +} +inline void SimpleLateralDebug::set_steer_angle_lateral_rate_contribution(double value) { + + steer_angle_lateral_rate_contribution_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.steer_angle_lateral_rate_contribution) +} + +// double steer_angle_heading_contribution = 12; +inline void SimpleLateralDebug::clear_steer_angle_heading_contribution() { + steer_angle_heading_contribution_ = 0; +} +inline double SimpleLateralDebug::steer_angle_heading_contribution() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.steer_angle_heading_contribution) + return steer_angle_heading_contribution_; +} +inline void SimpleLateralDebug::set_steer_angle_heading_contribution(double value) { + + steer_angle_heading_contribution_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.steer_angle_heading_contribution) +} + +// double steer_angle_heading_rate_contribution = 13; +inline void SimpleLateralDebug::clear_steer_angle_heading_rate_contribution() { + steer_angle_heading_rate_contribution_ = 0; +} +inline double SimpleLateralDebug::steer_angle_heading_rate_contribution() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.steer_angle_heading_rate_contribution) + return steer_angle_heading_rate_contribution_; +} +inline void SimpleLateralDebug::set_steer_angle_heading_rate_contribution(double value) { + + steer_angle_heading_rate_contribution_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.steer_angle_heading_rate_contribution) +} + +// double steer_angle_feedback = 14; +inline void SimpleLateralDebug::clear_steer_angle_feedback() { + steer_angle_feedback_ = 0; +} +inline double SimpleLateralDebug::steer_angle_feedback() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.steer_angle_feedback) + return steer_angle_feedback_; +} +inline void SimpleLateralDebug::set_steer_angle_feedback(double value) { + + steer_angle_feedback_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.steer_angle_feedback) +} + +// double steering_position = 15; +inline void SimpleLateralDebug::clear_steering_position() { + steering_position_ = 0; +} +inline double SimpleLateralDebug::steering_position() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.steering_position) + return steering_position_; +} +inline void SimpleLateralDebug::set_steering_position(double value) { + + steering_position_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.steering_position) +} + +// double ref_speed = 16; +inline void SimpleLateralDebug::clear_ref_speed() { + ref_speed_ = 0; +} +inline double SimpleLateralDebug::ref_speed() const { + // @@protoc_insertion_point(field_get:apollo.control.SimpleLateralDebug.ref_speed) + return ref_speed_; +} +inline void SimpleLateralDebug::set_ref_speed(double value) { + + ref_speed_ = value; + // @@protoc_insertion_point(field_set:apollo.control.SimpleLateralDebug.ref_speed) +} + +// ------------------------------------------------------------------- + +// InputDebug + +// .apollo.common.Header localization_header = 1; +inline bool InputDebug::has_localization_header() const { + return this != internal_default_instance() && localization_header_ != NULL; +} +inline const ::apollo::common::Header& InputDebug::_internal_localization_header() const { + return *localization_header_; +} +inline const ::apollo::common::Header& InputDebug::localization_header() const { + const ::apollo::common::Header* p = localization_header_; + // @@protoc_insertion_point(field_get:apollo.control.InputDebug.localization_header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* InputDebug::release_localization_header() { + // @@protoc_insertion_point(field_release:apollo.control.InputDebug.localization_header) + + ::apollo::common::Header* temp = localization_header_; + localization_header_ = NULL; + return temp; +} +inline ::apollo::common::Header* InputDebug::mutable_localization_header() { + + if (localization_header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + localization_header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.InputDebug.localization_header) + return localization_header_; +} +inline void InputDebug::set_allocated_localization_header(::apollo::common::Header* localization_header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(localization_header_); + } + if (localization_header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + localization_header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, localization_header, submessage_arena); + } + + } else { + + } + localization_header_ = localization_header; + // @@protoc_insertion_point(field_set_allocated:apollo.control.InputDebug.localization_header) +} + +// .apollo.common.Header canbus_header = 2; +inline bool InputDebug::has_canbus_header() const { + return this != internal_default_instance() && canbus_header_ != NULL; +} +inline const ::apollo::common::Header& InputDebug::_internal_canbus_header() const { + return *canbus_header_; +} +inline const ::apollo::common::Header& InputDebug::canbus_header() const { + const ::apollo::common::Header* p = canbus_header_; + // @@protoc_insertion_point(field_get:apollo.control.InputDebug.canbus_header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* InputDebug::release_canbus_header() { + // @@protoc_insertion_point(field_release:apollo.control.InputDebug.canbus_header) + + ::apollo::common::Header* temp = canbus_header_; + canbus_header_ = NULL; + return temp; +} +inline ::apollo::common::Header* InputDebug::mutable_canbus_header() { + + if (canbus_header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + canbus_header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.InputDebug.canbus_header) + return canbus_header_; +} +inline void InputDebug::set_allocated_canbus_header(::apollo::common::Header* canbus_header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(canbus_header_); + } + if (canbus_header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + canbus_header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, canbus_header, submessage_arena); + } + + } else { + + } + canbus_header_ = canbus_header; + // @@protoc_insertion_point(field_set_allocated:apollo.control.InputDebug.canbus_header) +} + +// .apollo.common.Header trajectory_header = 3; +inline bool InputDebug::has_trajectory_header() const { + return this != internal_default_instance() && trajectory_header_ != NULL; +} +inline const ::apollo::common::Header& InputDebug::_internal_trajectory_header() const { + return *trajectory_header_; +} +inline const ::apollo::common::Header& InputDebug::trajectory_header() const { + const ::apollo::common::Header* p = trajectory_header_; + // @@protoc_insertion_point(field_get:apollo.control.InputDebug.trajectory_header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* InputDebug::release_trajectory_header() { + // @@protoc_insertion_point(field_release:apollo.control.InputDebug.trajectory_header) + + ::apollo::common::Header* temp = trajectory_header_; + trajectory_header_ = NULL; + return temp; +} +inline ::apollo::common::Header* InputDebug::mutable_trajectory_header() { + + if (trajectory_header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + trajectory_header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.InputDebug.trajectory_header) + return trajectory_header_; +} +inline void InputDebug::set_allocated_trajectory_header(::apollo::common::Header* trajectory_header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(trajectory_header_); + } + if (trajectory_header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + trajectory_header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, trajectory_header, submessage_arena); + } + + } else { + + } + trajectory_header_ = trajectory_header; + // @@protoc_insertion_point(field_set_allocated:apollo.control.InputDebug.trajectory_header) +} + +// ------------------------------------------------------------------- + +// Debug + +// .apollo.control.SimpleLongitudinalDebug simple_lon_debug = 1; +inline bool Debug::has_simple_lon_debug() const { + return this != internal_default_instance() && simple_lon_debug_ != NULL; +} +inline void Debug::clear_simple_lon_debug() { + if (GetArenaNoVirtual() == NULL && simple_lon_debug_ != NULL) { + delete simple_lon_debug_; + } + simple_lon_debug_ = NULL; +} +inline const ::apollo::control::SimpleLongitudinalDebug& Debug::_internal_simple_lon_debug() const { + return *simple_lon_debug_; +} +inline const ::apollo::control::SimpleLongitudinalDebug& Debug::simple_lon_debug() const { + const ::apollo::control::SimpleLongitudinalDebug* p = simple_lon_debug_; + // @@protoc_insertion_point(field_get:apollo.control.Debug.simple_lon_debug) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_SimpleLongitudinalDebug_default_instance_); +} +inline ::apollo::control::SimpleLongitudinalDebug* Debug::release_simple_lon_debug() { + // @@protoc_insertion_point(field_release:apollo.control.Debug.simple_lon_debug) + + ::apollo::control::SimpleLongitudinalDebug* temp = simple_lon_debug_; + simple_lon_debug_ = NULL; + return temp; +} +inline ::apollo::control::SimpleLongitudinalDebug* Debug::mutable_simple_lon_debug() { + + if (simple_lon_debug_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::SimpleLongitudinalDebug>(GetArenaNoVirtual()); + simple_lon_debug_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.Debug.simple_lon_debug) + return simple_lon_debug_; +} +inline void Debug::set_allocated_simple_lon_debug(::apollo::control::SimpleLongitudinalDebug* simple_lon_debug) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete simple_lon_debug_; + } + if (simple_lon_debug) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + simple_lon_debug = ::google::protobuf::internal::GetOwnedMessage( + message_arena, simple_lon_debug, submessage_arena); + } + + } else { + + } + simple_lon_debug_ = simple_lon_debug; + // @@protoc_insertion_point(field_set_allocated:apollo.control.Debug.simple_lon_debug) +} + +// .apollo.control.SimpleLateralDebug simple_lat_debug = 2; +inline bool Debug::has_simple_lat_debug() const { + return this != internal_default_instance() && simple_lat_debug_ != NULL; +} +inline void Debug::clear_simple_lat_debug() { + if (GetArenaNoVirtual() == NULL && simple_lat_debug_ != NULL) { + delete simple_lat_debug_; + } + simple_lat_debug_ = NULL; +} +inline const ::apollo::control::SimpleLateralDebug& Debug::_internal_simple_lat_debug() const { + return *simple_lat_debug_; +} +inline const ::apollo::control::SimpleLateralDebug& Debug::simple_lat_debug() const { + const ::apollo::control::SimpleLateralDebug* p = simple_lat_debug_; + // @@protoc_insertion_point(field_get:apollo.control.Debug.simple_lat_debug) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_SimpleLateralDebug_default_instance_); +} +inline ::apollo::control::SimpleLateralDebug* Debug::release_simple_lat_debug() { + // @@protoc_insertion_point(field_release:apollo.control.Debug.simple_lat_debug) + + ::apollo::control::SimpleLateralDebug* temp = simple_lat_debug_; + simple_lat_debug_ = NULL; + return temp; +} +inline ::apollo::control::SimpleLateralDebug* Debug::mutable_simple_lat_debug() { + + if (simple_lat_debug_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::SimpleLateralDebug>(GetArenaNoVirtual()); + simple_lat_debug_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.Debug.simple_lat_debug) + return simple_lat_debug_; +} +inline void Debug::set_allocated_simple_lat_debug(::apollo::control::SimpleLateralDebug* simple_lat_debug) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete simple_lat_debug_; + } + if (simple_lat_debug) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + simple_lat_debug = ::google::protobuf::internal::GetOwnedMessage( + message_arena, simple_lat_debug, submessage_arena); + } + + } else { + + } + simple_lat_debug_ = simple_lat_debug; + // @@protoc_insertion_point(field_set_allocated:apollo.control.Debug.simple_lat_debug) +} + +// .apollo.control.InputDebug input_debug = 3; +inline bool Debug::has_input_debug() const { + return this != internal_default_instance() && input_debug_ != NULL; +} +inline void Debug::clear_input_debug() { + if (GetArenaNoVirtual() == NULL && input_debug_ != NULL) { + delete input_debug_; + } + input_debug_ = NULL; +} +inline const ::apollo::control::InputDebug& Debug::_internal_input_debug() const { + return *input_debug_; +} +inline const ::apollo::control::InputDebug& Debug::input_debug() const { + const ::apollo::control::InputDebug* p = input_debug_; + // @@protoc_insertion_point(field_get:apollo.control.Debug.input_debug) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_InputDebug_default_instance_); +} +inline ::apollo::control::InputDebug* Debug::release_input_debug() { + // @@protoc_insertion_point(field_release:apollo.control.Debug.input_debug) + + ::apollo::control::InputDebug* temp = input_debug_; + input_debug_ = NULL; + return temp; +} +inline ::apollo::control::InputDebug* Debug::mutable_input_debug() { + + if (input_debug_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::InputDebug>(GetArenaNoVirtual()); + input_debug_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.Debug.input_debug) + return input_debug_; +} +inline void Debug::set_allocated_input_debug(::apollo::control::InputDebug* input_debug) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete input_debug_; + } + if (input_debug) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + input_debug = ::google::protobuf::internal::GetOwnedMessage( + message_arena, input_debug, submessage_arena); + } + + } else { + + } + input_debug_ = input_debug; + // @@protoc_insertion_point(field_set_allocated:apollo.control.Debug.input_debug) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace control +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::control::TurnSignal> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::control::TurnSignal>() { + return ::apollo::control::TurnSignal_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fcmd_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/control/control_conf.pb.cc b/apollo_msgs/include/apollo_msgs/proto/control/control_conf.pb.cc new file mode 100644 index 0000000..8d83dea --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/control/control_conf.pb.cc @@ -0,0 +1,957 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/control/control_conf.proto + +#include "apollo_msgs/proto/control/control_conf.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_LatControllerConf; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto ::google::protobuf::internal::SCCInfo<3> scc_info_LonControllerConf; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto +namespace apollo { +namespace control { +class ControlConfDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ControlConf_default_instance_; +} // namespace control +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto { +static void InitDefaultsControlConf() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::_ControlConf_default_instance_; + new (ptr) ::apollo::control::ControlConf(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::ControlConf::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_ControlConf = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsControlConf}, { + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto::scc_info_LatControllerConf.base, + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::scc_info_LonControllerConf.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_ControlConf.base); +} + +::google::protobuf::Metadata file_level_metadata[1]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, control_period_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, max_planning_interval_sec_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, max_planning_delay_threshold_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, driving_mode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, action_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, soft_estop_brake_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, active_controllers_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, max_steering_percentage_allowed_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, max_status_interval_sec_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, lat_controller_conf_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, lon_controller_conf_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, trajectory_period_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, chassis_period_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::ControlConf, localization_period_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::control::ControlConf)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::control::_ControlConf_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/control/control_conf.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 1); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n,apollo_msgs/proto/control/control_conf" + ".proto\022\016apollo.control\032&apollo_msgs/prot" + "o/canbus/chassis.proto\032\'apollo_msgs/prot" + "o/control/pad_msg.proto\0323apollo_msgs/pro" + "to/control/lat_controller_conf.proto\0323ap" + "ollo_msgs/proto/control/lon_controller_c" + "onf.proto\"\215\005\n\013ControlConf\022\026\n\016control_per" + "iod\030\001 \001(\001\022!\n\031max_planning_interval_sec\030\002" + " \001(\001\022$\n\034max_planning_delay_threshold\030\003 \001" + "(\001\0228\n\014driving_mode\030\004 \001(\0162\".apollo.canbus" + ".Chassis.DrivingMode\022-\n\006action\030\005 \001(\0162\035.a" + "pollo.control.DrivingAction\022\030\n\020soft_esto" + "p_brake\030\006 \001(\001\022F\n\022active_controllers\030\007 \003(" + "\0162*.apollo.control.ControlConf.Controlle" + "rType\022\'\n\037max_steering_percentage_allowed" + "\030\010 \001(\005\022\037\n\027max_status_interval_sec\030\t \001(\001\022" + ">\n\023lat_controller_conf\030\n \001(\0132!.apollo.co" + "ntrol.LatControllerConf\022>\n\023lon_controlle" + "r_conf\030\013 \001(\0132!.apollo.control.LonControl" + "lerConf\022\031\n\021trajectory_period\030\014 \001(\001\022\026\n\016ch" + "assis_period\030\r \001(\001\022\033\n\023localization_perio" + "d\030\016 \001(\001\"8\n\016ControllerType\022\022\n\016LAT_CONTROL" + "LER\020\000\022\022\n\016LON_CONTROLLER\020\001b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 913); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/control/control_conf.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto +namespace apollo { +namespace control { +const ::google::protobuf::EnumDescriptor* ControlConf_ControllerType_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto::file_level_enum_descriptors[0]; +} +bool ControlConf_ControllerType_IsValid(int value) { + switch (value) { + case 0: + case 1: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const ControlConf_ControllerType ControlConf::LAT_CONTROLLER; +const ControlConf_ControllerType ControlConf::LON_CONTROLLER; +const ControlConf_ControllerType ControlConf::ControllerType_MIN; +const ControlConf_ControllerType ControlConf::ControllerType_MAX; +const int ControlConf::ControllerType_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +// =================================================================== + +void ControlConf::InitAsDefaultInstance() { + ::apollo::control::_ControlConf_default_instance_._instance.get_mutable()->lat_controller_conf_ = const_cast< ::apollo::control::LatControllerConf*>( + ::apollo::control::LatControllerConf::internal_default_instance()); + ::apollo::control::_ControlConf_default_instance_._instance.get_mutable()->lon_controller_conf_ = const_cast< ::apollo::control::LonControllerConf*>( + ::apollo::control::LonControllerConf::internal_default_instance()); +} +void ControlConf::clear_lat_controller_conf() { + if (GetArenaNoVirtual() == NULL && lat_controller_conf_ != NULL) { + delete lat_controller_conf_; + } + lat_controller_conf_ = NULL; +} +void ControlConf::clear_lon_controller_conf() { + if (GetArenaNoVirtual() == NULL && lon_controller_conf_ != NULL) { + delete lon_controller_conf_; + } + lon_controller_conf_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ControlConf::kControlPeriodFieldNumber; +const int ControlConf::kMaxPlanningIntervalSecFieldNumber; +const int ControlConf::kMaxPlanningDelayThresholdFieldNumber; +const int ControlConf::kDrivingModeFieldNumber; +const int ControlConf::kActionFieldNumber; +const int ControlConf::kSoftEstopBrakeFieldNumber; +const int ControlConf::kActiveControllersFieldNumber; +const int ControlConf::kMaxSteeringPercentageAllowedFieldNumber; +const int ControlConf::kMaxStatusIntervalSecFieldNumber; +const int ControlConf::kLatControllerConfFieldNumber; +const int ControlConf::kLonControllerConfFieldNumber; +const int ControlConf::kTrajectoryPeriodFieldNumber; +const int ControlConf::kChassisPeriodFieldNumber; +const int ControlConf::kLocalizationPeriodFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ControlConf::ControlConf() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto::scc_info_ControlConf.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.ControlConf) +} +ControlConf::ControlConf(const ControlConf& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + active_controllers_(from.active_controllers_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_lat_controller_conf()) { + lat_controller_conf_ = new ::apollo::control::LatControllerConf(*from.lat_controller_conf_); + } else { + lat_controller_conf_ = NULL; + } + if (from.has_lon_controller_conf()) { + lon_controller_conf_ = new ::apollo::control::LonControllerConf(*from.lon_controller_conf_); + } else { + lon_controller_conf_ = NULL; + } + ::memcpy(&control_period_, &from.control_period_, + static_cast(reinterpret_cast(&max_steering_percentage_allowed_) - + reinterpret_cast(&control_period_)) + sizeof(max_steering_percentage_allowed_)); + // @@protoc_insertion_point(copy_constructor:apollo.control.ControlConf) +} + +void ControlConf::SharedCtor() { + ::memset(&lat_controller_conf_, 0, static_cast( + reinterpret_cast(&max_steering_percentage_allowed_) - + reinterpret_cast(&lat_controller_conf_)) + sizeof(max_steering_percentage_allowed_)); +} + +ControlConf::~ControlConf() { + // @@protoc_insertion_point(destructor:apollo.control.ControlConf) + SharedDtor(); +} + +void ControlConf::SharedDtor() { + if (this != internal_default_instance()) delete lat_controller_conf_; + if (this != internal_default_instance()) delete lon_controller_conf_; +} + +void ControlConf::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ControlConf::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ControlConf& ControlConf::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto::scc_info_ControlConf.base); + return *internal_default_instance(); +} + + +void ControlConf::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.ControlConf) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + active_controllers_.Clear(); + if (GetArenaNoVirtual() == NULL && lat_controller_conf_ != NULL) { + delete lat_controller_conf_; + } + lat_controller_conf_ = NULL; + if (GetArenaNoVirtual() == NULL && lon_controller_conf_ != NULL) { + delete lon_controller_conf_; + } + lon_controller_conf_ = NULL; + ::memset(&control_period_, 0, static_cast( + reinterpret_cast(&max_steering_percentage_allowed_) - + reinterpret_cast(&control_period_)) + sizeof(max_steering_percentage_allowed_)); + _internal_metadata_.Clear(); +} + +bool ControlConf::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.ControlConf) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double control_period = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &control_period_))); + } else { + goto handle_unusual; + } + break; + } + + // double max_planning_interval_sec = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &max_planning_interval_sec_))); + } else { + goto handle_unusual; + } + break; + } + + // double max_planning_delay_threshold = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &max_planning_delay_threshold_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_driving_mode(static_cast< ::apollo::canbus::Chassis_DrivingMode >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.DrivingAction action = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(40u /* 40 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_action(static_cast< ::apollo::control::DrivingAction >(value)); + } else { + goto handle_unusual; + } + break; + } + + // double soft_estop_brake = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &soft_estop_brake_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.control.ControlConf.ControllerType active_controllers = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(58u /* 58 & 0xFF */)) { + ::google::protobuf::uint32 length; + DO_(input->ReadVarint32(&length)); + ::google::protobuf::io::CodedInputStream::Limit limit = input->PushLimit(static_cast(length)); + while (input->BytesUntilLimit() > 0) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + add_active_controllers(static_cast< ::apollo::control::ControlConf_ControllerType >(value)); + } + input->PopLimit(limit); + } else if ( + static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(56u /* 56 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + add_active_controllers(static_cast< ::apollo::control::ControlConf_ControllerType >(value)); + } else { + goto handle_unusual; + } + break; + } + + // int32 max_steering_percentage_allowed = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(64u /* 64 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &max_steering_percentage_allowed_))); + } else { + goto handle_unusual; + } + break; + } + + // double max_status_interval_sec = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(73u /* 73 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &max_status_interval_sec_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.LatControllerConf lat_controller_conf = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(82u /* 82 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_lat_controller_conf())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.LonControllerConf lon_controller_conf = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(90u /* 90 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_lon_controller_conf())); + } else { + goto handle_unusual; + } + break; + } + + // double trajectory_period = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(97u /* 97 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &trajectory_period_))); + } else { + goto handle_unusual; + } + break; + } + + // double chassis_period = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(105u /* 105 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &chassis_period_))); + } else { + goto handle_unusual; + } + break; + } + + // double localization_period = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(113u /* 113 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &localization_period_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.ControlConf) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.ControlConf) + return false; +#undef DO_ +} + +void ControlConf::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.ControlConf) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double control_period = 1; + if (this->control_period() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->control_period(), output); + } + + // double max_planning_interval_sec = 2; + if (this->max_planning_interval_sec() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->max_planning_interval_sec(), output); + } + + // double max_planning_delay_threshold = 3; + if (this->max_planning_delay_threshold() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->max_planning_delay_threshold(), output); + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 4; + if (this->driving_mode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 4, this->driving_mode(), output); + } + + // .apollo.control.DrivingAction action = 5; + if (this->action() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 5, this->action(), output); + } + + // double soft_estop_brake = 6; + if (this->soft_estop_brake() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->soft_estop_brake(), output); + } + + // repeated .apollo.control.ControlConf.ControllerType active_controllers = 7; + if (this->active_controllers_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag( + 7, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + output); + output->WriteVarint32( + static_cast< ::google::protobuf::uint32>(_active_controllers_cached_byte_size_)); + } + for (int i = 0, n = this->active_controllers_size(); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteEnumNoTag( + this->active_controllers(i), output); + } + + // int32 max_steering_percentage_allowed = 8; + if (this->max_steering_percentage_allowed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(8, this->max_steering_percentage_allowed(), output); + } + + // double max_status_interval_sec = 9; + if (this->max_status_interval_sec() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->max_status_interval_sec(), output); + } + + // .apollo.control.LatControllerConf lat_controller_conf = 10; + if (this->has_lat_controller_conf()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 10, this->_internal_lat_controller_conf(), output); + } + + // .apollo.control.LonControllerConf lon_controller_conf = 11; + if (this->has_lon_controller_conf()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 11, this->_internal_lon_controller_conf(), output); + } + + // double trajectory_period = 12; + if (this->trajectory_period() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(12, this->trajectory_period(), output); + } + + // double chassis_period = 13; + if (this->chassis_period() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(13, this->chassis_period(), output); + } + + // double localization_period = 14; + if (this->localization_period() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(14, this->localization_period(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.ControlConf) +} + +::google::protobuf::uint8* ControlConf::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.ControlConf) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double control_period = 1; + if (this->control_period() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->control_period(), target); + } + + // double max_planning_interval_sec = 2; + if (this->max_planning_interval_sec() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->max_planning_interval_sec(), target); + } + + // double max_planning_delay_threshold = 3; + if (this->max_planning_delay_threshold() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->max_planning_delay_threshold(), target); + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 4; + if (this->driving_mode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 4, this->driving_mode(), target); + } + + // .apollo.control.DrivingAction action = 5; + if (this->action() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 5, this->action(), target); + } + + // double soft_estop_brake = 6; + if (this->soft_estop_brake() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->soft_estop_brake(), target); + } + + // repeated .apollo.control.ControlConf.ControllerType active_controllers = 7; + if (this->active_controllers_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 7, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( static_cast< ::google::protobuf::uint32>( + _active_controllers_cached_byte_size_), target); + target = ::google::protobuf::internal::WireFormatLite::WriteEnumNoTagToArray( + this->active_controllers_, target); + } + + // int32 max_steering_percentage_allowed = 8; + if (this->max_steering_percentage_allowed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(8, this->max_steering_percentage_allowed(), target); + } + + // double max_status_interval_sec = 9; + if (this->max_status_interval_sec() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->max_status_interval_sec(), target); + } + + // .apollo.control.LatControllerConf lat_controller_conf = 10; + if (this->has_lat_controller_conf()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 10, this->_internal_lat_controller_conf(), deterministic, target); + } + + // .apollo.control.LonControllerConf lon_controller_conf = 11; + if (this->has_lon_controller_conf()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 11, this->_internal_lon_controller_conf(), deterministic, target); + } + + // double trajectory_period = 12; + if (this->trajectory_period() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(12, this->trajectory_period(), target); + } + + // double chassis_period = 13; + if (this->chassis_period() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(13, this->chassis_period(), target); + } + + // double localization_period = 14; + if (this->localization_period() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(14, this->localization_period(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.ControlConf) + return target; +} + +size_t ControlConf::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.ControlConf) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.control.ControlConf.ControllerType active_controllers = 7; + { + size_t data_size = 0; + unsigned int count = static_cast(this->active_controllers_size());for (unsigned int i = 0; i < count; i++) { + data_size += ::google::protobuf::internal::WireFormatLite::EnumSize( + this->active_controllers(static_cast(i))); + } + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + static_cast< ::google::protobuf::int32>(data_size)); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _active_controllers_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // .apollo.control.LatControllerConf lat_controller_conf = 10; + if (this->has_lat_controller_conf()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *lat_controller_conf_); + } + + // .apollo.control.LonControllerConf lon_controller_conf = 11; + if (this->has_lon_controller_conf()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *lon_controller_conf_); + } + + // double control_period = 1; + if (this->control_period() != 0) { + total_size += 1 + 8; + } + + // double max_planning_interval_sec = 2; + if (this->max_planning_interval_sec() != 0) { + total_size += 1 + 8; + } + + // double max_planning_delay_threshold = 3; + if (this->max_planning_delay_threshold() != 0) { + total_size += 1 + 8; + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 4; + if (this->driving_mode() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->driving_mode()); + } + + // .apollo.control.DrivingAction action = 5; + if (this->action() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->action()); + } + + // double soft_estop_brake = 6; + if (this->soft_estop_brake() != 0) { + total_size += 1 + 8; + } + + // double max_status_interval_sec = 9; + if (this->max_status_interval_sec() != 0) { + total_size += 1 + 8; + } + + // double trajectory_period = 12; + if (this->trajectory_period() != 0) { + total_size += 1 + 8; + } + + // double chassis_period = 13; + if (this->chassis_period() != 0) { + total_size += 1 + 8; + } + + // double localization_period = 14; + if (this->localization_period() != 0) { + total_size += 1 + 8; + } + + // int32 max_steering_percentage_allowed = 8; + if (this->max_steering_percentage_allowed() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->max_steering_percentage_allowed()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ControlConf::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.ControlConf) + GOOGLE_DCHECK_NE(&from, this); + const ControlConf* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.ControlConf) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.ControlConf) + MergeFrom(*source); + } +} + +void ControlConf::MergeFrom(const ControlConf& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.ControlConf) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + active_controllers_.MergeFrom(from.active_controllers_); + if (from.has_lat_controller_conf()) { + mutable_lat_controller_conf()->::apollo::control::LatControllerConf::MergeFrom(from.lat_controller_conf()); + } + if (from.has_lon_controller_conf()) { + mutable_lon_controller_conf()->::apollo::control::LonControllerConf::MergeFrom(from.lon_controller_conf()); + } + if (from.control_period() != 0) { + set_control_period(from.control_period()); + } + if (from.max_planning_interval_sec() != 0) { + set_max_planning_interval_sec(from.max_planning_interval_sec()); + } + if (from.max_planning_delay_threshold() != 0) { + set_max_planning_delay_threshold(from.max_planning_delay_threshold()); + } + if (from.driving_mode() != 0) { + set_driving_mode(from.driving_mode()); + } + if (from.action() != 0) { + set_action(from.action()); + } + if (from.soft_estop_brake() != 0) { + set_soft_estop_brake(from.soft_estop_brake()); + } + if (from.max_status_interval_sec() != 0) { + set_max_status_interval_sec(from.max_status_interval_sec()); + } + if (from.trajectory_period() != 0) { + set_trajectory_period(from.trajectory_period()); + } + if (from.chassis_period() != 0) { + set_chassis_period(from.chassis_period()); + } + if (from.localization_period() != 0) { + set_localization_period(from.localization_period()); + } + if (from.max_steering_percentage_allowed() != 0) { + set_max_steering_percentage_allowed(from.max_steering_percentage_allowed()); + } +} + +void ControlConf::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.ControlConf) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ControlConf::CopyFrom(const ControlConf& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.ControlConf) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ControlConf::IsInitialized() const { + return true; +} + +void ControlConf::Swap(ControlConf* other) { + if (other == this) return; + InternalSwap(other); +} +void ControlConf::InternalSwap(ControlConf* other) { + using std::swap; + active_controllers_.InternalSwap(&other->active_controllers_); + swap(lat_controller_conf_, other->lat_controller_conf_); + swap(lon_controller_conf_, other->lon_controller_conf_); + swap(control_period_, other->control_period_); + swap(max_planning_interval_sec_, other->max_planning_interval_sec_); + swap(max_planning_delay_threshold_, other->max_planning_delay_threshold_); + swap(driving_mode_, other->driving_mode_); + swap(action_, other->action_); + swap(soft_estop_brake_, other->soft_estop_brake_); + swap(max_status_interval_sec_, other->max_status_interval_sec_); + swap(trajectory_period_, other->trajectory_period_); + swap(chassis_period_, other->chassis_period_); + swap(localization_period_, other->localization_period_); + swap(max_steering_percentage_allowed_, other->max_steering_percentage_allowed_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ControlConf::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace control +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::ControlConf* Arena::CreateMaybeMessage< ::apollo::control::ControlConf >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::ControlConf >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/control/control_conf.pb.h b/apollo_msgs/include/apollo_msgs/proto/control/control_conf.pb.h new file mode 100644 index 0000000..10d0f09 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/control/control_conf.pb.h @@ -0,0 +1,640 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/control/control_conf.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "apollo_msgs/proto/canbus/chassis.pb.h" +#include "apollo_msgs/proto/control/pad_msg.pb.h" +#include "apollo_msgs/proto/control/lat_controller_conf.pb.h" +#include "apollo_msgs/proto/control/lon_controller_conf.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[1]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto +namespace apollo { +namespace control { +class ControlConf; +class ControlConfDefaultTypeInternal; +extern ControlConfDefaultTypeInternal _ControlConf_default_instance_; +} // namespace control +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::control::ControlConf* Arena::CreateMaybeMessage<::apollo::control::ControlConf>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace control { + +enum ControlConf_ControllerType { + ControlConf_ControllerType_LAT_CONTROLLER = 0, + ControlConf_ControllerType_LON_CONTROLLER = 1, + ControlConf_ControllerType_ControlConf_ControllerType_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + ControlConf_ControllerType_ControlConf_ControllerType_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool ControlConf_ControllerType_IsValid(int value); +const ControlConf_ControllerType ControlConf_ControllerType_ControllerType_MIN = ControlConf_ControllerType_LAT_CONTROLLER; +const ControlConf_ControllerType ControlConf_ControllerType_ControllerType_MAX = ControlConf_ControllerType_LON_CONTROLLER; +const int ControlConf_ControllerType_ControllerType_ARRAYSIZE = ControlConf_ControllerType_ControllerType_MAX + 1; + +const ::google::protobuf::EnumDescriptor* ControlConf_ControllerType_descriptor(); +inline const ::std::string& ControlConf_ControllerType_Name(ControlConf_ControllerType value) { + return ::google::protobuf::internal::NameOfEnum( + ControlConf_ControllerType_descriptor(), value); +} +inline bool ControlConf_ControllerType_Parse( + const ::std::string& name, ControlConf_ControllerType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + ControlConf_ControllerType_descriptor(), name, value); +} +// =================================================================== + +class ControlConf : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.ControlConf) */ { + public: + ControlConf(); + virtual ~ControlConf(); + + ControlConf(const ControlConf& from); + + inline ControlConf& operator=(const ControlConf& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ControlConf(ControlConf&& from) noexcept + : ControlConf() { + *this = ::std::move(from); + } + + inline ControlConf& operator=(ControlConf&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ControlConf& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ControlConf* internal_default_instance() { + return reinterpret_cast( + &_ControlConf_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(ControlConf* other); + friend void swap(ControlConf& a, ControlConf& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ControlConf* New() const final { + return CreateMaybeMessage(NULL); + } + + ControlConf* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ControlConf& from); + void MergeFrom(const ControlConf& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ControlConf* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef ControlConf_ControllerType ControllerType; + static const ControllerType LAT_CONTROLLER = + ControlConf_ControllerType_LAT_CONTROLLER; + static const ControllerType LON_CONTROLLER = + ControlConf_ControllerType_LON_CONTROLLER; + static inline bool ControllerType_IsValid(int value) { + return ControlConf_ControllerType_IsValid(value); + } + static const ControllerType ControllerType_MIN = + ControlConf_ControllerType_ControllerType_MIN; + static const ControllerType ControllerType_MAX = + ControlConf_ControllerType_ControllerType_MAX; + static const int ControllerType_ARRAYSIZE = + ControlConf_ControllerType_ControllerType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + ControllerType_descriptor() { + return ControlConf_ControllerType_descriptor(); + } + static inline const ::std::string& ControllerType_Name(ControllerType value) { + return ControlConf_ControllerType_Name(value); + } + static inline bool ControllerType_Parse(const ::std::string& name, + ControllerType* value) { + return ControlConf_ControllerType_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // repeated .apollo.control.ControlConf.ControllerType active_controllers = 7; + int active_controllers_size() const; + void clear_active_controllers(); + static const int kActiveControllersFieldNumber = 7; + ::apollo::control::ControlConf_ControllerType active_controllers(int index) const; + void set_active_controllers(int index, ::apollo::control::ControlConf_ControllerType value); + void add_active_controllers(::apollo::control::ControlConf_ControllerType value); + const ::google::protobuf::RepeatedField& active_controllers() const; + ::google::protobuf::RepeatedField* mutable_active_controllers(); + + // .apollo.control.LatControllerConf lat_controller_conf = 10; + bool has_lat_controller_conf() const; + void clear_lat_controller_conf(); + static const int kLatControllerConfFieldNumber = 10; + private: + const ::apollo::control::LatControllerConf& _internal_lat_controller_conf() const; + public: + const ::apollo::control::LatControllerConf& lat_controller_conf() const; + ::apollo::control::LatControllerConf* release_lat_controller_conf(); + ::apollo::control::LatControllerConf* mutable_lat_controller_conf(); + void set_allocated_lat_controller_conf(::apollo::control::LatControllerConf* lat_controller_conf); + + // .apollo.control.LonControllerConf lon_controller_conf = 11; + bool has_lon_controller_conf() const; + void clear_lon_controller_conf(); + static const int kLonControllerConfFieldNumber = 11; + private: + const ::apollo::control::LonControllerConf& _internal_lon_controller_conf() const; + public: + const ::apollo::control::LonControllerConf& lon_controller_conf() const; + ::apollo::control::LonControllerConf* release_lon_controller_conf(); + ::apollo::control::LonControllerConf* mutable_lon_controller_conf(); + void set_allocated_lon_controller_conf(::apollo::control::LonControllerConf* lon_controller_conf); + + // double control_period = 1; + void clear_control_period(); + static const int kControlPeriodFieldNumber = 1; + double control_period() const; + void set_control_period(double value); + + // double max_planning_interval_sec = 2; + void clear_max_planning_interval_sec(); + static const int kMaxPlanningIntervalSecFieldNumber = 2; + double max_planning_interval_sec() const; + void set_max_planning_interval_sec(double value); + + // double max_planning_delay_threshold = 3; + void clear_max_planning_delay_threshold(); + static const int kMaxPlanningDelayThresholdFieldNumber = 3; + double max_planning_delay_threshold() const; + void set_max_planning_delay_threshold(double value); + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 4; + void clear_driving_mode(); + static const int kDrivingModeFieldNumber = 4; + ::apollo::canbus::Chassis_DrivingMode driving_mode() const; + void set_driving_mode(::apollo::canbus::Chassis_DrivingMode value); + + // .apollo.control.DrivingAction action = 5; + void clear_action(); + static const int kActionFieldNumber = 5; + ::apollo::control::DrivingAction action() const; + void set_action(::apollo::control::DrivingAction value); + + // double soft_estop_brake = 6; + void clear_soft_estop_brake(); + static const int kSoftEstopBrakeFieldNumber = 6; + double soft_estop_brake() const; + void set_soft_estop_brake(double value); + + // double max_status_interval_sec = 9; + void clear_max_status_interval_sec(); + static const int kMaxStatusIntervalSecFieldNumber = 9; + double max_status_interval_sec() const; + void set_max_status_interval_sec(double value); + + // double trajectory_period = 12; + void clear_trajectory_period(); + static const int kTrajectoryPeriodFieldNumber = 12; + double trajectory_period() const; + void set_trajectory_period(double value); + + // double chassis_period = 13; + void clear_chassis_period(); + static const int kChassisPeriodFieldNumber = 13; + double chassis_period() const; + void set_chassis_period(double value); + + // double localization_period = 14; + void clear_localization_period(); + static const int kLocalizationPeriodFieldNumber = 14; + double localization_period() const; + void set_localization_period(double value); + + // int32 max_steering_percentage_allowed = 8; + void clear_max_steering_percentage_allowed(); + static const int kMaxSteeringPercentageAllowedFieldNumber = 8; + ::google::protobuf::int32 max_steering_percentage_allowed() const; + void set_max_steering_percentage_allowed(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:apollo.control.ControlConf) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedField active_controllers_; + mutable int _active_controllers_cached_byte_size_; + ::apollo::control::LatControllerConf* lat_controller_conf_; + ::apollo::control::LonControllerConf* lon_controller_conf_; + double control_period_; + double max_planning_interval_sec_; + double max_planning_delay_threshold_; + int driving_mode_; + int action_; + double soft_estop_brake_; + double max_status_interval_sec_; + double trajectory_period_; + double chassis_period_; + double localization_period_; + ::google::protobuf::int32 max_steering_percentage_allowed_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// ControlConf + +// double control_period = 1; +inline void ControlConf::clear_control_period() { + control_period_ = 0; +} +inline double ControlConf::control_period() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.control_period) + return control_period_; +} +inline void ControlConf::set_control_period(double value) { + + control_period_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlConf.control_period) +} + +// double max_planning_interval_sec = 2; +inline void ControlConf::clear_max_planning_interval_sec() { + max_planning_interval_sec_ = 0; +} +inline double ControlConf::max_planning_interval_sec() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.max_planning_interval_sec) + return max_planning_interval_sec_; +} +inline void ControlConf::set_max_planning_interval_sec(double value) { + + max_planning_interval_sec_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlConf.max_planning_interval_sec) +} + +// double max_planning_delay_threshold = 3; +inline void ControlConf::clear_max_planning_delay_threshold() { + max_planning_delay_threshold_ = 0; +} +inline double ControlConf::max_planning_delay_threshold() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.max_planning_delay_threshold) + return max_planning_delay_threshold_; +} +inline void ControlConf::set_max_planning_delay_threshold(double value) { + + max_planning_delay_threshold_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlConf.max_planning_delay_threshold) +} + +// .apollo.canbus.Chassis.DrivingMode driving_mode = 4; +inline void ControlConf::clear_driving_mode() { + driving_mode_ = 0; +} +inline ::apollo::canbus::Chassis_DrivingMode ControlConf::driving_mode() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.driving_mode) + return static_cast< ::apollo::canbus::Chassis_DrivingMode >(driving_mode_); +} +inline void ControlConf::set_driving_mode(::apollo::canbus::Chassis_DrivingMode value) { + + driving_mode_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlConf.driving_mode) +} + +// .apollo.control.DrivingAction action = 5; +inline void ControlConf::clear_action() { + action_ = 0; +} +inline ::apollo::control::DrivingAction ControlConf::action() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.action) + return static_cast< ::apollo::control::DrivingAction >(action_); +} +inline void ControlConf::set_action(::apollo::control::DrivingAction value) { + + action_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlConf.action) +} + +// double soft_estop_brake = 6; +inline void ControlConf::clear_soft_estop_brake() { + soft_estop_brake_ = 0; +} +inline double ControlConf::soft_estop_brake() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.soft_estop_brake) + return soft_estop_brake_; +} +inline void ControlConf::set_soft_estop_brake(double value) { + + soft_estop_brake_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlConf.soft_estop_brake) +} + +// repeated .apollo.control.ControlConf.ControllerType active_controllers = 7; +inline int ControlConf::active_controllers_size() const { + return active_controllers_.size(); +} +inline void ControlConf::clear_active_controllers() { + active_controllers_.Clear(); +} +inline ::apollo::control::ControlConf_ControllerType ControlConf::active_controllers(int index) const { + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.active_controllers) + return static_cast< ::apollo::control::ControlConf_ControllerType >(active_controllers_.Get(index)); +} +inline void ControlConf::set_active_controllers(int index, ::apollo::control::ControlConf_ControllerType value) { + active_controllers_.Set(index, value); + // @@protoc_insertion_point(field_set:apollo.control.ControlConf.active_controllers) +} +inline void ControlConf::add_active_controllers(::apollo::control::ControlConf_ControllerType value) { + active_controllers_.Add(value); + // @@protoc_insertion_point(field_add:apollo.control.ControlConf.active_controllers) +} +inline const ::google::protobuf::RepeatedField& +ControlConf::active_controllers() const { + // @@protoc_insertion_point(field_list:apollo.control.ControlConf.active_controllers) + return active_controllers_; +} +inline ::google::protobuf::RepeatedField* +ControlConf::mutable_active_controllers() { + // @@protoc_insertion_point(field_mutable_list:apollo.control.ControlConf.active_controllers) + return &active_controllers_; +} + +// int32 max_steering_percentage_allowed = 8; +inline void ControlConf::clear_max_steering_percentage_allowed() { + max_steering_percentage_allowed_ = 0; +} +inline ::google::protobuf::int32 ControlConf::max_steering_percentage_allowed() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.max_steering_percentage_allowed) + return max_steering_percentage_allowed_; +} +inline void ControlConf::set_max_steering_percentage_allowed(::google::protobuf::int32 value) { + + max_steering_percentage_allowed_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlConf.max_steering_percentage_allowed) +} + +// double max_status_interval_sec = 9; +inline void ControlConf::clear_max_status_interval_sec() { + max_status_interval_sec_ = 0; +} +inline double ControlConf::max_status_interval_sec() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.max_status_interval_sec) + return max_status_interval_sec_; +} +inline void ControlConf::set_max_status_interval_sec(double value) { + + max_status_interval_sec_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlConf.max_status_interval_sec) +} + +// .apollo.control.LatControllerConf lat_controller_conf = 10; +inline bool ControlConf::has_lat_controller_conf() const { + return this != internal_default_instance() && lat_controller_conf_ != NULL; +} +inline const ::apollo::control::LatControllerConf& ControlConf::_internal_lat_controller_conf() const { + return *lat_controller_conf_; +} +inline const ::apollo::control::LatControllerConf& ControlConf::lat_controller_conf() const { + const ::apollo::control::LatControllerConf* p = lat_controller_conf_; + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.lat_controller_conf) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_LatControllerConf_default_instance_); +} +inline ::apollo::control::LatControllerConf* ControlConf::release_lat_controller_conf() { + // @@protoc_insertion_point(field_release:apollo.control.ControlConf.lat_controller_conf) + + ::apollo::control::LatControllerConf* temp = lat_controller_conf_; + lat_controller_conf_ = NULL; + return temp; +} +inline ::apollo::control::LatControllerConf* ControlConf::mutable_lat_controller_conf() { + + if (lat_controller_conf_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::LatControllerConf>(GetArenaNoVirtual()); + lat_controller_conf_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.ControlConf.lat_controller_conf) + return lat_controller_conf_; +} +inline void ControlConf::set_allocated_lat_controller_conf(::apollo::control::LatControllerConf* lat_controller_conf) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(lat_controller_conf_); + } + if (lat_controller_conf) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + lat_controller_conf = ::google::protobuf::internal::GetOwnedMessage( + message_arena, lat_controller_conf, submessage_arena); + } + + } else { + + } + lat_controller_conf_ = lat_controller_conf; + // @@protoc_insertion_point(field_set_allocated:apollo.control.ControlConf.lat_controller_conf) +} + +// .apollo.control.LonControllerConf lon_controller_conf = 11; +inline bool ControlConf::has_lon_controller_conf() const { + return this != internal_default_instance() && lon_controller_conf_ != NULL; +} +inline const ::apollo::control::LonControllerConf& ControlConf::_internal_lon_controller_conf() const { + return *lon_controller_conf_; +} +inline const ::apollo::control::LonControllerConf& ControlConf::lon_controller_conf() const { + const ::apollo::control::LonControllerConf* p = lon_controller_conf_; + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.lon_controller_conf) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_LonControllerConf_default_instance_); +} +inline ::apollo::control::LonControllerConf* ControlConf::release_lon_controller_conf() { + // @@protoc_insertion_point(field_release:apollo.control.ControlConf.lon_controller_conf) + + ::apollo::control::LonControllerConf* temp = lon_controller_conf_; + lon_controller_conf_ = NULL; + return temp; +} +inline ::apollo::control::LonControllerConf* ControlConf::mutable_lon_controller_conf() { + + if (lon_controller_conf_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::LonControllerConf>(GetArenaNoVirtual()); + lon_controller_conf_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.ControlConf.lon_controller_conf) + return lon_controller_conf_; +} +inline void ControlConf::set_allocated_lon_controller_conf(::apollo::control::LonControllerConf* lon_controller_conf) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(lon_controller_conf_); + } + if (lon_controller_conf) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + lon_controller_conf = ::google::protobuf::internal::GetOwnedMessage( + message_arena, lon_controller_conf, submessage_arena); + } + + } else { + + } + lon_controller_conf_ = lon_controller_conf; + // @@protoc_insertion_point(field_set_allocated:apollo.control.ControlConf.lon_controller_conf) +} + +// double trajectory_period = 12; +inline void ControlConf::clear_trajectory_period() { + trajectory_period_ = 0; +} +inline double ControlConf::trajectory_period() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.trajectory_period) + return trajectory_period_; +} +inline void ControlConf::set_trajectory_period(double value) { + + trajectory_period_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlConf.trajectory_period) +} + +// double chassis_period = 13; +inline void ControlConf::clear_chassis_period() { + chassis_period_ = 0; +} +inline double ControlConf::chassis_period() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.chassis_period) + return chassis_period_; +} +inline void ControlConf::set_chassis_period(double value) { + + chassis_period_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlConf.chassis_period) +} + +// double localization_period = 14; +inline void ControlConf::clear_localization_period() { + localization_period_ = 0; +} +inline double ControlConf::localization_period() const { + // @@protoc_insertion_point(field_get:apollo.control.ControlConf.localization_period) + return localization_period_; +} +inline void ControlConf::set_localization_period(double value) { + + localization_period_ = value; + // @@protoc_insertion_point(field_set:apollo.control.ControlConf.localization_period) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) + +} // namespace control +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::control::ControlConf_ControllerType> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::control::ControlConf_ControllerType>() { + return ::apollo::control::ControlConf_ControllerType_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2fcontrol_5fconf_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/control/lat_controller_conf.pb.cc b/apollo_msgs/include/apollo_msgs/proto/control/lat_controller_conf.pb.cc new file mode 100644 index 0000000..9c62926 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/control/lat_controller_conf.pb.cc @@ -0,0 +1,932 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/control/lat_controller_conf.proto + +#include "apollo_msgs/proto/control/lat_controller_conf.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace apollo { +namespace control { +class LatControllerConfDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _LatControllerConf_default_instance_; +} // namespace control +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto { +static void InitDefaultsLatControllerConf() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::_LatControllerConf_default_instance_; + new (ptr) ::apollo::control::LatControllerConf(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::LatControllerConf::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_LatControllerConf = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsLatControllerConf}, {}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_LatControllerConf.base); +} + +::google::protobuf::Metadata file_level_metadata[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, ts_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, preview_window_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, cf_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, cr_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, wheelbase_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, mass_fl_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, mass_fr_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, mass_rl_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, mass_rr_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, eps_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, matrix_q_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, cutoff_freq_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, mean_filter_window_size_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, steer_transmission_ratio_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, steer_single_direction_max_degree_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LatControllerConf, max_iteration_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::control::LatControllerConf)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::control::_LatControllerConf_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/control/lat_controller_conf.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 1); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n3apollo_msgs/proto/control/lat_controll" + "er_conf.proto\022\016apollo.control\"\337\002\n\021LatCon" + "trollerConf\022\n\n\002ts\030\001 \001(\001\022\026\n\016preview_windo" + "w\030\002 \001(\005\022\n\n\002cf\030\003 \001(\001\022\n\n\002cr\030\004 \001(\001\022\021\n\twheel" + "base\030\005 \001(\001\022\017\n\007mass_fl\030\006 \001(\005\022\017\n\007mass_fr\030\007" + " \001(\005\022\017\n\007mass_rl\030\010 \001(\005\022\017\n\007mass_rr\030\t \001(\005\022\013" + "\n\003eps\030\n \001(\001\022\020\n\010matrix_q\030\013 \003(\001\022\023\n\013cutoff_" + "freq\030\014 \001(\005\022\037\n\027mean_filter_window_size\030\r " + "\001(\005\022 \n\030steer_transmission_ratio\030\016 \001(\005\022)\n" + "!steer_single_direction_max_degree\030\017 \001(\005" + "\022\025\n\rmax_iteration\030\020 \001(\005b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 431); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/control/lat_controller_conf.proto", &protobuf_RegisterTypes); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto +namespace apollo { +namespace control { + +// =================================================================== + +void LatControllerConf::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int LatControllerConf::kTsFieldNumber; +const int LatControllerConf::kPreviewWindowFieldNumber; +const int LatControllerConf::kCfFieldNumber; +const int LatControllerConf::kCrFieldNumber; +const int LatControllerConf::kWheelbaseFieldNumber; +const int LatControllerConf::kMassFlFieldNumber; +const int LatControllerConf::kMassFrFieldNumber; +const int LatControllerConf::kMassRlFieldNumber; +const int LatControllerConf::kMassRrFieldNumber; +const int LatControllerConf::kEpsFieldNumber; +const int LatControllerConf::kMatrixQFieldNumber; +const int LatControllerConf::kCutoffFreqFieldNumber; +const int LatControllerConf::kMeanFilterWindowSizeFieldNumber; +const int LatControllerConf::kSteerTransmissionRatioFieldNumber; +const int LatControllerConf::kSteerSingleDirectionMaxDegreeFieldNumber; +const int LatControllerConf::kMaxIterationFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +LatControllerConf::LatControllerConf() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto::scc_info_LatControllerConf.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.LatControllerConf) +} +LatControllerConf::LatControllerConf(const LatControllerConf& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + matrix_q_(from.matrix_q_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&ts_, &from.ts_, + static_cast(reinterpret_cast(&max_iteration_) - + reinterpret_cast(&ts_)) + sizeof(max_iteration_)); + // @@protoc_insertion_point(copy_constructor:apollo.control.LatControllerConf) +} + +void LatControllerConf::SharedCtor() { + ::memset(&ts_, 0, static_cast( + reinterpret_cast(&max_iteration_) - + reinterpret_cast(&ts_)) + sizeof(max_iteration_)); +} + +LatControllerConf::~LatControllerConf() { + // @@protoc_insertion_point(destructor:apollo.control.LatControllerConf) + SharedDtor(); +} + +void LatControllerConf::SharedDtor() { +} + +void LatControllerConf::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* LatControllerConf::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const LatControllerConf& LatControllerConf::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto::scc_info_LatControllerConf.base); + return *internal_default_instance(); +} + + +void LatControllerConf::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.LatControllerConf) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + matrix_q_.Clear(); + ::memset(&ts_, 0, static_cast( + reinterpret_cast(&max_iteration_) - + reinterpret_cast(&ts_)) + sizeof(max_iteration_)); + _internal_metadata_.Clear(); +} + +bool LatControllerConf::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.LatControllerConf) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double ts = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &ts_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 preview_window = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &preview_window_))); + } else { + goto handle_unusual; + } + break; + } + + // double cf = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &cf_))); + } else { + goto handle_unusual; + } + break; + } + + // double cr = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &cr_))); + } else { + goto handle_unusual; + } + break; + } + + // double wheelbase = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &wheelbase_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 mass_fl = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(48u /* 48 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &mass_fl_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 mass_fr = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(56u /* 56 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &mass_fr_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 mass_rl = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(64u /* 64 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &mass_rl_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 mass_rr = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(72u /* 72 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &mass_rr_))); + } else { + goto handle_unusual; + } + break; + } + + // double eps = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(81u /* 81 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &eps_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double matrix_q = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(90u /* 90 & 0xFF */)) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_matrix_q()))); + } else if ( + static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(89u /* 89 & 0xFF */)) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 90u, input, this->mutable_matrix_q()))); + } else { + goto handle_unusual; + } + break; + } + + // int32 cutoff_freq = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(96u /* 96 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &cutoff_freq_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 mean_filter_window_size = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(104u /* 104 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &mean_filter_window_size_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 steer_transmission_ratio = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(112u /* 112 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &steer_transmission_ratio_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 steer_single_direction_max_degree = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(120u /* 120 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &steer_single_direction_max_degree_))); + } else { + goto handle_unusual; + } + break; + } + + // int32 max_iteration = 16; + case 16: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(128u /* 128 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &max_iteration_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.LatControllerConf) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.LatControllerConf) + return false; +#undef DO_ +} + +void LatControllerConf::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.LatControllerConf) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double ts = 1; + if (this->ts() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->ts(), output); + } + + // int32 preview_window = 2; + if (this->preview_window() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->preview_window(), output); + } + + // double cf = 3; + if (this->cf() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->cf(), output); + } + + // double cr = 4; + if (this->cr() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->cr(), output); + } + + // double wheelbase = 5; + if (this->wheelbase() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->wheelbase(), output); + } + + // int32 mass_fl = 6; + if (this->mass_fl() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(6, this->mass_fl(), output); + } + + // int32 mass_fr = 7; + if (this->mass_fr() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(7, this->mass_fr(), output); + } + + // int32 mass_rl = 8; + if (this->mass_rl() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(8, this->mass_rl(), output); + } + + // int32 mass_rr = 9; + if (this->mass_rr() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(9, this->mass_rr(), output); + } + + // double eps = 10; + if (this->eps() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(10, this->eps(), output); + } + + // repeated double matrix_q = 11; + if (this->matrix_q_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(11, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(static_cast< ::google::protobuf::uint32>( + _matrix_q_cached_byte_size_)); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->matrix_q().data(), this->matrix_q_size(), output); + } + + // int32 cutoff_freq = 12; + if (this->cutoff_freq() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(12, this->cutoff_freq(), output); + } + + // int32 mean_filter_window_size = 13; + if (this->mean_filter_window_size() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(13, this->mean_filter_window_size(), output); + } + + // int32 steer_transmission_ratio = 14; + if (this->steer_transmission_ratio() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(14, this->steer_transmission_ratio(), output); + } + + // int32 steer_single_direction_max_degree = 15; + if (this->steer_single_direction_max_degree() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(15, this->steer_single_direction_max_degree(), output); + } + + // int32 max_iteration = 16; + if (this->max_iteration() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(16, this->max_iteration(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.LatControllerConf) +} + +::google::protobuf::uint8* LatControllerConf::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.LatControllerConf) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double ts = 1; + if (this->ts() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->ts(), target); + } + + // int32 preview_window = 2; + if (this->preview_window() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->preview_window(), target); + } + + // double cf = 3; + if (this->cf() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->cf(), target); + } + + // double cr = 4; + if (this->cr() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->cr(), target); + } + + // double wheelbase = 5; + if (this->wheelbase() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->wheelbase(), target); + } + + // int32 mass_fl = 6; + if (this->mass_fl() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(6, this->mass_fl(), target); + } + + // int32 mass_fr = 7; + if (this->mass_fr() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(7, this->mass_fr(), target); + } + + // int32 mass_rl = 8; + if (this->mass_rl() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(8, this->mass_rl(), target); + } + + // int32 mass_rr = 9; + if (this->mass_rr() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(9, this->mass_rr(), target); + } + + // double eps = 10; + if (this->eps() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(10, this->eps(), target); + } + + // repeated double matrix_q = 11; + if (this->matrix_q_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 11, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + static_cast< ::google::protobuf::int32>( + _matrix_q_cached_byte_size_), target); + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->matrix_q_, target); + } + + // int32 cutoff_freq = 12; + if (this->cutoff_freq() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(12, this->cutoff_freq(), target); + } + + // int32 mean_filter_window_size = 13; + if (this->mean_filter_window_size() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(13, this->mean_filter_window_size(), target); + } + + // int32 steer_transmission_ratio = 14; + if (this->steer_transmission_ratio() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(14, this->steer_transmission_ratio(), target); + } + + // int32 steer_single_direction_max_degree = 15; + if (this->steer_single_direction_max_degree() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(15, this->steer_single_direction_max_degree(), target); + } + + // int32 max_iteration = 16; + if (this->max_iteration() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(16, this->max_iteration(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.LatControllerConf) + return target; +} + +size_t LatControllerConf::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.LatControllerConf) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated double matrix_q = 11; + { + unsigned int count = static_cast(this->matrix_q_size()); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + static_cast< ::google::protobuf::int32>(data_size)); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _matrix_q_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // double ts = 1; + if (this->ts() != 0) { + total_size += 1 + 8; + } + + // double cf = 3; + if (this->cf() != 0) { + total_size += 1 + 8; + } + + // double cr = 4; + if (this->cr() != 0) { + total_size += 1 + 8; + } + + // int32 preview_window = 2; + if (this->preview_window() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->preview_window()); + } + + // int32 mass_fl = 6; + if (this->mass_fl() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->mass_fl()); + } + + // double wheelbase = 5; + if (this->wheelbase() != 0) { + total_size += 1 + 8; + } + + // int32 mass_fr = 7; + if (this->mass_fr() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->mass_fr()); + } + + // int32 mass_rl = 8; + if (this->mass_rl() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->mass_rl()); + } + + // double eps = 10; + if (this->eps() != 0) { + total_size += 1 + 8; + } + + // int32 mass_rr = 9; + if (this->mass_rr() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->mass_rr()); + } + + // int32 cutoff_freq = 12; + if (this->cutoff_freq() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->cutoff_freq()); + } + + // int32 mean_filter_window_size = 13; + if (this->mean_filter_window_size() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->mean_filter_window_size()); + } + + // int32 steer_transmission_ratio = 14; + if (this->steer_transmission_ratio() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->steer_transmission_ratio()); + } + + // int32 steer_single_direction_max_degree = 15; + if (this->steer_single_direction_max_degree() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->steer_single_direction_max_degree()); + } + + // int32 max_iteration = 16; + if (this->max_iteration() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->max_iteration()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void LatControllerConf::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.LatControllerConf) + GOOGLE_DCHECK_NE(&from, this); + const LatControllerConf* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.LatControllerConf) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.LatControllerConf) + MergeFrom(*source); + } +} + +void LatControllerConf::MergeFrom(const LatControllerConf& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.LatControllerConf) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + matrix_q_.MergeFrom(from.matrix_q_); + if (from.ts() != 0) { + set_ts(from.ts()); + } + if (from.cf() != 0) { + set_cf(from.cf()); + } + if (from.cr() != 0) { + set_cr(from.cr()); + } + if (from.preview_window() != 0) { + set_preview_window(from.preview_window()); + } + if (from.mass_fl() != 0) { + set_mass_fl(from.mass_fl()); + } + if (from.wheelbase() != 0) { + set_wheelbase(from.wheelbase()); + } + if (from.mass_fr() != 0) { + set_mass_fr(from.mass_fr()); + } + if (from.mass_rl() != 0) { + set_mass_rl(from.mass_rl()); + } + if (from.eps() != 0) { + set_eps(from.eps()); + } + if (from.mass_rr() != 0) { + set_mass_rr(from.mass_rr()); + } + if (from.cutoff_freq() != 0) { + set_cutoff_freq(from.cutoff_freq()); + } + if (from.mean_filter_window_size() != 0) { + set_mean_filter_window_size(from.mean_filter_window_size()); + } + if (from.steer_transmission_ratio() != 0) { + set_steer_transmission_ratio(from.steer_transmission_ratio()); + } + if (from.steer_single_direction_max_degree() != 0) { + set_steer_single_direction_max_degree(from.steer_single_direction_max_degree()); + } + if (from.max_iteration() != 0) { + set_max_iteration(from.max_iteration()); + } +} + +void LatControllerConf::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.LatControllerConf) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void LatControllerConf::CopyFrom(const LatControllerConf& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.LatControllerConf) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool LatControllerConf::IsInitialized() const { + return true; +} + +void LatControllerConf::Swap(LatControllerConf* other) { + if (other == this) return; + InternalSwap(other); +} +void LatControllerConf::InternalSwap(LatControllerConf* other) { + using std::swap; + matrix_q_.InternalSwap(&other->matrix_q_); + swap(ts_, other->ts_); + swap(cf_, other->cf_); + swap(cr_, other->cr_); + swap(preview_window_, other->preview_window_); + swap(mass_fl_, other->mass_fl_); + swap(wheelbase_, other->wheelbase_); + swap(mass_fr_, other->mass_fr_); + swap(mass_rl_, other->mass_rl_); + swap(eps_, other->eps_); + swap(mass_rr_, other->mass_rr_); + swap(cutoff_freq_, other->cutoff_freq_); + swap(mean_filter_window_size_, other->mean_filter_window_size_); + swap(steer_transmission_ratio_, other->steer_transmission_ratio_); + swap(steer_single_direction_max_degree_, other->steer_single_direction_max_degree_); + swap(max_iteration_, other->max_iteration_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata LatControllerConf::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace control +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::LatControllerConf* Arena::CreateMaybeMessage< ::apollo::control::LatControllerConf >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::LatControllerConf >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/control/lat_controller_conf.pb.h b/apollo_msgs/include/apollo_msgs/proto/control/lat_controller_conf.pb.h new file mode 100644 index 0000000..e3bb907 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/control/lat_controller_conf.pb.h @@ -0,0 +1,540 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/control/lat_controller_conf.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[1]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto +namespace apollo { +namespace control { +class LatControllerConf; +class LatControllerConfDefaultTypeInternal; +extern LatControllerConfDefaultTypeInternal _LatControllerConf_default_instance_; +} // namespace control +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::control::LatControllerConf* Arena::CreateMaybeMessage<::apollo::control::LatControllerConf>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace control { + +// =================================================================== + +class LatControllerConf : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.LatControllerConf) */ { + public: + LatControllerConf(); + virtual ~LatControllerConf(); + + LatControllerConf(const LatControllerConf& from); + + inline LatControllerConf& operator=(const LatControllerConf& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + LatControllerConf(LatControllerConf&& from) noexcept + : LatControllerConf() { + *this = ::std::move(from); + } + + inline LatControllerConf& operator=(LatControllerConf&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const LatControllerConf& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const LatControllerConf* internal_default_instance() { + return reinterpret_cast( + &_LatControllerConf_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(LatControllerConf* other); + friend void swap(LatControllerConf& a, LatControllerConf& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline LatControllerConf* New() const final { + return CreateMaybeMessage(NULL); + } + + LatControllerConf* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const LatControllerConf& from); + void MergeFrom(const LatControllerConf& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(LatControllerConf* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated double matrix_q = 11; + int matrix_q_size() const; + void clear_matrix_q(); + static const int kMatrixQFieldNumber = 11; + double matrix_q(int index) const; + void set_matrix_q(int index, double value); + void add_matrix_q(double value); + const ::google::protobuf::RepeatedField< double >& + matrix_q() const; + ::google::protobuf::RepeatedField< double >* + mutable_matrix_q(); + + // double ts = 1; + void clear_ts(); + static const int kTsFieldNumber = 1; + double ts() const; + void set_ts(double value); + + // double cf = 3; + void clear_cf(); + static const int kCfFieldNumber = 3; + double cf() const; + void set_cf(double value); + + // double cr = 4; + void clear_cr(); + static const int kCrFieldNumber = 4; + double cr() const; + void set_cr(double value); + + // int32 preview_window = 2; + void clear_preview_window(); + static const int kPreviewWindowFieldNumber = 2; + ::google::protobuf::int32 preview_window() const; + void set_preview_window(::google::protobuf::int32 value); + + // int32 mass_fl = 6; + void clear_mass_fl(); + static const int kMassFlFieldNumber = 6; + ::google::protobuf::int32 mass_fl() const; + void set_mass_fl(::google::protobuf::int32 value); + + // double wheelbase = 5; + void clear_wheelbase(); + static const int kWheelbaseFieldNumber = 5; + double wheelbase() const; + void set_wheelbase(double value); + + // int32 mass_fr = 7; + void clear_mass_fr(); + static const int kMassFrFieldNumber = 7; + ::google::protobuf::int32 mass_fr() const; + void set_mass_fr(::google::protobuf::int32 value); + + // int32 mass_rl = 8; + void clear_mass_rl(); + static const int kMassRlFieldNumber = 8; + ::google::protobuf::int32 mass_rl() const; + void set_mass_rl(::google::protobuf::int32 value); + + // double eps = 10; + void clear_eps(); + static const int kEpsFieldNumber = 10; + double eps() const; + void set_eps(double value); + + // int32 mass_rr = 9; + void clear_mass_rr(); + static const int kMassRrFieldNumber = 9; + ::google::protobuf::int32 mass_rr() const; + void set_mass_rr(::google::protobuf::int32 value); + + // int32 cutoff_freq = 12; + void clear_cutoff_freq(); + static const int kCutoffFreqFieldNumber = 12; + ::google::protobuf::int32 cutoff_freq() const; + void set_cutoff_freq(::google::protobuf::int32 value); + + // int32 mean_filter_window_size = 13; + void clear_mean_filter_window_size(); + static const int kMeanFilterWindowSizeFieldNumber = 13; + ::google::protobuf::int32 mean_filter_window_size() const; + void set_mean_filter_window_size(::google::protobuf::int32 value); + + // int32 steer_transmission_ratio = 14; + void clear_steer_transmission_ratio(); + static const int kSteerTransmissionRatioFieldNumber = 14; + ::google::protobuf::int32 steer_transmission_ratio() const; + void set_steer_transmission_ratio(::google::protobuf::int32 value); + + // int32 steer_single_direction_max_degree = 15; + void clear_steer_single_direction_max_degree(); + static const int kSteerSingleDirectionMaxDegreeFieldNumber = 15; + ::google::protobuf::int32 steer_single_direction_max_degree() const; + void set_steer_single_direction_max_degree(::google::protobuf::int32 value); + + // int32 max_iteration = 16; + void clear_max_iteration(); + static const int kMaxIterationFieldNumber = 16; + ::google::protobuf::int32 max_iteration() const; + void set_max_iteration(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:apollo.control.LatControllerConf) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedField< double > matrix_q_; + mutable int _matrix_q_cached_byte_size_; + double ts_; + double cf_; + double cr_; + ::google::protobuf::int32 preview_window_; + ::google::protobuf::int32 mass_fl_; + double wheelbase_; + ::google::protobuf::int32 mass_fr_; + ::google::protobuf::int32 mass_rl_; + double eps_; + ::google::protobuf::int32 mass_rr_; + ::google::protobuf::int32 cutoff_freq_; + ::google::protobuf::int32 mean_filter_window_size_; + ::google::protobuf::int32 steer_transmission_ratio_; + ::google::protobuf::int32 steer_single_direction_max_degree_; + ::google::protobuf::int32 max_iteration_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// LatControllerConf + +// double ts = 1; +inline void LatControllerConf::clear_ts() { + ts_ = 0; +} +inline double LatControllerConf::ts() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.ts) + return ts_; +} +inline void LatControllerConf::set_ts(double value) { + + ts_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.ts) +} + +// int32 preview_window = 2; +inline void LatControllerConf::clear_preview_window() { + preview_window_ = 0; +} +inline ::google::protobuf::int32 LatControllerConf::preview_window() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.preview_window) + return preview_window_; +} +inline void LatControllerConf::set_preview_window(::google::protobuf::int32 value) { + + preview_window_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.preview_window) +} + +// double cf = 3; +inline void LatControllerConf::clear_cf() { + cf_ = 0; +} +inline double LatControllerConf::cf() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.cf) + return cf_; +} +inline void LatControllerConf::set_cf(double value) { + + cf_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.cf) +} + +// double cr = 4; +inline void LatControllerConf::clear_cr() { + cr_ = 0; +} +inline double LatControllerConf::cr() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.cr) + return cr_; +} +inline void LatControllerConf::set_cr(double value) { + + cr_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.cr) +} + +// double wheelbase = 5; +inline void LatControllerConf::clear_wheelbase() { + wheelbase_ = 0; +} +inline double LatControllerConf::wheelbase() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.wheelbase) + return wheelbase_; +} +inline void LatControllerConf::set_wheelbase(double value) { + + wheelbase_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.wheelbase) +} + +// int32 mass_fl = 6; +inline void LatControllerConf::clear_mass_fl() { + mass_fl_ = 0; +} +inline ::google::protobuf::int32 LatControllerConf::mass_fl() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.mass_fl) + return mass_fl_; +} +inline void LatControllerConf::set_mass_fl(::google::protobuf::int32 value) { + + mass_fl_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.mass_fl) +} + +// int32 mass_fr = 7; +inline void LatControllerConf::clear_mass_fr() { + mass_fr_ = 0; +} +inline ::google::protobuf::int32 LatControllerConf::mass_fr() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.mass_fr) + return mass_fr_; +} +inline void LatControllerConf::set_mass_fr(::google::protobuf::int32 value) { + + mass_fr_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.mass_fr) +} + +// int32 mass_rl = 8; +inline void LatControllerConf::clear_mass_rl() { + mass_rl_ = 0; +} +inline ::google::protobuf::int32 LatControllerConf::mass_rl() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.mass_rl) + return mass_rl_; +} +inline void LatControllerConf::set_mass_rl(::google::protobuf::int32 value) { + + mass_rl_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.mass_rl) +} + +// int32 mass_rr = 9; +inline void LatControllerConf::clear_mass_rr() { + mass_rr_ = 0; +} +inline ::google::protobuf::int32 LatControllerConf::mass_rr() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.mass_rr) + return mass_rr_; +} +inline void LatControllerConf::set_mass_rr(::google::protobuf::int32 value) { + + mass_rr_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.mass_rr) +} + +// double eps = 10; +inline void LatControllerConf::clear_eps() { + eps_ = 0; +} +inline double LatControllerConf::eps() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.eps) + return eps_; +} +inline void LatControllerConf::set_eps(double value) { + + eps_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.eps) +} + +// repeated double matrix_q = 11; +inline int LatControllerConf::matrix_q_size() const { + return matrix_q_.size(); +} +inline void LatControllerConf::clear_matrix_q() { + matrix_q_.Clear(); +} +inline double LatControllerConf::matrix_q(int index) const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.matrix_q) + return matrix_q_.Get(index); +} +inline void LatControllerConf::set_matrix_q(int index, double value) { + matrix_q_.Set(index, value); + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.matrix_q) +} +inline void LatControllerConf::add_matrix_q(double value) { + matrix_q_.Add(value); + // @@protoc_insertion_point(field_add:apollo.control.LatControllerConf.matrix_q) +} +inline const ::google::protobuf::RepeatedField< double >& +LatControllerConf::matrix_q() const { + // @@protoc_insertion_point(field_list:apollo.control.LatControllerConf.matrix_q) + return matrix_q_; +} +inline ::google::protobuf::RepeatedField< double >* +LatControllerConf::mutable_matrix_q() { + // @@protoc_insertion_point(field_mutable_list:apollo.control.LatControllerConf.matrix_q) + return &matrix_q_; +} + +// int32 cutoff_freq = 12; +inline void LatControllerConf::clear_cutoff_freq() { + cutoff_freq_ = 0; +} +inline ::google::protobuf::int32 LatControllerConf::cutoff_freq() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.cutoff_freq) + return cutoff_freq_; +} +inline void LatControllerConf::set_cutoff_freq(::google::protobuf::int32 value) { + + cutoff_freq_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.cutoff_freq) +} + +// int32 mean_filter_window_size = 13; +inline void LatControllerConf::clear_mean_filter_window_size() { + mean_filter_window_size_ = 0; +} +inline ::google::protobuf::int32 LatControllerConf::mean_filter_window_size() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.mean_filter_window_size) + return mean_filter_window_size_; +} +inline void LatControllerConf::set_mean_filter_window_size(::google::protobuf::int32 value) { + + mean_filter_window_size_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.mean_filter_window_size) +} + +// int32 steer_transmission_ratio = 14; +inline void LatControllerConf::clear_steer_transmission_ratio() { + steer_transmission_ratio_ = 0; +} +inline ::google::protobuf::int32 LatControllerConf::steer_transmission_ratio() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.steer_transmission_ratio) + return steer_transmission_ratio_; +} +inline void LatControllerConf::set_steer_transmission_ratio(::google::protobuf::int32 value) { + + steer_transmission_ratio_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.steer_transmission_ratio) +} + +// int32 steer_single_direction_max_degree = 15; +inline void LatControllerConf::clear_steer_single_direction_max_degree() { + steer_single_direction_max_degree_ = 0; +} +inline ::google::protobuf::int32 LatControllerConf::steer_single_direction_max_degree() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.steer_single_direction_max_degree) + return steer_single_direction_max_degree_; +} +inline void LatControllerConf::set_steer_single_direction_max_degree(::google::protobuf::int32 value) { + + steer_single_direction_max_degree_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.steer_single_direction_max_degree) +} + +// int32 max_iteration = 16; +inline void LatControllerConf::clear_max_iteration() { + max_iteration_ = 0; +} +inline ::google::protobuf::int32 LatControllerConf::max_iteration() const { + // @@protoc_insertion_point(field_get:apollo.control.LatControllerConf.max_iteration) + return max_iteration_; +} +inline void LatControllerConf::set_max_iteration(::google::protobuf::int32 value) { + + max_iteration_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LatControllerConf.max_iteration) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) + +} // namespace control +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2flat_5fcontroller_5fconf_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/control/lon_controller_conf.pb.cc b/apollo_msgs/include/apollo_msgs/proto/control/lon_controller_conf.pb.cc new file mode 100644 index 0000000..da5a36a --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/control/lon_controller_conf.pb.cc @@ -0,0 +1,1636 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/control/lon_controller_conf.proto + +#include "apollo_msgs/proto/control/lon_controller_conf.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_ControlCalibrationTable; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_FilterConf; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_PidConf; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto +namespace apollo { +namespace control { +class PidConfDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _PidConf_default_instance_; +class FilterConfDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _FilterConf_default_instance_; +class LonControllerConfDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _LonControllerConf_default_instance_; +} // namespace control +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto { +static void InitDefaultsPidConf() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::_PidConf_default_instance_; + new (ptr) ::apollo::control::PidConf(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::PidConf::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_PidConf = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsPidConf}, {}}; + +static void InitDefaultsFilterConf() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::_FilterConf_default_instance_; + new (ptr) ::apollo::control::FilterConf(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::FilterConf::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_FilterConf = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsFilterConf}, {}}; + +static void InitDefaultsLonControllerConf() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::_LonControllerConf_default_instance_; + new (ptr) ::apollo::control::LonControllerConf(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::LonControllerConf::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<3> scc_info_LonControllerConf = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 3, InitDefaultsLonControllerConf}, { + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::scc_info_PidConf.base, + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::scc_info_FilterConf.base, + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::scc_info_ControlCalibrationTable.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_PidConf.base); + ::google::protobuf::internal::InitSCC(&scc_info_FilterConf.base); + ::google::protobuf::internal::InitSCC(&scc_info_LonControllerConf.base); +} + +::google::protobuf::Metadata file_level_metadata[3]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::PidConf, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::PidConf, integrator_enable_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::PidConf, integrator_saturation_level_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::PidConf, kp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::PidConf, ki_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::PidConf, kd_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::FilterConf, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::FilterConf, cutoff_freq_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, ts_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, brake_deadzone_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, throttle_deadzone_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, speed_controller_input_limit_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, station_error_limit_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, preview_window_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, standstill_acceleration_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, station_pid_conf_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, low_speed_pid_conf_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, high_speed_pid_conf_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, switch_speed_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, throttle_filter_conf_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, brake_filter_conf_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, acceleration_filter_conf_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::LonControllerConf, calibration_table_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::control::PidConf)}, + { 10, -1, sizeof(::apollo::control::FilterConf)}, + { 16, -1, sizeof(::apollo::control::LonControllerConf)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::control::_PidConf_default_instance_), + reinterpret_cast(&::apollo::control::_FilterConf_default_instance_), + reinterpret_cast(&::apollo::control::_LonControllerConf_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/control/lon_controller_conf.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 3); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n3apollo_msgs/proto/control/lon_controll" + "er_conf.proto\022\016apollo.control\0321apollo_ms" + "gs/proto/control/calibration_table.proto" + "\"m\n\007PidConf\022\031\n\021integrator_enable\030\001 \001(\010\022#" + "\n\033integrator_saturation_level\030\002 \001(\001\022\n\n\002k" + "p\030\003 \001(\001\022\n\n\002ki\030\004 \001(\001\022\n\n\002kd\030\005 \001(\001\"!\n\nFilte" + "rConf\022\023\n\013cutoff_freq\030\001 \001(\005\"\206\005\n\021LonContro" + "llerConf\022\n\n\002ts\030\001 \001(\001\022\026\n\016brake_deadzone\030\002" + " \001(\001\022\031\n\021throttle_deadzone\030\003 \001(\001\022$\n\034speed" + "_controller_input_limit\030\004 \001(\001\022\033\n\023station" + "_error_limit\030\005 \001(\001\022\026\n\016preview_window\030\006 \001" + "(\001\022\037\n\027standstill_acceleration\030\007 \001(\001\0221\n\020s" + "tation_pid_conf\030\010 \001(\0132\027.apollo.control.P" + "idConf\0223\n\022low_speed_pid_conf\030\t \001(\0132\027.apo" + "llo.control.PidConf\0224\n\023high_speed_pid_co" + "nf\030\n \001(\0132\027.apollo.control.PidConf\022\024\n\014swi" + "tch_speed\030\013 \001(\001\0228\n\024throttle_filter_conf\030" + "\014 \001(\0132\032.apollo.control.FilterConf\0225\n\021bra" + "ke_filter_conf\030\r \001(\0132\032.apollo.control.Fi" + "lterConf\022<\n\030acceleration_filter_conf\030\016 \001" + "(\0132\032.apollo.control.FilterConf\022S\n\021calibr" + "ation_table\030\017 \001(\01328.apollo.control.calib" + "rationtable.ControlCalibrationTableb\006pro" + "to3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 923); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/control/lon_controller_conf.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fcalibration_5ftable_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto +namespace apollo { +namespace control { + +// =================================================================== + +void PidConf::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PidConf::kIntegratorEnableFieldNumber; +const int PidConf::kIntegratorSaturationLevelFieldNumber; +const int PidConf::kKpFieldNumber; +const int PidConf::kKiFieldNumber; +const int PidConf::kKdFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PidConf::PidConf() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::scc_info_PidConf.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.PidConf) +} +PidConf::PidConf(const PidConf& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&integrator_saturation_level_, &from.integrator_saturation_level_, + static_cast(reinterpret_cast(&integrator_enable_) - + reinterpret_cast(&integrator_saturation_level_)) + sizeof(integrator_enable_)); + // @@protoc_insertion_point(copy_constructor:apollo.control.PidConf) +} + +void PidConf::SharedCtor() { + ::memset(&integrator_saturation_level_, 0, static_cast( + reinterpret_cast(&integrator_enable_) - + reinterpret_cast(&integrator_saturation_level_)) + sizeof(integrator_enable_)); +} + +PidConf::~PidConf() { + // @@protoc_insertion_point(destructor:apollo.control.PidConf) + SharedDtor(); +} + +void PidConf::SharedDtor() { +} + +void PidConf::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* PidConf::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const PidConf& PidConf::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::scc_info_PidConf.base); + return *internal_default_instance(); +} + + +void PidConf::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.PidConf) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&integrator_saturation_level_, 0, static_cast( + reinterpret_cast(&integrator_enable_) - + reinterpret_cast(&integrator_saturation_level_)) + sizeof(integrator_enable_)); + _internal_metadata_.Clear(); +} + +bool PidConf::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.PidConf) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool integrator_enable = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &integrator_enable_))); + } else { + goto handle_unusual; + } + break; + } + + // double integrator_saturation_level = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &integrator_saturation_level_))); + } else { + goto handle_unusual; + } + break; + } + + // double kp = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &kp_))); + } else { + goto handle_unusual; + } + break; + } + + // double ki = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &ki_))); + } else { + goto handle_unusual; + } + break; + } + + // double kd = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &kd_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.PidConf) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.PidConf) + return false; +#undef DO_ +} + +void PidConf::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.PidConf) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool integrator_enable = 1; + if (this->integrator_enable() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->integrator_enable(), output); + } + + // double integrator_saturation_level = 2; + if (this->integrator_saturation_level() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->integrator_saturation_level(), output); + } + + // double kp = 3; + if (this->kp() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->kp(), output); + } + + // double ki = 4; + if (this->ki() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->ki(), output); + } + + // double kd = 5; + if (this->kd() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->kd(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.PidConf) +} + +::google::protobuf::uint8* PidConf::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.PidConf) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool integrator_enable = 1; + if (this->integrator_enable() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->integrator_enable(), target); + } + + // double integrator_saturation_level = 2; + if (this->integrator_saturation_level() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->integrator_saturation_level(), target); + } + + // double kp = 3; + if (this->kp() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->kp(), target); + } + + // double ki = 4; + if (this->ki() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->ki(), target); + } + + // double kd = 5; + if (this->kd() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->kd(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.PidConf) + return target; +} + +size_t PidConf::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.PidConf) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double integrator_saturation_level = 2; + if (this->integrator_saturation_level() != 0) { + total_size += 1 + 8; + } + + // double kp = 3; + if (this->kp() != 0) { + total_size += 1 + 8; + } + + // double ki = 4; + if (this->ki() != 0) { + total_size += 1 + 8; + } + + // double kd = 5; + if (this->kd() != 0) { + total_size += 1 + 8; + } + + // bool integrator_enable = 1; + if (this->integrator_enable() != 0) { + total_size += 1 + 1; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void PidConf::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.PidConf) + GOOGLE_DCHECK_NE(&from, this); + const PidConf* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.PidConf) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.PidConf) + MergeFrom(*source); + } +} + +void PidConf::MergeFrom(const PidConf& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.PidConf) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.integrator_saturation_level() != 0) { + set_integrator_saturation_level(from.integrator_saturation_level()); + } + if (from.kp() != 0) { + set_kp(from.kp()); + } + if (from.ki() != 0) { + set_ki(from.ki()); + } + if (from.kd() != 0) { + set_kd(from.kd()); + } + if (from.integrator_enable() != 0) { + set_integrator_enable(from.integrator_enable()); + } +} + +void PidConf::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.PidConf) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PidConf::CopyFrom(const PidConf& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.PidConf) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PidConf::IsInitialized() const { + return true; +} + +void PidConf::Swap(PidConf* other) { + if (other == this) return; + InternalSwap(other); +} +void PidConf::InternalSwap(PidConf* other) { + using std::swap; + swap(integrator_saturation_level_, other->integrator_saturation_level_); + swap(kp_, other->kp_); + swap(ki_, other->ki_); + swap(kd_, other->kd_); + swap(integrator_enable_, other->integrator_enable_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata PidConf::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void FilterConf::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int FilterConf::kCutoffFreqFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +FilterConf::FilterConf() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::scc_info_FilterConf.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.FilterConf) +} +FilterConf::FilterConf(const FilterConf& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + cutoff_freq_ = from.cutoff_freq_; + // @@protoc_insertion_point(copy_constructor:apollo.control.FilterConf) +} + +void FilterConf::SharedCtor() { + cutoff_freq_ = 0; +} + +FilterConf::~FilterConf() { + // @@protoc_insertion_point(destructor:apollo.control.FilterConf) + SharedDtor(); +} + +void FilterConf::SharedDtor() { +} + +void FilterConf::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* FilterConf::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const FilterConf& FilterConf::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::scc_info_FilterConf.base); + return *internal_default_instance(); +} + + +void FilterConf::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.FilterConf) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cutoff_freq_ = 0; + _internal_metadata_.Clear(); +} + +bool FilterConf::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.FilterConf) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // int32 cutoff_freq = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &cutoff_freq_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.FilterConf) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.FilterConf) + return false; +#undef DO_ +} + +void FilterConf::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.FilterConf) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // int32 cutoff_freq = 1; + if (this->cutoff_freq() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->cutoff_freq(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.FilterConf) +} + +::google::protobuf::uint8* FilterConf::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.FilterConf) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // int32 cutoff_freq = 1; + if (this->cutoff_freq() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->cutoff_freq(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.FilterConf) + return target; +} + +size_t FilterConf::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.FilterConf) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // int32 cutoff_freq = 1; + if (this->cutoff_freq() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->cutoff_freq()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void FilterConf::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.FilterConf) + GOOGLE_DCHECK_NE(&from, this); + const FilterConf* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.FilterConf) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.FilterConf) + MergeFrom(*source); + } +} + +void FilterConf::MergeFrom(const FilterConf& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.FilterConf) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.cutoff_freq() != 0) { + set_cutoff_freq(from.cutoff_freq()); + } +} + +void FilterConf::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.FilterConf) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void FilterConf::CopyFrom(const FilterConf& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.FilterConf) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool FilterConf::IsInitialized() const { + return true; +} + +void FilterConf::Swap(FilterConf* other) { + if (other == this) return; + InternalSwap(other); +} +void FilterConf::InternalSwap(FilterConf* other) { + using std::swap; + swap(cutoff_freq_, other->cutoff_freq_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata FilterConf::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void LonControllerConf::InitAsDefaultInstance() { + ::apollo::control::_LonControllerConf_default_instance_._instance.get_mutable()->station_pid_conf_ = const_cast< ::apollo::control::PidConf*>( + ::apollo::control::PidConf::internal_default_instance()); + ::apollo::control::_LonControllerConf_default_instance_._instance.get_mutable()->low_speed_pid_conf_ = const_cast< ::apollo::control::PidConf*>( + ::apollo::control::PidConf::internal_default_instance()); + ::apollo::control::_LonControllerConf_default_instance_._instance.get_mutable()->high_speed_pid_conf_ = const_cast< ::apollo::control::PidConf*>( + ::apollo::control::PidConf::internal_default_instance()); + ::apollo::control::_LonControllerConf_default_instance_._instance.get_mutable()->throttle_filter_conf_ = const_cast< ::apollo::control::FilterConf*>( + ::apollo::control::FilterConf::internal_default_instance()); + ::apollo::control::_LonControllerConf_default_instance_._instance.get_mutable()->brake_filter_conf_ = const_cast< ::apollo::control::FilterConf*>( + ::apollo::control::FilterConf::internal_default_instance()); + ::apollo::control::_LonControllerConf_default_instance_._instance.get_mutable()->acceleration_filter_conf_ = const_cast< ::apollo::control::FilterConf*>( + ::apollo::control::FilterConf::internal_default_instance()); + ::apollo::control::_LonControllerConf_default_instance_._instance.get_mutable()->calibration_table_ = const_cast< ::apollo::control::calibrationtable::ControlCalibrationTable*>( + ::apollo::control::calibrationtable::ControlCalibrationTable::internal_default_instance()); +} +void LonControllerConf::clear_calibration_table() { + if (GetArenaNoVirtual() == NULL && calibration_table_ != NULL) { + delete calibration_table_; + } + calibration_table_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int LonControllerConf::kTsFieldNumber; +const int LonControllerConf::kBrakeDeadzoneFieldNumber; +const int LonControllerConf::kThrottleDeadzoneFieldNumber; +const int LonControllerConf::kSpeedControllerInputLimitFieldNumber; +const int LonControllerConf::kStationErrorLimitFieldNumber; +const int LonControllerConf::kPreviewWindowFieldNumber; +const int LonControllerConf::kStandstillAccelerationFieldNumber; +const int LonControllerConf::kStationPidConfFieldNumber; +const int LonControllerConf::kLowSpeedPidConfFieldNumber; +const int LonControllerConf::kHighSpeedPidConfFieldNumber; +const int LonControllerConf::kSwitchSpeedFieldNumber; +const int LonControllerConf::kThrottleFilterConfFieldNumber; +const int LonControllerConf::kBrakeFilterConfFieldNumber; +const int LonControllerConf::kAccelerationFilterConfFieldNumber; +const int LonControllerConf::kCalibrationTableFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +LonControllerConf::LonControllerConf() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::scc_info_LonControllerConf.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.LonControllerConf) +} +LonControllerConf::LonControllerConf(const LonControllerConf& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_station_pid_conf()) { + station_pid_conf_ = new ::apollo::control::PidConf(*from.station_pid_conf_); + } else { + station_pid_conf_ = NULL; + } + if (from.has_low_speed_pid_conf()) { + low_speed_pid_conf_ = new ::apollo::control::PidConf(*from.low_speed_pid_conf_); + } else { + low_speed_pid_conf_ = NULL; + } + if (from.has_high_speed_pid_conf()) { + high_speed_pid_conf_ = new ::apollo::control::PidConf(*from.high_speed_pid_conf_); + } else { + high_speed_pid_conf_ = NULL; + } + if (from.has_throttle_filter_conf()) { + throttle_filter_conf_ = new ::apollo::control::FilterConf(*from.throttle_filter_conf_); + } else { + throttle_filter_conf_ = NULL; + } + if (from.has_brake_filter_conf()) { + brake_filter_conf_ = new ::apollo::control::FilterConf(*from.brake_filter_conf_); + } else { + brake_filter_conf_ = NULL; + } + if (from.has_acceleration_filter_conf()) { + acceleration_filter_conf_ = new ::apollo::control::FilterConf(*from.acceleration_filter_conf_); + } else { + acceleration_filter_conf_ = NULL; + } + if (from.has_calibration_table()) { + calibration_table_ = new ::apollo::control::calibrationtable::ControlCalibrationTable(*from.calibration_table_); + } else { + calibration_table_ = NULL; + } + ::memcpy(&ts_, &from.ts_, + static_cast(reinterpret_cast(&switch_speed_) - + reinterpret_cast(&ts_)) + sizeof(switch_speed_)); + // @@protoc_insertion_point(copy_constructor:apollo.control.LonControllerConf) +} + +void LonControllerConf::SharedCtor() { + ::memset(&station_pid_conf_, 0, static_cast( + reinterpret_cast(&switch_speed_) - + reinterpret_cast(&station_pid_conf_)) + sizeof(switch_speed_)); +} + +LonControllerConf::~LonControllerConf() { + // @@protoc_insertion_point(destructor:apollo.control.LonControllerConf) + SharedDtor(); +} + +void LonControllerConf::SharedDtor() { + if (this != internal_default_instance()) delete station_pid_conf_; + if (this != internal_default_instance()) delete low_speed_pid_conf_; + if (this != internal_default_instance()) delete high_speed_pid_conf_; + if (this != internal_default_instance()) delete throttle_filter_conf_; + if (this != internal_default_instance()) delete brake_filter_conf_; + if (this != internal_default_instance()) delete acceleration_filter_conf_; + if (this != internal_default_instance()) delete calibration_table_; +} + +void LonControllerConf::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* LonControllerConf::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const LonControllerConf& LonControllerConf::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::scc_info_LonControllerConf.base); + return *internal_default_instance(); +} + + +void LonControllerConf::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.LonControllerConf) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && station_pid_conf_ != NULL) { + delete station_pid_conf_; + } + station_pid_conf_ = NULL; + if (GetArenaNoVirtual() == NULL && low_speed_pid_conf_ != NULL) { + delete low_speed_pid_conf_; + } + low_speed_pid_conf_ = NULL; + if (GetArenaNoVirtual() == NULL && high_speed_pid_conf_ != NULL) { + delete high_speed_pid_conf_; + } + high_speed_pid_conf_ = NULL; + if (GetArenaNoVirtual() == NULL && throttle_filter_conf_ != NULL) { + delete throttle_filter_conf_; + } + throttle_filter_conf_ = NULL; + if (GetArenaNoVirtual() == NULL && brake_filter_conf_ != NULL) { + delete brake_filter_conf_; + } + brake_filter_conf_ = NULL; + if (GetArenaNoVirtual() == NULL && acceleration_filter_conf_ != NULL) { + delete acceleration_filter_conf_; + } + acceleration_filter_conf_ = NULL; + if (GetArenaNoVirtual() == NULL && calibration_table_ != NULL) { + delete calibration_table_; + } + calibration_table_ = NULL; + ::memset(&ts_, 0, static_cast( + reinterpret_cast(&switch_speed_) - + reinterpret_cast(&ts_)) + sizeof(switch_speed_)); + _internal_metadata_.Clear(); +} + +bool LonControllerConf::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.LonControllerConf) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double ts = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &ts_))); + } else { + goto handle_unusual; + } + break; + } + + // double brake_deadzone = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &brake_deadzone_))); + } else { + goto handle_unusual; + } + break; + } + + // double throttle_deadzone = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &throttle_deadzone_))); + } else { + goto handle_unusual; + } + break; + } + + // double speed_controller_input_limit = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &speed_controller_input_limit_))); + } else { + goto handle_unusual; + } + break; + } + + // double station_error_limit = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &station_error_limit_))); + } else { + goto handle_unusual; + } + break; + } + + // double preview_window = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &preview_window_))); + } else { + goto handle_unusual; + } + break; + } + + // double standstill_acceleration = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &standstill_acceleration_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.PidConf station_pid_conf = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(66u /* 66 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_station_pid_conf())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.PidConf low_speed_pid_conf = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(74u /* 74 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_low_speed_pid_conf())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.PidConf high_speed_pid_conf = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(82u /* 82 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_high_speed_pid_conf())); + } else { + goto handle_unusual; + } + break; + } + + // double switch_speed = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(89u /* 89 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &switch_speed_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.FilterConf throttle_filter_conf = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(98u /* 98 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_throttle_filter_conf())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.FilterConf brake_filter_conf = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(106u /* 106 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_brake_filter_conf())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.FilterConf acceleration_filter_conf = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(114u /* 114 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_acceleration_filter_conf())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.calibrationtable.ControlCalibrationTable calibration_table = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(122u /* 122 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_calibration_table())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.LonControllerConf) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.LonControllerConf) + return false; +#undef DO_ +} + +void LonControllerConf::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.LonControllerConf) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double ts = 1; + if (this->ts() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->ts(), output); + } + + // double brake_deadzone = 2; + if (this->brake_deadzone() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->brake_deadzone(), output); + } + + // double throttle_deadzone = 3; + if (this->throttle_deadzone() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->throttle_deadzone(), output); + } + + // double speed_controller_input_limit = 4; + if (this->speed_controller_input_limit() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->speed_controller_input_limit(), output); + } + + // double station_error_limit = 5; + if (this->station_error_limit() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->station_error_limit(), output); + } + + // double preview_window = 6; + if (this->preview_window() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->preview_window(), output); + } + + // double standstill_acceleration = 7; + if (this->standstill_acceleration() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->standstill_acceleration(), output); + } + + // .apollo.control.PidConf station_pid_conf = 8; + if (this->has_station_pid_conf()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 8, this->_internal_station_pid_conf(), output); + } + + // .apollo.control.PidConf low_speed_pid_conf = 9; + if (this->has_low_speed_pid_conf()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 9, this->_internal_low_speed_pid_conf(), output); + } + + // .apollo.control.PidConf high_speed_pid_conf = 10; + if (this->has_high_speed_pid_conf()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 10, this->_internal_high_speed_pid_conf(), output); + } + + // double switch_speed = 11; + if (this->switch_speed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(11, this->switch_speed(), output); + } + + // .apollo.control.FilterConf throttle_filter_conf = 12; + if (this->has_throttle_filter_conf()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 12, this->_internal_throttle_filter_conf(), output); + } + + // .apollo.control.FilterConf brake_filter_conf = 13; + if (this->has_brake_filter_conf()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 13, this->_internal_brake_filter_conf(), output); + } + + // .apollo.control.FilterConf acceleration_filter_conf = 14; + if (this->has_acceleration_filter_conf()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 14, this->_internal_acceleration_filter_conf(), output); + } + + // .apollo.control.calibrationtable.ControlCalibrationTable calibration_table = 15; + if (this->has_calibration_table()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 15, this->_internal_calibration_table(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.LonControllerConf) +} + +::google::protobuf::uint8* LonControllerConf::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.LonControllerConf) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double ts = 1; + if (this->ts() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->ts(), target); + } + + // double brake_deadzone = 2; + if (this->brake_deadzone() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->brake_deadzone(), target); + } + + // double throttle_deadzone = 3; + if (this->throttle_deadzone() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->throttle_deadzone(), target); + } + + // double speed_controller_input_limit = 4; + if (this->speed_controller_input_limit() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->speed_controller_input_limit(), target); + } + + // double station_error_limit = 5; + if (this->station_error_limit() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->station_error_limit(), target); + } + + // double preview_window = 6; + if (this->preview_window() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->preview_window(), target); + } + + // double standstill_acceleration = 7; + if (this->standstill_acceleration() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->standstill_acceleration(), target); + } + + // .apollo.control.PidConf station_pid_conf = 8; + if (this->has_station_pid_conf()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 8, this->_internal_station_pid_conf(), deterministic, target); + } + + // .apollo.control.PidConf low_speed_pid_conf = 9; + if (this->has_low_speed_pid_conf()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 9, this->_internal_low_speed_pid_conf(), deterministic, target); + } + + // .apollo.control.PidConf high_speed_pid_conf = 10; + if (this->has_high_speed_pid_conf()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 10, this->_internal_high_speed_pid_conf(), deterministic, target); + } + + // double switch_speed = 11; + if (this->switch_speed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(11, this->switch_speed(), target); + } + + // .apollo.control.FilterConf throttle_filter_conf = 12; + if (this->has_throttle_filter_conf()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 12, this->_internal_throttle_filter_conf(), deterministic, target); + } + + // .apollo.control.FilterConf brake_filter_conf = 13; + if (this->has_brake_filter_conf()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 13, this->_internal_brake_filter_conf(), deterministic, target); + } + + // .apollo.control.FilterConf acceleration_filter_conf = 14; + if (this->has_acceleration_filter_conf()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 14, this->_internal_acceleration_filter_conf(), deterministic, target); + } + + // .apollo.control.calibrationtable.ControlCalibrationTable calibration_table = 15; + if (this->has_calibration_table()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 15, this->_internal_calibration_table(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.LonControllerConf) + return target; +} + +size_t LonControllerConf::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.LonControllerConf) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.control.PidConf station_pid_conf = 8; + if (this->has_station_pid_conf()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *station_pid_conf_); + } + + // .apollo.control.PidConf low_speed_pid_conf = 9; + if (this->has_low_speed_pid_conf()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *low_speed_pid_conf_); + } + + // .apollo.control.PidConf high_speed_pid_conf = 10; + if (this->has_high_speed_pid_conf()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *high_speed_pid_conf_); + } + + // .apollo.control.FilterConf throttle_filter_conf = 12; + if (this->has_throttle_filter_conf()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *throttle_filter_conf_); + } + + // .apollo.control.FilterConf brake_filter_conf = 13; + if (this->has_brake_filter_conf()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *brake_filter_conf_); + } + + // .apollo.control.FilterConf acceleration_filter_conf = 14; + if (this->has_acceleration_filter_conf()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *acceleration_filter_conf_); + } + + // .apollo.control.calibrationtable.ControlCalibrationTable calibration_table = 15; + if (this->has_calibration_table()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *calibration_table_); + } + + // double ts = 1; + if (this->ts() != 0) { + total_size += 1 + 8; + } + + // double brake_deadzone = 2; + if (this->brake_deadzone() != 0) { + total_size += 1 + 8; + } + + // double throttle_deadzone = 3; + if (this->throttle_deadzone() != 0) { + total_size += 1 + 8; + } + + // double speed_controller_input_limit = 4; + if (this->speed_controller_input_limit() != 0) { + total_size += 1 + 8; + } + + // double station_error_limit = 5; + if (this->station_error_limit() != 0) { + total_size += 1 + 8; + } + + // double preview_window = 6; + if (this->preview_window() != 0) { + total_size += 1 + 8; + } + + // double standstill_acceleration = 7; + if (this->standstill_acceleration() != 0) { + total_size += 1 + 8; + } + + // double switch_speed = 11; + if (this->switch_speed() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void LonControllerConf::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.LonControllerConf) + GOOGLE_DCHECK_NE(&from, this); + const LonControllerConf* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.LonControllerConf) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.LonControllerConf) + MergeFrom(*source); + } +} + +void LonControllerConf::MergeFrom(const LonControllerConf& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.LonControllerConf) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_station_pid_conf()) { + mutable_station_pid_conf()->::apollo::control::PidConf::MergeFrom(from.station_pid_conf()); + } + if (from.has_low_speed_pid_conf()) { + mutable_low_speed_pid_conf()->::apollo::control::PidConf::MergeFrom(from.low_speed_pid_conf()); + } + if (from.has_high_speed_pid_conf()) { + mutable_high_speed_pid_conf()->::apollo::control::PidConf::MergeFrom(from.high_speed_pid_conf()); + } + if (from.has_throttle_filter_conf()) { + mutable_throttle_filter_conf()->::apollo::control::FilterConf::MergeFrom(from.throttle_filter_conf()); + } + if (from.has_brake_filter_conf()) { + mutable_brake_filter_conf()->::apollo::control::FilterConf::MergeFrom(from.brake_filter_conf()); + } + if (from.has_acceleration_filter_conf()) { + mutable_acceleration_filter_conf()->::apollo::control::FilterConf::MergeFrom(from.acceleration_filter_conf()); + } + if (from.has_calibration_table()) { + mutable_calibration_table()->::apollo::control::calibrationtable::ControlCalibrationTable::MergeFrom(from.calibration_table()); + } + if (from.ts() != 0) { + set_ts(from.ts()); + } + if (from.brake_deadzone() != 0) { + set_brake_deadzone(from.brake_deadzone()); + } + if (from.throttle_deadzone() != 0) { + set_throttle_deadzone(from.throttle_deadzone()); + } + if (from.speed_controller_input_limit() != 0) { + set_speed_controller_input_limit(from.speed_controller_input_limit()); + } + if (from.station_error_limit() != 0) { + set_station_error_limit(from.station_error_limit()); + } + if (from.preview_window() != 0) { + set_preview_window(from.preview_window()); + } + if (from.standstill_acceleration() != 0) { + set_standstill_acceleration(from.standstill_acceleration()); + } + if (from.switch_speed() != 0) { + set_switch_speed(from.switch_speed()); + } +} + +void LonControllerConf::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.LonControllerConf) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void LonControllerConf::CopyFrom(const LonControllerConf& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.LonControllerConf) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool LonControllerConf::IsInitialized() const { + return true; +} + +void LonControllerConf::Swap(LonControllerConf* other) { + if (other == this) return; + InternalSwap(other); +} +void LonControllerConf::InternalSwap(LonControllerConf* other) { + using std::swap; + swap(station_pid_conf_, other->station_pid_conf_); + swap(low_speed_pid_conf_, other->low_speed_pid_conf_); + swap(high_speed_pid_conf_, other->high_speed_pid_conf_); + swap(throttle_filter_conf_, other->throttle_filter_conf_); + swap(brake_filter_conf_, other->brake_filter_conf_); + swap(acceleration_filter_conf_, other->acceleration_filter_conf_); + swap(calibration_table_, other->calibration_table_); + swap(ts_, other->ts_); + swap(brake_deadzone_, other->brake_deadzone_); + swap(throttle_deadzone_, other->throttle_deadzone_); + swap(speed_controller_input_limit_, other->speed_controller_input_limit_); + swap(station_error_limit_, other->station_error_limit_); + swap(preview_window_, other->preview_window_); + swap(standstill_acceleration_, other->standstill_acceleration_); + swap(switch_speed_, other->switch_speed_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata LonControllerConf::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace control +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::PidConf* Arena::CreateMaybeMessage< ::apollo::control::PidConf >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::PidConf >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::FilterConf* Arena::CreateMaybeMessage< ::apollo::control::FilterConf >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::FilterConf >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::LonControllerConf* Arena::CreateMaybeMessage< ::apollo::control::LonControllerConf >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::LonControllerConf >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/control/lon_controller_conf.pb.h b/apollo_msgs/include/apollo_msgs/proto/control/lon_controller_conf.pb.h new file mode 100644 index 0000000..b24aef1 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/control/lon_controller_conf.pb.h @@ -0,0 +1,1151 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/control/lon_controller_conf.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include "apollo_msgs/proto/control/calibration_table.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[3]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto +namespace apollo { +namespace control { +class FilterConf; +class FilterConfDefaultTypeInternal; +extern FilterConfDefaultTypeInternal _FilterConf_default_instance_; +class LonControllerConf; +class LonControllerConfDefaultTypeInternal; +extern LonControllerConfDefaultTypeInternal _LonControllerConf_default_instance_; +class PidConf; +class PidConfDefaultTypeInternal; +extern PidConfDefaultTypeInternal _PidConf_default_instance_; +} // namespace control +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::control::FilterConf* Arena::CreateMaybeMessage<::apollo::control::FilterConf>(Arena*); +template<> ::apollo::control::LonControllerConf* Arena::CreateMaybeMessage<::apollo::control::LonControllerConf>(Arena*); +template<> ::apollo::control::PidConf* Arena::CreateMaybeMessage<::apollo::control::PidConf>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace control { + +// =================================================================== + +class PidConf : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.PidConf) */ { + public: + PidConf(); + virtual ~PidConf(); + + PidConf(const PidConf& from); + + inline PidConf& operator=(const PidConf& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + PidConf(PidConf&& from) noexcept + : PidConf() { + *this = ::std::move(from); + } + + inline PidConf& operator=(PidConf&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const PidConf& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const PidConf* internal_default_instance() { + return reinterpret_cast( + &_PidConf_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(PidConf* other); + friend void swap(PidConf& a, PidConf& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline PidConf* New() const final { + return CreateMaybeMessage(NULL); + } + + PidConf* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const PidConf& from); + void MergeFrom(const PidConf& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(PidConf* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double integrator_saturation_level = 2; + void clear_integrator_saturation_level(); + static const int kIntegratorSaturationLevelFieldNumber = 2; + double integrator_saturation_level() const; + void set_integrator_saturation_level(double value); + + // double kp = 3; + void clear_kp(); + static const int kKpFieldNumber = 3; + double kp() const; + void set_kp(double value); + + // double ki = 4; + void clear_ki(); + static const int kKiFieldNumber = 4; + double ki() const; + void set_ki(double value); + + // double kd = 5; + void clear_kd(); + static const int kKdFieldNumber = 5; + double kd() const; + void set_kd(double value); + + // bool integrator_enable = 1; + void clear_integrator_enable(); + static const int kIntegratorEnableFieldNumber = 1; + bool integrator_enable() const; + void set_integrator_enable(bool value); + + // @@protoc_insertion_point(class_scope:apollo.control.PidConf) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double integrator_saturation_level_; + double kp_; + double ki_; + double kd_; + bool integrator_enable_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class FilterConf : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.FilterConf) */ { + public: + FilterConf(); + virtual ~FilterConf(); + + FilterConf(const FilterConf& from); + + inline FilterConf& operator=(const FilterConf& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + FilterConf(FilterConf&& from) noexcept + : FilterConf() { + *this = ::std::move(from); + } + + inline FilterConf& operator=(FilterConf&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const FilterConf& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const FilterConf* internal_default_instance() { + return reinterpret_cast( + &_FilterConf_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(FilterConf* other); + friend void swap(FilterConf& a, FilterConf& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline FilterConf* New() const final { + return CreateMaybeMessage(NULL); + } + + FilterConf* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const FilterConf& from); + void MergeFrom(const FilterConf& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(FilterConf* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // int32 cutoff_freq = 1; + void clear_cutoff_freq(); + static const int kCutoffFreqFieldNumber = 1; + ::google::protobuf::int32 cutoff_freq() const; + void set_cutoff_freq(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:apollo.control.FilterConf) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 cutoff_freq_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class LonControllerConf : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.LonControllerConf) */ { + public: + LonControllerConf(); + virtual ~LonControllerConf(); + + LonControllerConf(const LonControllerConf& from); + + inline LonControllerConf& operator=(const LonControllerConf& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + LonControllerConf(LonControllerConf&& from) noexcept + : LonControllerConf() { + *this = ::std::move(from); + } + + inline LonControllerConf& operator=(LonControllerConf&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const LonControllerConf& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const LonControllerConf* internal_default_instance() { + return reinterpret_cast( + &_LonControllerConf_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + void Swap(LonControllerConf* other); + friend void swap(LonControllerConf& a, LonControllerConf& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline LonControllerConf* New() const final { + return CreateMaybeMessage(NULL); + } + + LonControllerConf* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const LonControllerConf& from); + void MergeFrom(const LonControllerConf& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(LonControllerConf* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.control.PidConf station_pid_conf = 8; + bool has_station_pid_conf() const; + void clear_station_pid_conf(); + static const int kStationPidConfFieldNumber = 8; + private: + const ::apollo::control::PidConf& _internal_station_pid_conf() const; + public: + const ::apollo::control::PidConf& station_pid_conf() const; + ::apollo::control::PidConf* release_station_pid_conf(); + ::apollo::control::PidConf* mutable_station_pid_conf(); + void set_allocated_station_pid_conf(::apollo::control::PidConf* station_pid_conf); + + // .apollo.control.PidConf low_speed_pid_conf = 9; + bool has_low_speed_pid_conf() const; + void clear_low_speed_pid_conf(); + static const int kLowSpeedPidConfFieldNumber = 9; + private: + const ::apollo::control::PidConf& _internal_low_speed_pid_conf() const; + public: + const ::apollo::control::PidConf& low_speed_pid_conf() const; + ::apollo::control::PidConf* release_low_speed_pid_conf(); + ::apollo::control::PidConf* mutable_low_speed_pid_conf(); + void set_allocated_low_speed_pid_conf(::apollo::control::PidConf* low_speed_pid_conf); + + // .apollo.control.PidConf high_speed_pid_conf = 10; + bool has_high_speed_pid_conf() const; + void clear_high_speed_pid_conf(); + static const int kHighSpeedPidConfFieldNumber = 10; + private: + const ::apollo::control::PidConf& _internal_high_speed_pid_conf() const; + public: + const ::apollo::control::PidConf& high_speed_pid_conf() const; + ::apollo::control::PidConf* release_high_speed_pid_conf(); + ::apollo::control::PidConf* mutable_high_speed_pid_conf(); + void set_allocated_high_speed_pid_conf(::apollo::control::PidConf* high_speed_pid_conf); + + // .apollo.control.FilterConf throttle_filter_conf = 12; + bool has_throttle_filter_conf() const; + void clear_throttle_filter_conf(); + static const int kThrottleFilterConfFieldNumber = 12; + private: + const ::apollo::control::FilterConf& _internal_throttle_filter_conf() const; + public: + const ::apollo::control::FilterConf& throttle_filter_conf() const; + ::apollo::control::FilterConf* release_throttle_filter_conf(); + ::apollo::control::FilterConf* mutable_throttle_filter_conf(); + void set_allocated_throttle_filter_conf(::apollo::control::FilterConf* throttle_filter_conf); + + // .apollo.control.FilterConf brake_filter_conf = 13; + bool has_brake_filter_conf() const; + void clear_brake_filter_conf(); + static const int kBrakeFilterConfFieldNumber = 13; + private: + const ::apollo::control::FilterConf& _internal_brake_filter_conf() const; + public: + const ::apollo::control::FilterConf& brake_filter_conf() const; + ::apollo::control::FilterConf* release_brake_filter_conf(); + ::apollo::control::FilterConf* mutable_brake_filter_conf(); + void set_allocated_brake_filter_conf(::apollo::control::FilterConf* brake_filter_conf); + + // .apollo.control.FilterConf acceleration_filter_conf = 14; + bool has_acceleration_filter_conf() const; + void clear_acceleration_filter_conf(); + static const int kAccelerationFilterConfFieldNumber = 14; + private: + const ::apollo::control::FilterConf& _internal_acceleration_filter_conf() const; + public: + const ::apollo::control::FilterConf& acceleration_filter_conf() const; + ::apollo::control::FilterConf* release_acceleration_filter_conf(); + ::apollo::control::FilterConf* mutable_acceleration_filter_conf(); + void set_allocated_acceleration_filter_conf(::apollo::control::FilterConf* acceleration_filter_conf); + + // .apollo.control.calibrationtable.ControlCalibrationTable calibration_table = 15; + bool has_calibration_table() const; + void clear_calibration_table(); + static const int kCalibrationTableFieldNumber = 15; + private: + const ::apollo::control::calibrationtable::ControlCalibrationTable& _internal_calibration_table() const; + public: + const ::apollo::control::calibrationtable::ControlCalibrationTable& calibration_table() const; + ::apollo::control::calibrationtable::ControlCalibrationTable* release_calibration_table(); + ::apollo::control::calibrationtable::ControlCalibrationTable* mutable_calibration_table(); + void set_allocated_calibration_table(::apollo::control::calibrationtable::ControlCalibrationTable* calibration_table); + + // double ts = 1; + void clear_ts(); + static const int kTsFieldNumber = 1; + double ts() const; + void set_ts(double value); + + // double brake_deadzone = 2; + void clear_brake_deadzone(); + static const int kBrakeDeadzoneFieldNumber = 2; + double brake_deadzone() const; + void set_brake_deadzone(double value); + + // double throttle_deadzone = 3; + void clear_throttle_deadzone(); + static const int kThrottleDeadzoneFieldNumber = 3; + double throttle_deadzone() const; + void set_throttle_deadzone(double value); + + // double speed_controller_input_limit = 4; + void clear_speed_controller_input_limit(); + static const int kSpeedControllerInputLimitFieldNumber = 4; + double speed_controller_input_limit() const; + void set_speed_controller_input_limit(double value); + + // double station_error_limit = 5; + void clear_station_error_limit(); + static const int kStationErrorLimitFieldNumber = 5; + double station_error_limit() const; + void set_station_error_limit(double value); + + // double preview_window = 6; + void clear_preview_window(); + static const int kPreviewWindowFieldNumber = 6; + double preview_window() const; + void set_preview_window(double value); + + // double standstill_acceleration = 7; + void clear_standstill_acceleration(); + static const int kStandstillAccelerationFieldNumber = 7; + double standstill_acceleration() const; + void set_standstill_acceleration(double value); + + // double switch_speed = 11; + void clear_switch_speed(); + static const int kSwitchSpeedFieldNumber = 11; + double switch_speed() const; + void set_switch_speed(double value); + + // @@protoc_insertion_point(class_scope:apollo.control.LonControllerConf) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::control::PidConf* station_pid_conf_; + ::apollo::control::PidConf* low_speed_pid_conf_; + ::apollo::control::PidConf* high_speed_pid_conf_; + ::apollo::control::FilterConf* throttle_filter_conf_; + ::apollo::control::FilterConf* brake_filter_conf_; + ::apollo::control::FilterConf* acceleration_filter_conf_; + ::apollo::control::calibrationtable::ControlCalibrationTable* calibration_table_; + double ts_; + double brake_deadzone_; + double throttle_deadzone_; + double speed_controller_input_limit_; + double station_error_limit_; + double preview_window_; + double standstill_acceleration_; + double switch_speed_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// PidConf + +// bool integrator_enable = 1; +inline void PidConf::clear_integrator_enable() { + integrator_enable_ = false; +} +inline bool PidConf::integrator_enable() const { + // @@protoc_insertion_point(field_get:apollo.control.PidConf.integrator_enable) + return integrator_enable_; +} +inline void PidConf::set_integrator_enable(bool value) { + + integrator_enable_ = value; + // @@protoc_insertion_point(field_set:apollo.control.PidConf.integrator_enable) +} + +// double integrator_saturation_level = 2; +inline void PidConf::clear_integrator_saturation_level() { + integrator_saturation_level_ = 0; +} +inline double PidConf::integrator_saturation_level() const { + // @@protoc_insertion_point(field_get:apollo.control.PidConf.integrator_saturation_level) + return integrator_saturation_level_; +} +inline void PidConf::set_integrator_saturation_level(double value) { + + integrator_saturation_level_ = value; + // @@protoc_insertion_point(field_set:apollo.control.PidConf.integrator_saturation_level) +} + +// double kp = 3; +inline void PidConf::clear_kp() { + kp_ = 0; +} +inline double PidConf::kp() const { + // @@protoc_insertion_point(field_get:apollo.control.PidConf.kp) + return kp_; +} +inline void PidConf::set_kp(double value) { + + kp_ = value; + // @@protoc_insertion_point(field_set:apollo.control.PidConf.kp) +} + +// double ki = 4; +inline void PidConf::clear_ki() { + ki_ = 0; +} +inline double PidConf::ki() const { + // @@protoc_insertion_point(field_get:apollo.control.PidConf.ki) + return ki_; +} +inline void PidConf::set_ki(double value) { + + ki_ = value; + // @@protoc_insertion_point(field_set:apollo.control.PidConf.ki) +} + +// double kd = 5; +inline void PidConf::clear_kd() { + kd_ = 0; +} +inline double PidConf::kd() const { + // @@protoc_insertion_point(field_get:apollo.control.PidConf.kd) + return kd_; +} +inline void PidConf::set_kd(double value) { + + kd_ = value; + // @@protoc_insertion_point(field_set:apollo.control.PidConf.kd) +} + +// ------------------------------------------------------------------- + +// FilterConf + +// int32 cutoff_freq = 1; +inline void FilterConf::clear_cutoff_freq() { + cutoff_freq_ = 0; +} +inline ::google::protobuf::int32 FilterConf::cutoff_freq() const { + // @@protoc_insertion_point(field_get:apollo.control.FilterConf.cutoff_freq) + return cutoff_freq_; +} +inline void FilterConf::set_cutoff_freq(::google::protobuf::int32 value) { + + cutoff_freq_ = value; + // @@protoc_insertion_point(field_set:apollo.control.FilterConf.cutoff_freq) +} + +// ------------------------------------------------------------------- + +// LonControllerConf + +// double ts = 1; +inline void LonControllerConf::clear_ts() { + ts_ = 0; +} +inline double LonControllerConf::ts() const { + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.ts) + return ts_; +} +inline void LonControllerConf::set_ts(double value) { + + ts_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LonControllerConf.ts) +} + +// double brake_deadzone = 2; +inline void LonControllerConf::clear_brake_deadzone() { + brake_deadzone_ = 0; +} +inline double LonControllerConf::brake_deadzone() const { + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.brake_deadzone) + return brake_deadzone_; +} +inline void LonControllerConf::set_brake_deadzone(double value) { + + brake_deadzone_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LonControllerConf.brake_deadzone) +} + +// double throttle_deadzone = 3; +inline void LonControllerConf::clear_throttle_deadzone() { + throttle_deadzone_ = 0; +} +inline double LonControllerConf::throttle_deadzone() const { + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.throttle_deadzone) + return throttle_deadzone_; +} +inline void LonControllerConf::set_throttle_deadzone(double value) { + + throttle_deadzone_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LonControllerConf.throttle_deadzone) +} + +// double speed_controller_input_limit = 4; +inline void LonControllerConf::clear_speed_controller_input_limit() { + speed_controller_input_limit_ = 0; +} +inline double LonControllerConf::speed_controller_input_limit() const { + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.speed_controller_input_limit) + return speed_controller_input_limit_; +} +inline void LonControllerConf::set_speed_controller_input_limit(double value) { + + speed_controller_input_limit_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LonControllerConf.speed_controller_input_limit) +} + +// double station_error_limit = 5; +inline void LonControllerConf::clear_station_error_limit() { + station_error_limit_ = 0; +} +inline double LonControllerConf::station_error_limit() const { + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.station_error_limit) + return station_error_limit_; +} +inline void LonControllerConf::set_station_error_limit(double value) { + + station_error_limit_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LonControllerConf.station_error_limit) +} + +// double preview_window = 6; +inline void LonControllerConf::clear_preview_window() { + preview_window_ = 0; +} +inline double LonControllerConf::preview_window() const { + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.preview_window) + return preview_window_; +} +inline void LonControllerConf::set_preview_window(double value) { + + preview_window_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LonControllerConf.preview_window) +} + +// double standstill_acceleration = 7; +inline void LonControllerConf::clear_standstill_acceleration() { + standstill_acceleration_ = 0; +} +inline double LonControllerConf::standstill_acceleration() const { + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.standstill_acceleration) + return standstill_acceleration_; +} +inline void LonControllerConf::set_standstill_acceleration(double value) { + + standstill_acceleration_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LonControllerConf.standstill_acceleration) +} + +// .apollo.control.PidConf station_pid_conf = 8; +inline bool LonControllerConf::has_station_pid_conf() const { + return this != internal_default_instance() && station_pid_conf_ != NULL; +} +inline void LonControllerConf::clear_station_pid_conf() { + if (GetArenaNoVirtual() == NULL && station_pid_conf_ != NULL) { + delete station_pid_conf_; + } + station_pid_conf_ = NULL; +} +inline const ::apollo::control::PidConf& LonControllerConf::_internal_station_pid_conf() const { + return *station_pid_conf_; +} +inline const ::apollo::control::PidConf& LonControllerConf::station_pid_conf() const { + const ::apollo::control::PidConf* p = station_pid_conf_; + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.station_pid_conf) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_PidConf_default_instance_); +} +inline ::apollo::control::PidConf* LonControllerConf::release_station_pid_conf() { + // @@protoc_insertion_point(field_release:apollo.control.LonControllerConf.station_pid_conf) + + ::apollo::control::PidConf* temp = station_pid_conf_; + station_pid_conf_ = NULL; + return temp; +} +inline ::apollo::control::PidConf* LonControllerConf::mutable_station_pid_conf() { + + if (station_pid_conf_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::PidConf>(GetArenaNoVirtual()); + station_pid_conf_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.LonControllerConf.station_pid_conf) + return station_pid_conf_; +} +inline void LonControllerConf::set_allocated_station_pid_conf(::apollo::control::PidConf* station_pid_conf) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete station_pid_conf_; + } + if (station_pid_conf) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + station_pid_conf = ::google::protobuf::internal::GetOwnedMessage( + message_arena, station_pid_conf, submessage_arena); + } + + } else { + + } + station_pid_conf_ = station_pid_conf; + // @@protoc_insertion_point(field_set_allocated:apollo.control.LonControllerConf.station_pid_conf) +} + +// .apollo.control.PidConf low_speed_pid_conf = 9; +inline bool LonControllerConf::has_low_speed_pid_conf() const { + return this != internal_default_instance() && low_speed_pid_conf_ != NULL; +} +inline void LonControllerConf::clear_low_speed_pid_conf() { + if (GetArenaNoVirtual() == NULL && low_speed_pid_conf_ != NULL) { + delete low_speed_pid_conf_; + } + low_speed_pid_conf_ = NULL; +} +inline const ::apollo::control::PidConf& LonControllerConf::_internal_low_speed_pid_conf() const { + return *low_speed_pid_conf_; +} +inline const ::apollo::control::PidConf& LonControllerConf::low_speed_pid_conf() const { + const ::apollo::control::PidConf* p = low_speed_pid_conf_; + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.low_speed_pid_conf) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_PidConf_default_instance_); +} +inline ::apollo::control::PidConf* LonControllerConf::release_low_speed_pid_conf() { + // @@protoc_insertion_point(field_release:apollo.control.LonControllerConf.low_speed_pid_conf) + + ::apollo::control::PidConf* temp = low_speed_pid_conf_; + low_speed_pid_conf_ = NULL; + return temp; +} +inline ::apollo::control::PidConf* LonControllerConf::mutable_low_speed_pid_conf() { + + if (low_speed_pid_conf_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::PidConf>(GetArenaNoVirtual()); + low_speed_pid_conf_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.LonControllerConf.low_speed_pid_conf) + return low_speed_pid_conf_; +} +inline void LonControllerConf::set_allocated_low_speed_pid_conf(::apollo::control::PidConf* low_speed_pid_conf) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete low_speed_pid_conf_; + } + if (low_speed_pid_conf) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + low_speed_pid_conf = ::google::protobuf::internal::GetOwnedMessage( + message_arena, low_speed_pid_conf, submessage_arena); + } + + } else { + + } + low_speed_pid_conf_ = low_speed_pid_conf; + // @@protoc_insertion_point(field_set_allocated:apollo.control.LonControllerConf.low_speed_pid_conf) +} + +// .apollo.control.PidConf high_speed_pid_conf = 10; +inline bool LonControllerConf::has_high_speed_pid_conf() const { + return this != internal_default_instance() && high_speed_pid_conf_ != NULL; +} +inline void LonControllerConf::clear_high_speed_pid_conf() { + if (GetArenaNoVirtual() == NULL && high_speed_pid_conf_ != NULL) { + delete high_speed_pid_conf_; + } + high_speed_pid_conf_ = NULL; +} +inline const ::apollo::control::PidConf& LonControllerConf::_internal_high_speed_pid_conf() const { + return *high_speed_pid_conf_; +} +inline const ::apollo::control::PidConf& LonControllerConf::high_speed_pid_conf() const { + const ::apollo::control::PidConf* p = high_speed_pid_conf_; + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.high_speed_pid_conf) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_PidConf_default_instance_); +} +inline ::apollo::control::PidConf* LonControllerConf::release_high_speed_pid_conf() { + // @@protoc_insertion_point(field_release:apollo.control.LonControllerConf.high_speed_pid_conf) + + ::apollo::control::PidConf* temp = high_speed_pid_conf_; + high_speed_pid_conf_ = NULL; + return temp; +} +inline ::apollo::control::PidConf* LonControllerConf::mutable_high_speed_pid_conf() { + + if (high_speed_pid_conf_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::PidConf>(GetArenaNoVirtual()); + high_speed_pid_conf_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.LonControllerConf.high_speed_pid_conf) + return high_speed_pid_conf_; +} +inline void LonControllerConf::set_allocated_high_speed_pid_conf(::apollo::control::PidConf* high_speed_pid_conf) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete high_speed_pid_conf_; + } + if (high_speed_pid_conf) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + high_speed_pid_conf = ::google::protobuf::internal::GetOwnedMessage( + message_arena, high_speed_pid_conf, submessage_arena); + } + + } else { + + } + high_speed_pid_conf_ = high_speed_pid_conf; + // @@protoc_insertion_point(field_set_allocated:apollo.control.LonControllerConf.high_speed_pid_conf) +} + +// double switch_speed = 11; +inline void LonControllerConf::clear_switch_speed() { + switch_speed_ = 0; +} +inline double LonControllerConf::switch_speed() const { + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.switch_speed) + return switch_speed_; +} +inline void LonControllerConf::set_switch_speed(double value) { + + switch_speed_ = value; + // @@protoc_insertion_point(field_set:apollo.control.LonControllerConf.switch_speed) +} + +// .apollo.control.FilterConf throttle_filter_conf = 12; +inline bool LonControllerConf::has_throttle_filter_conf() const { + return this != internal_default_instance() && throttle_filter_conf_ != NULL; +} +inline void LonControllerConf::clear_throttle_filter_conf() { + if (GetArenaNoVirtual() == NULL && throttle_filter_conf_ != NULL) { + delete throttle_filter_conf_; + } + throttle_filter_conf_ = NULL; +} +inline const ::apollo::control::FilterConf& LonControllerConf::_internal_throttle_filter_conf() const { + return *throttle_filter_conf_; +} +inline const ::apollo::control::FilterConf& LonControllerConf::throttle_filter_conf() const { + const ::apollo::control::FilterConf* p = throttle_filter_conf_; + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.throttle_filter_conf) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_FilterConf_default_instance_); +} +inline ::apollo::control::FilterConf* LonControllerConf::release_throttle_filter_conf() { + // @@protoc_insertion_point(field_release:apollo.control.LonControllerConf.throttle_filter_conf) + + ::apollo::control::FilterConf* temp = throttle_filter_conf_; + throttle_filter_conf_ = NULL; + return temp; +} +inline ::apollo::control::FilterConf* LonControllerConf::mutable_throttle_filter_conf() { + + if (throttle_filter_conf_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::FilterConf>(GetArenaNoVirtual()); + throttle_filter_conf_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.LonControllerConf.throttle_filter_conf) + return throttle_filter_conf_; +} +inline void LonControllerConf::set_allocated_throttle_filter_conf(::apollo::control::FilterConf* throttle_filter_conf) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete throttle_filter_conf_; + } + if (throttle_filter_conf) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + throttle_filter_conf = ::google::protobuf::internal::GetOwnedMessage( + message_arena, throttle_filter_conf, submessage_arena); + } + + } else { + + } + throttle_filter_conf_ = throttle_filter_conf; + // @@protoc_insertion_point(field_set_allocated:apollo.control.LonControllerConf.throttle_filter_conf) +} + +// .apollo.control.FilterConf brake_filter_conf = 13; +inline bool LonControllerConf::has_brake_filter_conf() const { + return this != internal_default_instance() && brake_filter_conf_ != NULL; +} +inline void LonControllerConf::clear_brake_filter_conf() { + if (GetArenaNoVirtual() == NULL && brake_filter_conf_ != NULL) { + delete brake_filter_conf_; + } + brake_filter_conf_ = NULL; +} +inline const ::apollo::control::FilterConf& LonControllerConf::_internal_brake_filter_conf() const { + return *brake_filter_conf_; +} +inline const ::apollo::control::FilterConf& LonControllerConf::brake_filter_conf() const { + const ::apollo::control::FilterConf* p = brake_filter_conf_; + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.brake_filter_conf) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_FilterConf_default_instance_); +} +inline ::apollo::control::FilterConf* LonControllerConf::release_brake_filter_conf() { + // @@protoc_insertion_point(field_release:apollo.control.LonControllerConf.brake_filter_conf) + + ::apollo::control::FilterConf* temp = brake_filter_conf_; + brake_filter_conf_ = NULL; + return temp; +} +inline ::apollo::control::FilterConf* LonControllerConf::mutable_brake_filter_conf() { + + if (brake_filter_conf_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::FilterConf>(GetArenaNoVirtual()); + brake_filter_conf_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.LonControllerConf.brake_filter_conf) + return brake_filter_conf_; +} +inline void LonControllerConf::set_allocated_brake_filter_conf(::apollo::control::FilterConf* brake_filter_conf) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete brake_filter_conf_; + } + if (brake_filter_conf) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + brake_filter_conf = ::google::protobuf::internal::GetOwnedMessage( + message_arena, brake_filter_conf, submessage_arena); + } + + } else { + + } + brake_filter_conf_ = brake_filter_conf; + // @@protoc_insertion_point(field_set_allocated:apollo.control.LonControllerConf.brake_filter_conf) +} + +// .apollo.control.FilterConf acceleration_filter_conf = 14; +inline bool LonControllerConf::has_acceleration_filter_conf() const { + return this != internal_default_instance() && acceleration_filter_conf_ != NULL; +} +inline void LonControllerConf::clear_acceleration_filter_conf() { + if (GetArenaNoVirtual() == NULL && acceleration_filter_conf_ != NULL) { + delete acceleration_filter_conf_; + } + acceleration_filter_conf_ = NULL; +} +inline const ::apollo::control::FilterConf& LonControllerConf::_internal_acceleration_filter_conf() const { + return *acceleration_filter_conf_; +} +inline const ::apollo::control::FilterConf& LonControllerConf::acceleration_filter_conf() const { + const ::apollo::control::FilterConf* p = acceleration_filter_conf_; + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.acceleration_filter_conf) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::_FilterConf_default_instance_); +} +inline ::apollo::control::FilterConf* LonControllerConf::release_acceleration_filter_conf() { + // @@protoc_insertion_point(field_release:apollo.control.LonControllerConf.acceleration_filter_conf) + + ::apollo::control::FilterConf* temp = acceleration_filter_conf_; + acceleration_filter_conf_ = NULL; + return temp; +} +inline ::apollo::control::FilterConf* LonControllerConf::mutable_acceleration_filter_conf() { + + if (acceleration_filter_conf_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::FilterConf>(GetArenaNoVirtual()); + acceleration_filter_conf_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.LonControllerConf.acceleration_filter_conf) + return acceleration_filter_conf_; +} +inline void LonControllerConf::set_allocated_acceleration_filter_conf(::apollo::control::FilterConf* acceleration_filter_conf) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete acceleration_filter_conf_; + } + if (acceleration_filter_conf) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + acceleration_filter_conf = ::google::protobuf::internal::GetOwnedMessage( + message_arena, acceleration_filter_conf, submessage_arena); + } + + } else { + + } + acceleration_filter_conf_ = acceleration_filter_conf; + // @@protoc_insertion_point(field_set_allocated:apollo.control.LonControllerConf.acceleration_filter_conf) +} + +// .apollo.control.calibrationtable.ControlCalibrationTable calibration_table = 15; +inline bool LonControllerConf::has_calibration_table() const { + return this != internal_default_instance() && calibration_table_ != NULL; +} +inline const ::apollo::control::calibrationtable::ControlCalibrationTable& LonControllerConf::_internal_calibration_table() const { + return *calibration_table_; +} +inline const ::apollo::control::calibrationtable::ControlCalibrationTable& LonControllerConf::calibration_table() const { + const ::apollo::control::calibrationtable::ControlCalibrationTable* p = calibration_table_; + // @@protoc_insertion_point(field_get:apollo.control.LonControllerConf.calibration_table) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::control::calibrationtable::_ControlCalibrationTable_default_instance_); +} +inline ::apollo::control::calibrationtable::ControlCalibrationTable* LonControllerConf::release_calibration_table() { + // @@protoc_insertion_point(field_release:apollo.control.LonControllerConf.calibration_table) + + ::apollo::control::calibrationtable::ControlCalibrationTable* temp = calibration_table_; + calibration_table_ = NULL; + return temp; +} +inline ::apollo::control::calibrationtable::ControlCalibrationTable* LonControllerConf::mutable_calibration_table() { + + if (calibration_table_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::control::calibrationtable::ControlCalibrationTable>(GetArenaNoVirtual()); + calibration_table_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.LonControllerConf.calibration_table) + return calibration_table_; +} +inline void LonControllerConf::set_allocated_calibration_table(::apollo::control::calibrationtable::ControlCalibrationTable* calibration_table) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(calibration_table_); + } + if (calibration_table) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + calibration_table = ::google::protobuf::internal::GetOwnedMessage( + message_arena, calibration_table, submessage_arena); + } + + } else { + + } + calibration_table_ = calibration_table; + // @@protoc_insertion_point(field_set_allocated:apollo.control.LonControllerConf.calibration_table) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace control +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2flon_5fcontroller_5fconf_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/control/pad_msg.pb.cc b/apollo_msgs/include/apollo_msgs/proto/control/pad_msg.pb.cc new file mode 100644 index 0000000..f0f360c --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/control/pad_msg.pb.cc @@ -0,0 +1,478 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/control/pad_msg.proto + +#include "apollo_msgs/proto/control/pad_msg.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace apollo { +namespace control { +class PadMessageDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _PadMessage_default_instance_; +} // namespace control +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto { +static void InitDefaultsPadMessage() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::control::_PadMessage_default_instance_; + new (ptr) ::apollo::control::PadMessage(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::control::PadMessage::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_PadMessage = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsPadMessage}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_PadMessage.base); +} + +::google::protobuf::Metadata file_level_metadata[1]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::PadMessage, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::PadMessage, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::PadMessage, driving_mode_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::control::PadMessage, action_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::control::PadMessage)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::control::_PadMessage_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/control/pad_msg.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 1); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n\'apollo_msgs/proto/control/pad_msg.prot" + "o\022\016apollo.control\032%apollo_msgs/proto/com" + "mon/header.proto\032&apollo_msgs/proto/canb" + "us/chassis.proto\"\234\001\n\nPadMessage\022%\n\006heade" + "r\030\001 \001(\0132\025.apollo.common.Header\0228\n\014drivin" + "g_mode\030\002 \001(\0162\".apollo.canbus.Chassis.Dri" + "vingMode\022-\n\006action\030\003 \001(\0162\035.apollo.contro" + "l.DrivingAction*/\n\rDrivingAction\022\010\n\004STOP" + "\020\000\022\t\n\005START\020\001\022\t\n\005RESET\020\002b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 352); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/control/pad_msg.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto +namespace apollo { +namespace control { +const ::google::protobuf::EnumDescriptor* DrivingAction_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto::file_level_enum_descriptors[0]; +} +bool DrivingAction_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + return true; + default: + return false; + } +} + + +// =================================================================== + +void PadMessage::InitAsDefaultInstance() { + ::apollo::control::_PadMessage_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); +} +void PadMessage::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PadMessage::kHeaderFieldNumber; +const int PadMessage::kDrivingModeFieldNumber; +const int PadMessage::kActionFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PadMessage::PadMessage() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto::scc_info_PadMessage.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.control.PadMessage) +} +PadMessage::PadMessage(const PadMessage& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + ::memcpy(&driving_mode_, &from.driving_mode_, + static_cast(reinterpret_cast(&action_) - + reinterpret_cast(&driving_mode_)) + sizeof(action_)); + // @@protoc_insertion_point(copy_constructor:apollo.control.PadMessage) +} + +void PadMessage::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&action_) - + reinterpret_cast(&header_)) + sizeof(action_)); +} + +PadMessage::~PadMessage() { + // @@protoc_insertion_point(destructor:apollo.control.PadMessage) + SharedDtor(); +} + +void PadMessage::SharedDtor() { + if (this != internal_default_instance()) delete header_; +} + +void PadMessage::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* PadMessage::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const PadMessage& PadMessage::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto::scc_info_PadMessage.base); + return *internal_default_instance(); +} + + +void PadMessage::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.control.PadMessage) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + ::memset(&driving_mode_, 0, static_cast( + reinterpret_cast(&action_) - + reinterpret_cast(&driving_mode_)) + sizeof(action_)); + _internal_metadata_.Clear(); +} + +bool PadMessage::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.control.PadMessage) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_driving_mode(static_cast< ::apollo::canbus::Chassis_DrivingMode >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.control.DrivingAction action = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_action(static_cast< ::apollo::control::DrivingAction >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.control.PadMessage) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.control.PadMessage) + return false; +#undef DO_ +} + +void PadMessage::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.control.PadMessage) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 2; + if (this->driving_mode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 2, this->driving_mode(), output); + } + + // .apollo.control.DrivingAction action = 3; + if (this->action() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 3, this->action(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.control.PadMessage) +} + +::google::protobuf::uint8* PadMessage::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.control.PadMessage) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 2; + if (this->driving_mode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 2, this->driving_mode(), target); + } + + // .apollo.control.DrivingAction action = 3; + if (this->action() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 3, this->action(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.control.PadMessage) + return target; +} + +size_t PadMessage::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.control.PadMessage) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 2; + if (this->driving_mode() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->driving_mode()); + } + + // .apollo.control.DrivingAction action = 3; + if (this->action() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->action()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void PadMessage::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.control.PadMessage) + GOOGLE_DCHECK_NE(&from, this); + const PadMessage* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.control.PadMessage) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.control.PadMessage) + MergeFrom(*source); + } +} + +void PadMessage::MergeFrom(const PadMessage& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.control.PadMessage) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.driving_mode() != 0) { + set_driving_mode(from.driving_mode()); + } + if (from.action() != 0) { + set_action(from.action()); + } +} + +void PadMessage::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.control.PadMessage) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PadMessage::CopyFrom(const PadMessage& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.control.PadMessage) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PadMessage::IsInitialized() const { + return true; +} + +void PadMessage::Swap(PadMessage* other) { + if (other == this) return; + InternalSwap(other); +} +void PadMessage::InternalSwap(PadMessage* other) { + using std::swap; + swap(header_, other->header_); + swap(driving_mode_, other->driving_mode_); + swap(action_, other->action_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata PadMessage::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace control +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::control::PadMessage* Arena::CreateMaybeMessage< ::apollo::control::PadMessage >(Arena* arena) { + return Arena::CreateInternal< ::apollo::control::PadMessage >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/control/pad_msg.pb.h b/apollo_msgs/include/apollo_msgs/proto/control/pad_msg.pb.h new file mode 100644 index 0000000..b1497f5 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/control/pad_msg.pb.h @@ -0,0 +1,321 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/control/pad_msg.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "apollo_msgs/proto/common/header.pb.h" +#include "apollo_msgs/proto/canbus/chassis.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[1]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto +namespace apollo { +namespace control { +class PadMessage; +class PadMessageDefaultTypeInternal; +extern PadMessageDefaultTypeInternal _PadMessage_default_instance_; +} // namespace control +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::control::PadMessage* Arena::CreateMaybeMessage<::apollo::control::PadMessage>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace control { + +enum DrivingAction { + STOP = 0, + START = 1, + RESET = 2, + DrivingAction_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + DrivingAction_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool DrivingAction_IsValid(int value); +const DrivingAction DrivingAction_MIN = STOP; +const DrivingAction DrivingAction_MAX = RESET; +const int DrivingAction_ARRAYSIZE = DrivingAction_MAX + 1; + +const ::google::protobuf::EnumDescriptor* DrivingAction_descriptor(); +inline const ::std::string& DrivingAction_Name(DrivingAction value) { + return ::google::protobuf::internal::NameOfEnum( + DrivingAction_descriptor(), value); +} +inline bool DrivingAction_Parse( + const ::std::string& name, DrivingAction* value) { + return ::google::protobuf::internal::ParseNamedEnum( + DrivingAction_descriptor(), name, value); +} +// =================================================================== + +class PadMessage : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.control.PadMessage) */ { + public: + PadMessage(); + virtual ~PadMessage(); + + PadMessage(const PadMessage& from); + + inline PadMessage& operator=(const PadMessage& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + PadMessage(PadMessage&& from) noexcept + : PadMessage() { + *this = ::std::move(from); + } + + inline PadMessage& operator=(PadMessage&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const PadMessage& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const PadMessage* internal_default_instance() { + return reinterpret_cast( + &_PadMessage_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(PadMessage* other); + friend void swap(PadMessage& a, PadMessage& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline PadMessage* New() const final { + return CreateMaybeMessage(NULL); + } + + PadMessage* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const PadMessage& from); + void MergeFrom(const PadMessage& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(PadMessage* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.canbus.Chassis.DrivingMode driving_mode = 2; + void clear_driving_mode(); + static const int kDrivingModeFieldNumber = 2; + ::apollo::canbus::Chassis_DrivingMode driving_mode() const; + void set_driving_mode(::apollo::canbus::Chassis_DrivingMode value); + + // .apollo.control.DrivingAction action = 3; + void clear_action(); + static const int kActionFieldNumber = 3; + ::apollo::control::DrivingAction action() const; + void set_action(::apollo::control::DrivingAction value); + + // @@protoc_insertion_point(class_scope:apollo.control.PadMessage) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::Header* header_; + int driving_mode_; + int action_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// PadMessage + +// .apollo.common.Header header = 1; +inline bool PadMessage::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& PadMessage::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& PadMessage::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.control.PadMessage.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* PadMessage::release_header() { + // @@protoc_insertion_point(field_release:apollo.control.PadMessage.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* PadMessage::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.control.PadMessage.header) + return header_; +} +inline void PadMessage::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.control.PadMessage.header) +} + +// .apollo.canbus.Chassis.DrivingMode driving_mode = 2; +inline void PadMessage::clear_driving_mode() { + driving_mode_ = 0; +} +inline ::apollo::canbus::Chassis_DrivingMode PadMessage::driving_mode() const { + // @@protoc_insertion_point(field_get:apollo.control.PadMessage.driving_mode) + return static_cast< ::apollo::canbus::Chassis_DrivingMode >(driving_mode_); +} +inline void PadMessage::set_driving_mode(::apollo::canbus::Chassis_DrivingMode value) { + + driving_mode_ = value; + // @@protoc_insertion_point(field_set:apollo.control.PadMessage.driving_mode) +} + +// .apollo.control.DrivingAction action = 3; +inline void PadMessage::clear_action() { + action_ = 0; +} +inline ::apollo::control::DrivingAction PadMessage::action() const { + // @@protoc_insertion_point(field_get:apollo.control.PadMessage.action) + return static_cast< ::apollo::control::DrivingAction >(action_); +} +inline void PadMessage::set_action(::apollo::control::DrivingAction value) { + + action_ = value; + // @@protoc_insertion_point(field_set:apollo.control.PadMessage.action) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) + +} // namespace control +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::control::DrivingAction> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::control::DrivingAction>() { + return ::apollo::control::DrivingAction_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fcontrol_2fpad_5fmsg_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/decision/decision.pb.cc b/apollo_msgs/include/apollo_msgs/proto/decision/decision.pb.cc new file mode 100644 index 0000000..3cbd9fa --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/decision/decision.pb.cc @@ -0,0 +1,13319 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/decision/decision.proto + +#include "apollo_msgs/proto/decision/decision.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Signal; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Point3D; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_PointENU; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_EmergencyStopCruiseToStop; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_EmergencyStopHardBrake; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_LatencyStats; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_LightSignal; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_MainCruise; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_MainMissionComplete; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_MainNotReady; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_ModuleDebug; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_ObjectAvoid; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_ObjectIgnore; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Range; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_StopLine; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_TargetLane; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_MainParking; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_ObjectDecisions; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_ObjectNudge; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_ObjectSidePass; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Stats; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_MainChangeLane; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_MainEmergencyStop; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_MainStop; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_MasterVehicleDebug; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_ObjectDebug; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_ObjectDecision; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_ObjectFollow; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_ObjectOvertake; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_ObjectStop; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_ObjectYield; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<4> scc_info_Debug; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<8> scc_info_MainDecision; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<8> scc_info_ObjectDecisionType; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_PredictionObstacle; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto +namespace apollo { +namespace decision { +class RangeDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Range_default_instance_; +class TargetLaneDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _TargetLane_default_instance_; +class ObjectIgnoreDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ObjectIgnore_default_instance_; +class ObjectStopDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ObjectStop_default_instance_; +class ObjectNudgeDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ObjectNudge_default_instance_; +class ObjectYieldDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ObjectYield_default_instance_; +class ObjectFollowDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ObjectFollow_default_instance_; +class ObjectOvertakeDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ObjectOvertake_default_instance_; +class ObjectSidePassDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ObjectSidePass_default_instance_; +class ObjectAvoidDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ObjectAvoid_default_instance_; +class ObjectDecisionTypeDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; + const ::apollo::decision::ObjectIgnore* ignore_; + const ::apollo::decision::ObjectStop* stop_; + const ::apollo::decision::ObjectFollow* follow_; + const ::apollo::decision::ObjectYield* yield_; + const ::apollo::decision::ObjectOvertake* overtake_; + const ::apollo::decision::ObjectNudge* nudge_; + const ::apollo::decision::ObjectSidePass* sidepass_; + const ::apollo::decision::ObjectAvoid* avoid_; +} _ObjectDecisionType_default_instance_; +class ObjectDecisionDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ObjectDecision_default_instance_; +class ObjectDecisionsDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ObjectDecisions_default_instance_; +class StopLineDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _StopLine_default_instance_; +class MainStopDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _MainStop_default_instance_; +class EmergencyStopHardBrakeDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _EmergencyStopHardBrake_default_instance_; +class EmergencyStopCruiseToStopDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _EmergencyStopCruiseToStop_default_instance_; +class MainEmergencyStopDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; + const ::apollo::decision::EmergencyStopHardBrake* hard_brake_; + const ::apollo::decision::EmergencyStopCruiseToStop* cruise_to_stop_; +} _MainEmergencyStop_default_instance_; +class MainCruiseDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _MainCruise_default_instance_; +class MainChangeLaneDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _MainChangeLane_default_instance_; +class MainMissionCompleteDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _MainMissionComplete_default_instance_; +class MainNotReadyDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _MainNotReady_default_instance_; +class MainParkingDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _MainParking_default_instance_; +class MainDecisionDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; + const ::apollo::decision::MainCruise* cruise_; + const ::apollo::decision::MainStop* stop_; + const ::apollo::decision::MainEmergencyStop* estop_; + const ::apollo::decision::MainChangeLane* change_lane_; + const ::apollo::decision::MainMissionComplete* mission_complete_; + const ::apollo::decision::MainNotReady* not_ready_; + const ::apollo::decision::MainParking* parking_; +} _MainDecision_default_instance_; +class MasterVehicleDebugDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _MasterVehicleDebug_default_instance_; +class ObjectDebugDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ObjectDebug_default_instance_; +class LatencyStatsDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _LatencyStats_default_instance_; +class StatsDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Stats_default_instance_; +class ModuleDebugDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ModuleDebug_default_instance_; +class DebugDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Debug_default_instance_; +class LightSignalDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _LightSignal_default_instance_; +class DecisionResultDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _DecisionResult_default_instance_; +} // namespace decision +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto { +static void InitDefaultsRange() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_Range_default_instance_; + new (ptr) ::apollo::decision::Range(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::Range::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Range = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsRange}, {}}; + +static void InitDefaultsTargetLane() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_TargetLane_default_instance_; + new (ptr) ::apollo::decision::TargetLane(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::TargetLane::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_TargetLane = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsTargetLane}, {}}; + +static void InitDefaultsObjectIgnore() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_ObjectIgnore_default_instance_; + new (ptr) ::apollo::decision::ObjectIgnore(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::ObjectIgnore::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_ObjectIgnore = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsObjectIgnore}, {}}; + +static void InitDefaultsObjectStop() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_ObjectStop_default_instance_; + new (ptr) ::apollo::decision::ObjectStop(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::ObjectStop::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_ObjectStop = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsObjectStop}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Range.base, + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_PointENU.base,}}; + +static void InitDefaultsObjectNudge() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_ObjectNudge_default_instance_; + new (ptr) ::apollo::decision::ObjectNudge(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::ObjectNudge::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_ObjectNudge = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsObjectNudge}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Range.base,}}; + +static void InitDefaultsObjectYield() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_ObjectYield_default_instance_; + new (ptr) ::apollo::decision::ObjectYield(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::ObjectYield::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_ObjectYield = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsObjectYield}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Range.base, + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_PointENU.base,}}; + +static void InitDefaultsObjectFollow() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_ObjectFollow_default_instance_; + new (ptr) ::apollo::decision::ObjectFollow(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::ObjectFollow::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_ObjectFollow = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsObjectFollow}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Range.base, + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_PointENU.base,}}; + +static void InitDefaultsObjectOvertake() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_ObjectOvertake_default_instance_; + new (ptr) ::apollo::decision::ObjectOvertake(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::ObjectOvertake::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_ObjectOvertake = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsObjectOvertake}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Range.base, + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_PointENU.base,}}; + +static void InitDefaultsObjectSidePass() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_ObjectSidePass_default_instance_; + new (ptr) ::apollo::decision::ObjectSidePass(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::ObjectSidePass::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_ObjectSidePass = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsObjectSidePass}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Range.base,}}; + +static void InitDefaultsObjectAvoid() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_ObjectAvoid_default_instance_; + new (ptr) ::apollo::decision::ObjectAvoid(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::ObjectAvoid::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_ObjectAvoid = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsObjectAvoid}, {}}; + +static void InitDefaultsObjectDecisionType() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_ObjectDecisionType_default_instance_; + new (ptr) ::apollo::decision::ObjectDecisionType(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::ObjectDecisionType::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<8> scc_info_ObjectDecisionType = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 8, InitDefaultsObjectDecisionType}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectIgnore.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectStop.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectFollow.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectYield.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectOvertake.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectNudge.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectSidePass.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectAvoid.base,}}; + +static void InitDefaultsObjectDecision() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_ObjectDecision_default_instance_; + new (ptr) ::apollo::decision::ObjectDecision(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::ObjectDecision::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_ObjectDecision = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsObjectDecision}, { + &protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::scc_info_PredictionObstacle.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectDecisionType.base,}}; + +static void InitDefaultsObjectDecisions() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_ObjectDecisions_default_instance_; + new (ptr) ::apollo::decision::ObjectDecisions(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::ObjectDecisions::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_ObjectDecisions = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsObjectDecisions}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectDecision.base,}}; + +static void InitDefaultsStopLine() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_StopLine_default_instance_; + new (ptr) ::apollo::decision::StopLine(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::StopLine::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_StopLine = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsStopLine}, {}}; + +static void InitDefaultsMainStop() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_MainStop_default_instance_; + new (ptr) ::apollo::decision::MainStop(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::MainStop::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_MainStop = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsMainStop}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_StopLine.base, + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_PointENU.base,}}; + +static void InitDefaultsEmergencyStopHardBrake() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_EmergencyStopHardBrake_default_instance_; + new (ptr) ::apollo::decision::EmergencyStopHardBrake(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::EmergencyStopHardBrake::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_EmergencyStopHardBrake = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsEmergencyStopHardBrake}, {}}; + +static void InitDefaultsEmergencyStopCruiseToStop() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_EmergencyStopCruiseToStop_default_instance_; + new (ptr) ::apollo::decision::EmergencyStopCruiseToStop(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::EmergencyStopCruiseToStop::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_EmergencyStopCruiseToStop = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsEmergencyStopCruiseToStop}, {}}; + +static void InitDefaultsMainEmergencyStop() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_MainEmergencyStop_default_instance_; + new (ptr) ::apollo::decision::MainEmergencyStop(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::MainEmergencyStop::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_MainEmergencyStop = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsMainEmergencyStop}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_EmergencyStopHardBrake.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_EmergencyStopCruiseToStop.base,}}; + +static void InitDefaultsMainCruise() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_MainCruise_default_instance_; + new (ptr) ::apollo::decision::MainCruise(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::MainCruise::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_MainCruise = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsMainCruise}, {}}; + +static void InitDefaultsMainChangeLane() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_MainChangeLane_default_instance_; + new (ptr) ::apollo::decision::MainChangeLane(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::MainChangeLane::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_MainChangeLane = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsMainChangeLane}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_TargetLane.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainStop.base,}}; + +static void InitDefaultsMainMissionComplete() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_MainMissionComplete_default_instance_; + new (ptr) ::apollo::decision::MainMissionComplete(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::MainMissionComplete::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_MainMissionComplete = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsMainMissionComplete}, {}}; + +static void InitDefaultsMainNotReady() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_MainNotReady_default_instance_; + new (ptr) ::apollo::decision::MainNotReady(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::MainNotReady::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_MainNotReady = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsMainNotReady}, {}}; + +static void InitDefaultsMainParking() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_MainParking_default_instance_; + new (ptr) ::apollo::decision::MainParking(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::MainParking::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_MainParking = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsMainParking}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_PointENU.base,}}; + +static void InitDefaultsMainDecision() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_MainDecision_default_instance_; + new (ptr) ::apollo::decision::MainDecision(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::MainDecision::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<8> scc_info_MainDecision = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 8, InitDefaultsMainDecision}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainCruise.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainStop.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainEmergencyStop.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainChangeLane.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainMissionComplete.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainNotReady.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainParking.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_TargetLane.base,}}; + +static void InitDefaultsMasterVehicleDebug() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_MasterVehicleDebug_default_instance_; + new (ptr) ::apollo::decision::MasterVehicleDebug(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::MasterVehicleDebug::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_MasterVehicleDebug = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsMasterVehicleDebug}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_PointENU.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Range.base,}}; + +static void InitDefaultsObjectDebug() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_ObjectDebug_default_instance_; + new (ptr) ::apollo::decision::ObjectDebug(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::ObjectDebug::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_ObjectDebug = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsObjectDebug}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Range.base, + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_Point3D.base,}}; + +static void InitDefaultsLatencyStats() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_LatencyStats_default_instance_; + new (ptr) ::apollo::decision::LatencyStats(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::LatencyStats::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_LatencyStats = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsLatencyStats}, {}}; + +static void InitDefaultsStats() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_Stats_default_instance_; + new (ptr) ::apollo::decision::Stats(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::Stats::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_Stats = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsStats}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_LatencyStats.base,}}; + +static void InitDefaultsModuleDebug() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_ModuleDebug_default_instance_; + new (ptr) ::apollo::decision::ModuleDebug(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::ModuleDebug::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_ModuleDebug = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsModuleDebug}, {}}; + +static void InitDefaultsDebug() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_Debug_default_instance_; + new (ptr) ::apollo::decision::Debug(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::Debug::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<4> scc_info_Debug = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 4, InitDefaultsDebug}, { + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MasterVehicleDebug.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainDecision.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectDebug.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ModuleDebug.base,}}; + +static void InitDefaultsLightSignal() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_LightSignal_default_instance_; + new (ptr) ::apollo::decision::LightSignal(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::LightSignal::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_LightSignal = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsLightSignal}, {}}; + +static void InitDefaultsDecisionResult() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::decision::_DecisionResult_default_instance_; + new (ptr) ::apollo::decision::DecisionResult(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::decision::DecisionResult::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<7> scc_info_DecisionResult = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 7, InitDefaultsDecisionResult}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectDecisions.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainDecision.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Debug.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Stats.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::scc_info_Signal.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_LightSignal.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_Range.base); + ::google::protobuf::internal::InitSCC(&scc_info_TargetLane.base); + ::google::protobuf::internal::InitSCC(&scc_info_ObjectIgnore.base); + ::google::protobuf::internal::InitSCC(&scc_info_ObjectStop.base); + ::google::protobuf::internal::InitSCC(&scc_info_ObjectNudge.base); + ::google::protobuf::internal::InitSCC(&scc_info_ObjectYield.base); + ::google::protobuf::internal::InitSCC(&scc_info_ObjectFollow.base); + ::google::protobuf::internal::InitSCC(&scc_info_ObjectOvertake.base); + ::google::protobuf::internal::InitSCC(&scc_info_ObjectSidePass.base); + ::google::protobuf::internal::InitSCC(&scc_info_ObjectAvoid.base); + ::google::protobuf::internal::InitSCC(&scc_info_ObjectDecisionType.base); + ::google::protobuf::internal::InitSCC(&scc_info_ObjectDecision.base); + ::google::protobuf::internal::InitSCC(&scc_info_ObjectDecisions.base); + ::google::protobuf::internal::InitSCC(&scc_info_StopLine.base); + ::google::protobuf::internal::InitSCC(&scc_info_MainStop.base); + ::google::protobuf::internal::InitSCC(&scc_info_EmergencyStopHardBrake.base); + ::google::protobuf::internal::InitSCC(&scc_info_EmergencyStopCruiseToStop.base); + ::google::protobuf::internal::InitSCC(&scc_info_MainEmergencyStop.base); + ::google::protobuf::internal::InitSCC(&scc_info_MainCruise.base); + ::google::protobuf::internal::InitSCC(&scc_info_MainChangeLane.base); + ::google::protobuf::internal::InitSCC(&scc_info_MainMissionComplete.base); + ::google::protobuf::internal::InitSCC(&scc_info_MainNotReady.base); + ::google::protobuf::internal::InitSCC(&scc_info_MainParking.base); + ::google::protobuf::internal::InitSCC(&scc_info_MainDecision.base); + ::google::protobuf::internal::InitSCC(&scc_info_MasterVehicleDebug.base); + ::google::protobuf::internal::InitSCC(&scc_info_ObjectDebug.base); + ::google::protobuf::internal::InitSCC(&scc_info_LatencyStats.base); + ::google::protobuf::internal::InitSCC(&scc_info_Stats.base); + ::google::protobuf::internal::InitSCC(&scc_info_ModuleDebug.base); + ::google::protobuf::internal::InitSCC(&scc_info_Debug.base); + ::google::protobuf::internal::InitSCC(&scc_info_LightSignal.base); + ::google::protobuf::internal::InitSCC(&scc_info_DecisionResult.base); +} + +::google::protobuf::Metadata file_level_metadata[32]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[8]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::Range, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::Range, start_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::Range, end_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::TargetLane, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::TargetLane, id_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::TargetLane, start_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::TargetLane, end_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::TargetLane, speed_limit_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectIgnore, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectStop, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectStop, distance_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectStop, preferred_distance_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectStop, reason_code_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectStop, stop_point_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectNudge, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectNudge, distance_l_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectNudge, type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectNudge, preferred_distance_l_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectYield, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectYield, distance_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectYield, preferred_distance_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectYield, yield_point_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectFollow, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectFollow, distance_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectFollow, preferred_distance_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectFollow, follow_point_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectOvertake, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectOvertake, distance_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectOvertake, preferred_distance_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectOvertake, overtake_point_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectSidePass, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectSidePass, distance_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectSidePass, preferred_distance_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectSidePass, type_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectAvoid, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDecisionType, _internal_metadata_), + ~0u, // no _extensions_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDecisionType, _oneof_case_[0]), + ~0u, // no _weak_field_map_ + offsetof(::apollo::decision::ObjectDecisionTypeDefaultTypeInternal, ignore_), + offsetof(::apollo::decision::ObjectDecisionTypeDefaultTypeInternal, stop_), + offsetof(::apollo::decision::ObjectDecisionTypeDefaultTypeInternal, follow_), + offsetof(::apollo::decision::ObjectDecisionTypeDefaultTypeInternal, yield_), + offsetof(::apollo::decision::ObjectDecisionTypeDefaultTypeInternal, overtake_), + offsetof(::apollo::decision::ObjectDecisionTypeDefaultTypeInternal, nudge_), + offsetof(::apollo::decision::ObjectDecisionTypeDefaultTypeInternal, sidepass_), + offsetof(::apollo::decision::ObjectDecisionTypeDefaultTypeInternal, avoid_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDecisionType, object_tag_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDecision, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDecision, prediction_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDecision, id_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDecision, type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDecision, decision_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDecision, object_decision_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDecisions, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDecisions, decision_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::StopLine, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::StopLine, lane_id_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::StopLine, distance_s_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainStop, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainStop, enforced_line_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainStop, preferred_start_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainStop, preferred_end_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainStop, reason_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainStop, reason_code_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainStop, stop_point_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainStop, stop_heading_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::EmergencyStopHardBrake, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::EmergencyStopCruiseToStop, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainEmergencyStop, _internal_metadata_), + ~0u, // no _extensions_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainEmergencyStop, _oneof_case_[0]), + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainEmergencyStop, reason_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainEmergencyStop, reason_code_), + offsetof(::apollo::decision::MainEmergencyStopDefaultTypeInternal, hard_brake_), + offsetof(::apollo::decision::MainEmergencyStopDefaultTypeInternal, cruise_to_stop_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainEmergencyStop, task_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainCruise, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainChangeLane, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainChangeLane, type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainChangeLane, default_lane_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainChangeLane, default_lane_stop_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainChangeLane, target_lane_stop_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainMissionComplete, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainNotReady, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainNotReady, reason_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainParking, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainParking, type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainParking, heading_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainParking, stop_point_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainParking, parking_polygon_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainDecision, _internal_metadata_), + ~0u, // no _extensions_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainDecision, _oneof_case_[0]), + ~0u, // no _weak_field_map_ + offsetof(::apollo::decision::MainDecisionDefaultTypeInternal, cruise_), + offsetof(::apollo::decision::MainDecisionDefaultTypeInternal, stop_), + offsetof(::apollo::decision::MainDecisionDefaultTypeInternal, estop_), + offsetof(::apollo::decision::MainDecisionDefaultTypeInternal, change_lane_), + offsetof(::apollo::decision::MainDecisionDefaultTypeInternal, mission_complete_), + offsetof(::apollo::decision::MainDecisionDefaultTypeInternal, not_ready_), + offsetof(::apollo::decision::MainDecisionDefaultTypeInternal, parking_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainDecision, target_lane_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MainDecision, task_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MasterVehicleDebug, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MasterVehicleDebug, position_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MasterVehicleDebug, current_lane_id_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MasterVehicleDebug, lane_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MasterVehicleDebug, lane_l_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MasterVehicleDebug, route_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MasterVehicleDebug, route_l_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MasterVehicleDebug, heading_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MasterVehicleDebug, heading_speed_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MasterVehicleDebug, heading_acceleration_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MasterVehicleDebug, route_s_range_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::MasterVehicleDebug, route_l_range_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDebug, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDebug, id_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDebug, path_id_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDebug, route_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDebug, route_l_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDebug, on_route_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDebug, lane_id_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDebug, lane_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDebug, on_lane_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDebug, path_speed_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ObjectDebug, st_region_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LatencyStats, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LatencyStats, total_time_ms_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LatencyStats, sensor_read_time_ms_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LatencyStats, adc_prepare_time_ms_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LatencyStats, obj_prepare_time_ms_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LatencyStats, world_rule_time_ms_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LatencyStats, st_graph_time_ms_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LatencyStats, gateway_receive_delay_ms_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LatencyStats, perception_receive_delay_ms_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LatencyStats, prediction_receive_delay_ms_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LatencyStats, signal_receive_delay_ms_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LatencyStats, perception_interval_ms_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LatencyStats, prediction_interval_ms_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::Stats, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::Stats, latency_stats_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ModuleDebug, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ModuleDebug, gateway_sequence_num_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ModuleDebug, perception_sequence_num_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ModuleDebug, prediction_sequence_num_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::ModuleDebug, signal_sequence_num_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::Debug, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::Debug, master_vehicle_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::Debug, original_decision_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::Debug, object_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::Debug, map_version_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::Debug, decision_version_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::Debug, module_debug_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LightSignal, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LightSignal, emergency_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::LightSignal, turn_signal_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::DecisionResult, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::DecisionResult, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::DecisionResult, object_decision_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::DecisionResult, main_decision_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::DecisionResult, debug_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::DecisionResult, stats_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::DecisionResult, signal_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::decision::DecisionResult, light_signal_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::decision::Range)}, + { 7, -1, sizeof(::apollo::decision::TargetLane)}, + { 16, -1, sizeof(::apollo::decision::ObjectIgnore)}, + { 21, -1, sizeof(::apollo::decision::ObjectStop)}, + { 30, -1, sizeof(::apollo::decision::ObjectNudge)}, + { 38, -1, sizeof(::apollo::decision::ObjectYield)}, + { 46, -1, sizeof(::apollo::decision::ObjectFollow)}, + { 54, -1, sizeof(::apollo::decision::ObjectOvertake)}, + { 62, -1, sizeof(::apollo::decision::ObjectSidePass)}, + { 70, -1, sizeof(::apollo::decision::ObjectAvoid)}, + { 75, -1, sizeof(::apollo::decision::ObjectDecisionType)}, + { 89, -1, sizeof(::apollo::decision::ObjectDecision)}, + { 99, -1, sizeof(::apollo::decision::ObjectDecisions)}, + { 105, -1, sizeof(::apollo::decision::StopLine)}, + { 112, -1, sizeof(::apollo::decision::MainStop)}, + { 124, -1, sizeof(::apollo::decision::EmergencyStopHardBrake)}, + { 129, -1, sizeof(::apollo::decision::EmergencyStopCruiseToStop)}, + { 134, -1, sizeof(::apollo::decision::MainEmergencyStop)}, + { 144, -1, sizeof(::apollo::decision::MainCruise)}, + { 149, -1, sizeof(::apollo::decision::MainChangeLane)}, + { 158, -1, sizeof(::apollo::decision::MainMissionComplete)}, + { 163, -1, sizeof(::apollo::decision::MainNotReady)}, + { 169, -1, sizeof(::apollo::decision::MainParking)}, + { 178, -1, sizeof(::apollo::decision::MainDecision)}, + { 192, -1, sizeof(::apollo::decision::MasterVehicleDebug)}, + { 208, -1, sizeof(::apollo::decision::ObjectDebug)}, + { 223, -1, sizeof(::apollo::decision::LatencyStats)}, + { 240, -1, sizeof(::apollo::decision::Stats)}, + { 246, -1, sizeof(::apollo::decision::ModuleDebug)}, + { 255, -1, sizeof(::apollo::decision::Debug)}, + { 266, -1, sizeof(::apollo::decision::LightSignal)}, + { 273, -1, sizeof(::apollo::decision::DecisionResult)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::decision::_Range_default_instance_), + reinterpret_cast(&::apollo::decision::_TargetLane_default_instance_), + reinterpret_cast(&::apollo::decision::_ObjectIgnore_default_instance_), + reinterpret_cast(&::apollo::decision::_ObjectStop_default_instance_), + reinterpret_cast(&::apollo::decision::_ObjectNudge_default_instance_), + reinterpret_cast(&::apollo::decision::_ObjectYield_default_instance_), + reinterpret_cast(&::apollo::decision::_ObjectFollow_default_instance_), + reinterpret_cast(&::apollo::decision::_ObjectOvertake_default_instance_), + reinterpret_cast(&::apollo::decision::_ObjectSidePass_default_instance_), + reinterpret_cast(&::apollo::decision::_ObjectAvoid_default_instance_), + reinterpret_cast(&::apollo::decision::_ObjectDecisionType_default_instance_), + reinterpret_cast(&::apollo::decision::_ObjectDecision_default_instance_), + reinterpret_cast(&::apollo::decision::_ObjectDecisions_default_instance_), + reinterpret_cast(&::apollo::decision::_StopLine_default_instance_), + reinterpret_cast(&::apollo::decision::_MainStop_default_instance_), + reinterpret_cast(&::apollo::decision::_EmergencyStopHardBrake_default_instance_), + reinterpret_cast(&::apollo::decision::_EmergencyStopCruiseToStop_default_instance_), + reinterpret_cast(&::apollo::decision::_MainEmergencyStop_default_instance_), + reinterpret_cast(&::apollo::decision::_MainCruise_default_instance_), + reinterpret_cast(&::apollo::decision::_MainChangeLane_default_instance_), + reinterpret_cast(&::apollo::decision::_MainMissionComplete_default_instance_), + reinterpret_cast(&::apollo::decision::_MainNotReady_default_instance_), + reinterpret_cast(&::apollo::decision::_MainParking_default_instance_), + reinterpret_cast(&::apollo::decision::_MainDecision_default_instance_), + reinterpret_cast(&::apollo::decision::_MasterVehicleDebug_default_instance_), + reinterpret_cast(&::apollo::decision::_ObjectDebug_default_instance_), + reinterpret_cast(&::apollo::decision::_LatencyStats_default_instance_), + reinterpret_cast(&::apollo::decision::_Stats_default_instance_), + reinterpret_cast(&::apollo::decision::_ModuleDebug_default_instance_), + reinterpret_cast(&::apollo::decision::_Debug_default_instance_), + reinterpret_cast(&::apollo::decision::_LightSignal_default_instance_), + reinterpret_cast(&::apollo::decision::_DecisionResult_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/decision/decision.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 32); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n)apollo_msgs/proto/decision/decision.pr" + "oto\022\017apollo.decision\032%apollo_msgs/proto/" + "common/header.proto\032\'apollo_msgs/proto/c" + "ommon/geometry.proto\0326apollo_msgs/proto/" + "prediction/prediction_obstacle.proto\032&ap" + "ollo_msgs/proto/canbus/chassis.proto\"#\n\005" + "Range\022\r\n\005start\030\001 \001(\001\022\013\n\003end\030\002 \001(\001\"M\n\nTar" + "getLane\022\n\n\002id\030\001 \001(\t\022\017\n\007start_s\030\002 \001(\001\022\r\n\005" + "end_s\030\003 \001(\001\022\023\n\013speed_limit\030\004 \001(\001\"\016\n\014Obje" + "ctIgnore\"\271\001\n\nObjectStop\022\022\n\ndistance_s\030\001 " + "\001(\001\0224\n\024preferred_distance_s\030\002 \001(\0132\026.apol" + "lo.decision.Range\0224\n\013reason_code\030\003 \001(\0162\037" + ".apollo.decision.StopReasonCode\022+\n\nstop_" + "point\030\004 \001(\0132\027.apollo.common.PointENU\"\261\001\n" + "\013ObjectNudge\022\022\n\ndistance_l\030\001 \001(\001\022/\n\004type" + "\030\002 \001(\0162!.apollo.decision.ObjectNudge.Typ" + "e\0224\n\024preferred_distance_l\030\003 \001(\0132\026.apollo" + ".decision.Range\"\'\n\004Type\022\016\n\nLEFT_NUDGE\020\000\022" + "\017\n\013RIGHT_NUDGE\020\001\"\205\001\n\013ObjectYield\022\022\n\ndist" + "ance_s\030\001 \001(\001\0224\n\024preferred_distance_s\030\002 \001" + "(\0132\026.apollo.decision.Range\022,\n\013yield_poin" + "t\030\003 \001(\0132\027.apollo.common.PointENU\"\207\001\n\014Obj" + "ectFollow\022\022\n\ndistance_s\030\001 \001(\001\0224\n\024preferr" + "ed_distance_s\030\002 \001(\0132\026.apollo.decision.Ra" + "nge\022-\n\014follow_point\030\003 \001(\0132\027.apollo.commo" + "n.PointENU\"\213\001\n\016ObjectOvertake\022\022\n\ndistanc" + "e_s\030\001 \001(\001\0224\n\024preferred_distance_s\030\002 \001(\0132" + "\026.apollo.decision.Range\022/\n\016overtake_poin" + "t\030\003 \001(\0132\027.apollo.common.PointENU\"\254\001\n\016Obj" + "ectSidePass\022\022\n\ndistance_s\030\001 \001(\001\0224\n\024prefe" + "rred_distance_s\030\002 \001(\0132\026.apollo.decision." + "Range\0222\n\004type\030\003 \001(\0162$.apollo.decision.Ob" + "jectSidePass.Type\"\034\n\004Type\022\n\n\006FOLLOW\020\000\022\010\n" + "\004LEAD\020\001\"\r\n\013ObjectAvoid\"\250\003\n\022ObjectDecisio" + "nType\022/\n\006ignore\030\001 \001(\0132\035.apollo.decision." + "ObjectIgnoreH\000\022+\n\004stop\030\002 \001(\0132\033.apollo.de" + "cision.ObjectStopH\000\022/\n\006follow\030\003 \001(\0132\035.ap" + "ollo.decision.ObjectFollowH\000\022-\n\005yield\030\004 " + "\001(\0132\034.apollo.decision.ObjectYieldH\000\0223\n\010o" + "vertake\030\005 \001(\0132\037.apollo.decision.ObjectOv" + "ertakeH\000\022-\n\005nudge\030\006 \001(\0132\034.apollo.decisio" + "n.ObjectNudgeH\000\0223\n\010sidepass\030\007 \001(\0132\037.apol" + "lo.decision.ObjectSidePassH\000\022-\n\005avoid\030\010 " + "\001(\0132\034.apollo.decision.ObjectAvoidH\000B\014\n\no" + "bject_tag\"\301\002\n\016ObjectDecision\0229\n\npredicti" + "on\030\001 \001(\0132%.apollo.prediction.PredictionO" + "bstacle\022\n\n\002id\030\002 \001(\t\0228\n\004type\030\003 \001(\0162*.apol" + "lo.decision.ObjectDecision.ObjectType\0225\n" + "\010decision\030\004 \001(\0132#.apollo.decision.Object" + "DecisionType\022<\n\017object_decision\030\005 \003(\0132#." + "apollo.decision.ObjectDecisionType\"9\n\nOb" + "jectType\022\016\n\nPREDICTION\020\000\022\016\n\nPERCEPTION\020\001" + "\022\013\n\007VIRTUAL\020\002\"D\n\017ObjectDecisions\0221\n\010deci" + "sion\030\001 \003(\0132\037.apollo.decision.ObjectDecis" + "ion\"/\n\010StopLine\022\017\n\007lane_id\030\001 \001(\t\022\022\n\ndist" + "ance_s\030\002 \001(\001\"\253\002\n\010MainStop\0220\n\renforced_li" + "ne\030\001 \001(\0132\031.apollo.decision.StopLine\0222\n\017p" + "referred_start\030\002 \001(\0132\031.apollo.decision.S" + "topLine\0220\n\rpreferred_end\030\003 \001(\0132\031.apollo." + "decision.StopLine\022\016\n\006reason\030\004 \001(\t\0224\n\013rea" + "son_code\030\005 \001(\0162\037.apollo.decision.StopRea" + "sonCode\022+\n\nstop_point\030\006 \001(\0132\027.apollo.com" + "mon.PointENU\022\024\n\014stop_heading\030\007 \001(\001\"\030\n\026Em" + "ergencyStopHardBrake\"\033\n\031EmergencyStopCru" + "iseToStop\"\237\003\n\021MainEmergencyStop\022\016\n\006reaso" + "n\030\001 \001(\t\022B\n\013reason_code\030\002 \001(\0162-.apollo.de" + "cision.MainEmergencyStop.ReasonCode\022=\n\nh" + "ard_brake\030\003 \001(\0132\'.apollo.decision.Emerge" + "ncyStopHardBrakeH\000\022D\n\016cruise_to_stop\030\004 \001" + "(\0132*.apollo.decision.EmergencyStopCruise" + "ToStopH\000\"\250\001\n\nReasonCode\022\035\n\031ESTOP_REASON_" + "INTERNAL_ERR\020\000\022\032\n\026ESTOP_REASON_COLLISION" + "\020\001\022\035\n\031ESTOP_REASON_ST_FIND_PATH\020\002\022!\n\035EST" + "OP_REASON_ST_MAKE_DECISION\020\003\022\035\n\031ESTOP_RE" + "ASON_SENSOR_ERROR\020\004B\006\n\004task\"\014\n\nMainCruis" + "e\"\377\001\n\016MainChangeLane\0222\n\004type\030\001 \001(\0162$.apo" + "llo.decision.MainChangeLane.Type\0221\n\014defa" + "ult_lane\030\002 \003(\0132\033.apollo.decision.TargetL" + "ane\0224\n\021default_lane_stop\030\003 \001(\0132\031.apollo." + "decision.MainStop\0223\n\020target_lane_stop\030\004 " + "\001(\0132\031.apollo.decision.MainStop\"\033\n\004Type\022\010" + "\n\004LEFT\020\000\022\t\n\005RIGHT\020\001\"\025\n\023MainMissionComple" + "te\"\036\n\014MainNotReady\022\016\n\006reason\030\001 \001(\t\"\340\001\n\013M" + "ainParking\022/\n\004type\030\001 \001(\0162!.apollo.decisi" + "on.MainParking.Type\022\017\n\007heading\030\002 \001(\001\022+\n\n" + "stop_point\030\003 \001(\0132\027.apollo.common.PointEN" + "U\0220\n\017parking_polygon\030\004 \003(\0132\027.apollo.comm" + "on.PointENU\"0\n\004Type\022\023\n\017FORWARD_PARKING\020\000" + "\022\023\n\017REVERSE_PARKING\020\001\"\266\003\n\014MainDecision\022-" + "\n\006cruise\030\001 \001(\0132\033.apollo.decision.MainCru" + "iseH\000\022)\n\004stop\030\002 \001(\0132\031.apollo.decision.Ma" + "inStopH\000\0223\n\005estop\030\003 \001(\0132\".apollo.decisio" + "n.MainEmergencyStopH\000\0226\n\013change_lane\030\004 \001" + "(\0132\037.apollo.decision.MainChangeLaneH\000\022@\n" + "\020mission_complete\030\006 \001(\0132$.apollo.decisio" + "n.MainMissionCompleteH\000\0222\n\tnot_ready\030\007 \001" + "(\0132\035.apollo.decision.MainNotReadyH\000\022/\n\007p" + "arking\030\010 \001(\0132\034.apollo.decision.MainParki" + "ngH\000\0220\n\013target_lane\030\005 \003(\0132\033.apollo.decis" + "ion.TargetLaneB\006\n\004task\"\276\002\n\022MasterVehicle" + "Debug\022)\n\010position\030\001 \001(\0132\027.apollo.common." + "PointENU\022\027\n\017current_lane_id\030\002 \001(\t\022\016\n\006lan" + "e_s\030\003 \001(\001\022\016\n\006lane_l\030\004 \001(\001\022\017\n\007route_s\030\005 \001" + "(\001\022\017\n\007route_l\030\006 \001(\001\022\017\n\007heading\030\007 \001(\001\022\025\n\r" + "heading_speed\030\010 \001(\001\022\034\n\024heading_accelerat" + "ion\030\t \001(\001\022-\n\rroute_s_range\030\n \001(\0132\026.apoll" + "o.decision.Range\022-\n\rroute_l_range\030\013 \001(\0132" + "\026.apollo.decision.Range\"\377\001\n\013ObjectDebug\022" + "\n\n\002id\030\001 \001(\t\022\017\n\007path_id\030\002 \001(\t\022\'\n\007route_s\030" + "\003 \001(\0132\026.apollo.decision.Range\022\'\n\007route_l" + "\030\004 \001(\0132\026.apollo.decision.Range\022\020\n\010on_rou" + "te\030\005 \001(\010\022\017\n\007lane_id\030\006 \001(\t\022\016\n\006lane_s\030\007 \001(" + "\001\022\017\n\007on_lane\030\010 \001(\010\022\022\n\npath_speed\030\t \001(\001\022)" + "\n\tst_region\030\n \003(\0132\026.apollo.common.Point3" + "D\"\377\002\n\014LatencyStats\022\025\n\rtotal_time_ms\030\001 \001(" + "\001\022\033\n\023sensor_read_time_ms\030\002 \001(\001\022\033\n\023adc_pr" + "epare_time_ms\030\003 \001(\001\022\033\n\023obj_prepare_time_" + "ms\030\004 \001(\001\022\032\n\022world_rule_time_ms\030\005 \001(\001\022\030\n\020" + "st_graph_time_ms\030\006 \001(\001\022 \n\030gateway_receiv" + "e_delay_ms\030\010 \001(\001\022#\n\033perception_receive_d" + "elay_ms\030\t \001(\001\022#\n\033prediction_receive_dela" + "y_ms\030\n \001(\001\022\037\n\027signal_receive_delay_ms\030\013 " + "\001(\001\022\036\n\026perception_interval_ms\030\014 \001(\001\022\036\n\026p" + "rediction_interval_ms\030\r \001(\001\"=\n\005Stats\0224\n\r" + "latency_stats\030\001 \001(\0132\035.apollo.decision.La" + "tencyStats\"\212\001\n\013ModuleDebug\022\034\n\024gateway_se" + "quence_num\030\001 \001(\r\022\037\n\027perception_sequence_" + "num\030\002 \001(\r\022\037\n\027prediction_sequence_num\030\003 \001" + "(\r\022\033\n\023signal_sequence_num\030\004 \001(\r\"\217\002\n\005Debu" + "g\022;\n\016master_vehicle\030\001 \001(\0132#.apollo.decis" + "ion.MasterVehicleDebug\0228\n\021original_decis" + "ion\030\002 \001(\0132\035.apollo.decision.MainDecision" + "\022,\n\006object\030\003 \003(\0132\034.apollo.decision.Objec" + "tDebug\022\023\n\013map_version\030\005 \001(\014\022\030\n\020decision_" + "version\030\007 \001(\014\0222\n\014module_debug\030\006 \001(\0132\034.ap" + "ollo.decision.ModuleDebug\"\230\001\n\013LightSigna" + "l\022\021\n\temergency\030\001 \001(\010\022<\n\013turn_signal\030\002 \001(" + "\0162\'.apollo.decision.LightSignal.TurnSign" + "al\"8\n\nTurnSignal\022\013\n\007NO_TURN\020\000\022\r\n\tLEFT_TU" + "RN\020\001\022\016\n\nRIGHT_TURN\020\002\"\321\002\n\016DecisionResult\022" + "%\n\006header\030\001 \001(\0132\025.apollo.common.Header\0229" + "\n\017object_decision\030\002 \001(\0132 .apollo.decisio" + "n.ObjectDecisions\0224\n\rmain_decision\030\003 \001(\013" + "2\035.apollo.decision.MainDecision\022%\n\005debug" + "\030\004 \001(\0132\026.apollo.decision.Debug\022%\n\005stats\030" + "\006 \001(\0132\026.apollo.decision.Stats\022%\n\006signal\030" + "\007 \001(\0132\025.apollo.canbus.Signal\0222\n\014light_si" + "gnal\030\005 \001(\0132\034.apollo.decision.LightSignal" + "*\243\002\n\016StopReasonCode\022\034\n\030STOP_REASON_HEAD_" + "VEHICLE\020\000\022\033\n\027STOP_REASON_DESTINATION\020\001\022\032" + "\n\026STOP_REASON_PEDESTRIAN\020\002\022\030\n\024STOP_REASO" + "N_OBSTACLE\020\003\022\032\n\026STOP_REASON_PREPARKING\020\004" + "\022\026\n\022STOP_REASON_SIGNAL\020d\022\031\n\025STOP_REASON_" + "STOP_SIGN\020e\022\032\n\026STOP_REASON_YIELD_SIGN\020f\022" + "\032\n\026STOP_REASON_CLEAR_ZONE\020g\022\031\n\025STOP_REAS" + "ON_CROSSWALK\020hb\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 6222); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/decision/decision.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto +namespace apollo { +namespace decision { +const ::google::protobuf::EnumDescriptor* ObjectNudge_Type_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_enum_descriptors[0]; +} +bool ObjectNudge_Type_IsValid(int value) { + switch (value) { + case 0: + case 1: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const ObjectNudge_Type ObjectNudge::LEFT_NUDGE; +const ObjectNudge_Type ObjectNudge::RIGHT_NUDGE; +const ObjectNudge_Type ObjectNudge::Type_MIN; +const ObjectNudge_Type ObjectNudge::Type_MAX; +const int ObjectNudge::Type_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* ObjectSidePass_Type_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_enum_descriptors[1]; +} +bool ObjectSidePass_Type_IsValid(int value) { + switch (value) { + case 0: + case 1: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const ObjectSidePass_Type ObjectSidePass::FOLLOW; +const ObjectSidePass_Type ObjectSidePass::LEAD; +const ObjectSidePass_Type ObjectSidePass::Type_MIN; +const ObjectSidePass_Type ObjectSidePass::Type_MAX; +const int ObjectSidePass::Type_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* ObjectDecision_ObjectType_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_enum_descriptors[2]; +} +bool ObjectDecision_ObjectType_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const ObjectDecision_ObjectType ObjectDecision::PREDICTION; +const ObjectDecision_ObjectType ObjectDecision::PERCEPTION; +const ObjectDecision_ObjectType ObjectDecision::VIRTUAL; +const ObjectDecision_ObjectType ObjectDecision::ObjectType_MIN; +const ObjectDecision_ObjectType ObjectDecision::ObjectType_MAX; +const int ObjectDecision::ObjectType_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* MainEmergencyStop_ReasonCode_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_enum_descriptors[3]; +} +bool MainEmergencyStop_ReasonCode_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const MainEmergencyStop_ReasonCode MainEmergencyStop::ESTOP_REASON_INTERNAL_ERR; +const MainEmergencyStop_ReasonCode MainEmergencyStop::ESTOP_REASON_COLLISION; +const MainEmergencyStop_ReasonCode MainEmergencyStop::ESTOP_REASON_ST_FIND_PATH; +const MainEmergencyStop_ReasonCode MainEmergencyStop::ESTOP_REASON_ST_MAKE_DECISION; +const MainEmergencyStop_ReasonCode MainEmergencyStop::ESTOP_REASON_SENSOR_ERROR; +const MainEmergencyStop_ReasonCode MainEmergencyStop::ReasonCode_MIN; +const MainEmergencyStop_ReasonCode MainEmergencyStop::ReasonCode_MAX; +const int MainEmergencyStop::ReasonCode_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* MainChangeLane_Type_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_enum_descriptors[4]; +} +bool MainChangeLane_Type_IsValid(int value) { + switch (value) { + case 0: + case 1: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const MainChangeLane_Type MainChangeLane::LEFT; +const MainChangeLane_Type MainChangeLane::RIGHT; +const MainChangeLane_Type MainChangeLane::Type_MIN; +const MainChangeLane_Type MainChangeLane::Type_MAX; +const int MainChangeLane::Type_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* MainParking_Type_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_enum_descriptors[5]; +} +bool MainParking_Type_IsValid(int value) { + switch (value) { + case 0: + case 1: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const MainParking_Type MainParking::FORWARD_PARKING; +const MainParking_Type MainParking::REVERSE_PARKING; +const MainParking_Type MainParking::Type_MIN; +const MainParking_Type MainParking::Type_MAX; +const int MainParking::Type_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* LightSignal_TurnSignal_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_enum_descriptors[6]; +} +bool LightSignal_TurnSignal_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const LightSignal_TurnSignal LightSignal::NO_TURN; +const LightSignal_TurnSignal LightSignal::LEFT_TURN; +const LightSignal_TurnSignal LightSignal::RIGHT_TURN; +const LightSignal_TurnSignal LightSignal::TurnSignal_MIN; +const LightSignal_TurnSignal LightSignal::TurnSignal_MAX; +const int LightSignal::TurnSignal_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* StopReasonCode_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_enum_descriptors[7]; +} +bool StopReasonCode_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 100: + case 101: + case 102: + case 103: + case 104: + return true; + default: + return false; + } +} + + +// =================================================================== + +void Range::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Range::kStartFieldNumber; +const int Range::kEndFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Range::Range() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Range.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.Range) +} +Range::Range(const Range& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&start_, &from.start_, + static_cast(reinterpret_cast(&end_) - + reinterpret_cast(&start_)) + sizeof(end_)); + // @@protoc_insertion_point(copy_constructor:apollo.decision.Range) +} + +void Range::SharedCtor() { + ::memset(&start_, 0, static_cast( + reinterpret_cast(&end_) - + reinterpret_cast(&start_)) + sizeof(end_)); +} + +Range::~Range() { + // @@protoc_insertion_point(destructor:apollo.decision.Range) + SharedDtor(); +} + +void Range::SharedDtor() { +} + +void Range::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Range::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Range& Range::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Range.base); + return *internal_default_instance(); +} + + +void Range::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.Range) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&start_, 0, static_cast( + reinterpret_cast(&end_) - + reinterpret_cast(&start_)) + sizeof(end_)); + _internal_metadata_.Clear(); +} + +bool Range::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.Range) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double start = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &start_))); + } else { + goto handle_unusual; + } + break; + } + + // double end = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &end_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.Range) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.Range) + return false; +#undef DO_ +} + +void Range::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.Range) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double start = 1; + if (this->start() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->start(), output); + } + + // double end = 2; + if (this->end() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->end(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.Range) +} + +::google::protobuf::uint8* Range::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.Range) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double start = 1; + if (this->start() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->start(), target); + } + + // double end = 2; + if (this->end() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->end(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.Range) + return target; +} + +size_t Range::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.Range) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double start = 1; + if (this->start() != 0) { + total_size += 1 + 8; + } + + // double end = 2; + if (this->end() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Range::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.Range) + GOOGLE_DCHECK_NE(&from, this); + const Range* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.Range) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.Range) + MergeFrom(*source); + } +} + +void Range::MergeFrom(const Range& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.Range) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.start() != 0) { + set_start(from.start()); + } + if (from.end() != 0) { + set_end(from.end()); + } +} + +void Range::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.Range) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Range::CopyFrom(const Range& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.Range) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Range::IsInitialized() const { + return true; +} + +void Range::Swap(Range* other) { + if (other == this) return; + InternalSwap(other); +} +void Range::InternalSwap(Range* other) { + using std::swap; + swap(start_, other->start_); + swap(end_, other->end_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Range::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void TargetLane::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int TargetLane::kIdFieldNumber; +const int TargetLane::kStartSFieldNumber; +const int TargetLane::kEndSFieldNumber; +const int TargetLane::kSpeedLimitFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +TargetLane::TargetLane() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_TargetLane.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.TargetLane) +} +TargetLane::TargetLane(const TargetLane& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.id().size() > 0) { + id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.id_); + } + ::memcpy(&start_s_, &from.start_s_, + static_cast(reinterpret_cast(&speed_limit_) - + reinterpret_cast(&start_s_)) + sizeof(speed_limit_)); + // @@protoc_insertion_point(copy_constructor:apollo.decision.TargetLane) +} + +void TargetLane::SharedCtor() { + id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&start_s_, 0, static_cast( + reinterpret_cast(&speed_limit_) - + reinterpret_cast(&start_s_)) + sizeof(speed_limit_)); +} + +TargetLane::~TargetLane() { + // @@protoc_insertion_point(destructor:apollo.decision.TargetLane) + SharedDtor(); +} + +void TargetLane::SharedDtor() { + id_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + +void TargetLane::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* TargetLane::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const TargetLane& TargetLane::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_TargetLane.base); + return *internal_default_instance(); +} + + +void TargetLane::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.TargetLane) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&start_s_, 0, static_cast( + reinterpret_cast(&speed_limit_) - + reinterpret_cast(&start_s_)) + sizeof(speed_limit_)); + _internal_metadata_.Clear(); +} + +bool TargetLane::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.TargetLane) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // string id = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_id())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->id().data(), static_cast(this->id().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.decision.TargetLane.id")); + } else { + goto handle_unusual; + } + break; + } + + // double start_s = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &start_s_))); + } else { + goto handle_unusual; + } + break; + } + + // double end_s = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &end_s_))); + } else { + goto handle_unusual; + } + break; + } + + // double speed_limit = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &speed_limit_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.TargetLane) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.TargetLane) + return false; +#undef DO_ +} + +void TargetLane::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.TargetLane) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // string id = 1; + if (this->id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->id().data(), static_cast(this->id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.TargetLane.id"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 1, this->id(), output); + } + + // double start_s = 2; + if (this->start_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->start_s(), output); + } + + // double end_s = 3; + if (this->end_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->end_s(), output); + } + + // double speed_limit = 4; + if (this->speed_limit() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->speed_limit(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.TargetLane) +} + +::google::protobuf::uint8* TargetLane::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.TargetLane) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // string id = 1; + if (this->id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->id().data(), static_cast(this->id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.TargetLane.id"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 1, this->id(), target); + } + + // double start_s = 2; + if (this->start_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->start_s(), target); + } + + // double end_s = 3; + if (this->end_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->end_s(), target); + } + + // double speed_limit = 4; + if (this->speed_limit() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->speed_limit(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.TargetLane) + return target; +} + +size_t TargetLane::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.TargetLane) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // string id = 1; + if (this->id().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->id()); + } + + // double start_s = 2; + if (this->start_s() != 0) { + total_size += 1 + 8; + } + + // double end_s = 3; + if (this->end_s() != 0) { + total_size += 1 + 8; + } + + // double speed_limit = 4; + if (this->speed_limit() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void TargetLane::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.TargetLane) + GOOGLE_DCHECK_NE(&from, this); + const TargetLane* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.TargetLane) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.TargetLane) + MergeFrom(*source); + } +} + +void TargetLane::MergeFrom(const TargetLane& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.TargetLane) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.id().size() > 0) { + + id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.id_); + } + if (from.start_s() != 0) { + set_start_s(from.start_s()); + } + if (from.end_s() != 0) { + set_end_s(from.end_s()); + } + if (from.speed_limit() != 0) { + set_speed_limit(from.speed_limit()); + } +} + +void TargetLane::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.TargetLane) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void TargetLane::CopyFrom(const TargetLane& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.TargetLane) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool TargetLane::IsInitialized() const { + return true; +} + +void TargetLane::Swap(TargetLane* other) { + if (other == this) return; + InternalSwap(other); +} +void TargetLane::InternalSwap(TargetLane* other) { + using std::swap; + id_.Swap(&other->id_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(start_s_, other->start_s_); + swap(end_s_, other->end_s_); + swap(speed_limit_, other->speed_limit_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata TargetLane::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ObjectIgnore::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ObjectIgnore::ObjectIgnore() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectIgnore.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.ObjectIgnore) +} +ObjectIgnore::ObjectIgnore(const ObjectIgnore& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:apollo.decision.ObjectIgnore) +} + +void ObjectIgnore::SharedCtor() { +} + +ObjectIgnore::~ObjectIgnore() { + // @@protoc_insertion_point(destructor:apollo.decision.ObjectIgnore) + SharedDtor(); +} + +void ObjectIgnore::SharedDtor() { +} + +void ObjectIgnore::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ObjectIgnore::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ObjectIgnore& ObjectIgnore::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectIgnore.base); + return *internal_default_instance(); +} + + +void ObjectIgnore::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.ObjectIgnore) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _internal_metadata_.Clear(); +} + +bool ObjectIgnore::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.ObjectIgnore) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.ObjectIgnore) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.ObjectIgnore) + return false; +#undef DO_ +} + +void ObjectIgnore::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.ObjectIgnore) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.ObjectIgnore) +} + +::google::protobuf::uint8* ObjectIgnore::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.ObjectIgnore) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.ObjectIgnore) + return target; +} + +size_t ObjectIgnore::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.ObjectIgnore) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ObjectIgnore::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.ObjectIgnore) + GOOGLE_DCHECK_NE(&from, this); + const ObjectIgnore* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.ObjectIgnore) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.ObjectIgnore) + MergeFrom(*source); + } +} + +void ObjectIgnore::MergeFrom(const ObjectIgnore& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.ObjectIgnore) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + +} + +void ObjectIgnore::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.ObjectIgnore) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObjectIgnore::CopyFrom(const ObjectIgnore& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.ObjectIgnore) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObjectIgnore::IsInitialized() const { + return true; +} + +void ObjectIgnore::Swap(ObjectIgnore* other) { + if (other == this) return; + InternalSwap(other); +} +void ObjectIgnore::InternalSwap(ObjectIgnore* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ObjectIgnore::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ObjectStop::InitAsDefaultInstance() { + ::apollo::decision::_ObjectStop_default_instance_._instance.get_mutable()->preferred_distance_s_ = const_cast< ::apollo::decision::Range*>( + ::apollo::decision::Range::internal_default_instance()); + ::apollo::decision::_ObjectStop_default_instance_._instance.get_mutable()->stop_point_ = const_cast< ::apollo::common::PointENU*>( + ::apollo::common::PointENU::internal_default_instance()); +} +void ObjectStop::clear_stop_point() { + if (GetArenaNoVirtual() == NULL && stop_point_ != NULL) { + delete stop_point_; + } + stop_point_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ObjectStop::kDistanceSFieldNumber; +const int ObjectStop::kPreferredDistanceSFieldNumber; +const int ObjectStop::kReasonCodeFieldNumber; +const int ObjectStop::kStopPointFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ObjectStop::ObjectStop() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectStop.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.ObjectStop) +} +ObjectStop::ObjectStop(const ObjectStop& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_preferred_distance_s()) { + preferred_distance_s_ = new ::apollo::decision::Range(*from.preferred_distance_s_); + } else { + preferred_distance_s_ = NULL; + } + if (from.has_stop_point()) { + stop_point_ = new ::apollo::common::PointENU(*from.stop_point_); + } else { + stop_point_ = NULL; + } + ::memcpy(&distance_s_, &from.distance_s_, + static_cast(reinterpret_cast(&reason_code_) - + reinterpret_cast(&distance_s_)) + sizeof(reason_code_)); + // @@protoc_insertion_point(copy_constructor:apollo.decision.ObjectStop) +} + +void ObjectStop::SharedCtor() { + ::memset(&preferred_distance_s_, 0, static_cast( + reinterpret_cast(&reason_code_) - + reinterpret_cast(&preferred_distance_s_)) + sizeof(reason_code_)); +} + +ObjectStop::~ObjectStop() { + // @@protoc_insertion_point(destructor:apollo.decision.ObjectStop) + SharedDtor(); +} + +void ObjectStop::SharedDtor() { + if (this != internal_default_instance()) delete preferred_distance_s_; + if (this != internal_default_instance()) delete stop_point_; +} + +void ObjectStop::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ObjectStop::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ObjectStop& ObjectStop::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectStop.base); + return *internal_default_instance(); +} + + +void ObjectStop::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.ObjectStop) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && preferred_distance_s_ != NULL) { + delete preferred_distance_s_; + } + preferred_distance_s_ = NULL; + if (GetArenaNoVirtual() == NULL && stop_point_ != NULL) { + delete stop_point_; + } + stop_point_ = NULL; + ::memset(&distance_s_, 0, static_cast( + reinterpret_cast(&reason_code_) - + reinterpret_cast(&distance_s_)) + sizeof(reason_code_)); + _internal_metadata_.Clear(); +} + +bool ObjectStop::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.ObjectStop) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double distance_s = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &distance_s_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.Range preferred_distance_s = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_preferred_distance_s())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.StopReasonCode reason_code = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_reason_code(static_cast< ::apollo::decision::StopReasonCode >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.PointENU stop_point = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_stop_point())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.ObjectStop) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.ObjectStop) + return false; +#undef DO_ +} + +void ObjectStop::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.ObjectStop) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double distance_s = 1; + if (this->distance_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->distance_s(), output); + } + + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_preferred_distance_s(), output); + } + + // .apollo.decision.StopReasonCode reason_code = 3; + if (this->reason_code() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 3, this->reason_code(), output); + } + + // .apollo.common.PointENU stop_point = 4; + if (this->has_stop_point()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, this->_internal_stop_point(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.ObjectStop) +} + +::google::protobuf::uint8* ObjectStop::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.ObjectStop) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double distance_s = 1; + if (this->distance_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->distance_s(), target); + } + + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_preferred_distance_s(), deterministic, target); + } + + // .apollo.decision.StopReasonCode reason_code = 3; + if (this->reason_code() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 3, this->reason_code(), target); + } + + // .apollo.common.PointENU stop_point = 4; + if (this->has_stop_point()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->_internal_stop_point(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.ObjectStop) + return target; +} + +size_t ObjectStop::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.ObjectStop) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *preferred_distance_s_); + } + + // .apollo.common.PointENU stop_point = 4; + if (this->has_stop_point()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *stop_point_); + } + + // double distance_s = 1; + if (this->distance_s() != 0) { + total_size += 1 + 8; + } + + // .apollo.decision.StopReasonCode reason_code = 3; + if (this->reason_code() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->reason_code()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ObjectStop::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.ObjectStop) + GOOGLE_DCHECK_NE(&from, this); + const ObjectStop* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.ObjectStop) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.ObjectStop) + MergeFrom(*source); + } +} + +void ObjectStop::MergeFrom(const ObjectStop& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.ObjectStop) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_preferred_distance_s()) { + mutable_preferred_distance_s()->::apollo::decision::Range::MergeFrom(from.preferred_distance_s()); + } + if (from.has_stop_point()) { + mutable_stop_point()->::apollo::common::PointENU::MergeFrom(from.stop_point()); + } + if (from.distance_s() != 0) { + set_distance_s(from.distance_s()); + } + if (from.reason_code() != 0) { + set_reason_code(from.reason_code()); + } +} + +void ObjectStop::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.ObjectStop) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObjectStop::CopyFrom(const ObjectStop& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.ObjectStop) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObjectStop::IsInitialized() const { + return true; +} + +void ObjectStop::Swap(ObjectStop* other) { + if (other == this) return; + InternalSwap(other); +} +void ObjectStop::InternalSwap(ObjectStop* other) { + using std::swap; + swap(preferred_distance_s_, other->preferred_distance_s_); + swap(stop_point_, other->stop_point_); + swap(distance_s_, other->distance_s_); + swap(reason_code_, other->reason_code_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ObjectStop::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ObjectNudge::InitAsDefaultInstance() { + ::apollo::decision::_ObjectNudge_default_instance_._instance.get_mutable()->preferred_distance_l_ = const_cast< ::apollo::decision::Range*>( + ::apollo::decision::Range::internal_default_instance()); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ObjectNudge::kDistanceLFieldNumber; +const int ObjectNudge::kTypeFieldNumber; +const int ObjectNudge::kPreferredDistanceLFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ObjectNudge::ObjectNudge() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectNudge.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.ObjectNudge) +} +ObjectNudge::ObjectNudge(const ObjectNudge& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_preferred_distance_l()) { + preferred_distance_l_ = new ::apollo::decision::Range(*from.preferred_distance_l_); + } else { + preferred_distance_l_ = NULL; + } + ::memcpy(&distance_l_, &from.distance_l_, + static_cast(reinterpret_cast(&type_) - + reinterpret_cast(&distance_l_)) + sizeof(type_)); + // @@protoc_insertion_point(copy_constructor:apollo.decision.ObjectNudge) +} + +void ObjectNudge::SharedCtor() { + ::memset(&preferred_distance_l_, 0, static_cast( + reinterpret_cast(&type_) - + reinterpret_cast(&preferred_distance_l_)) + sizeof(type_)); +} + +ObjectNudge::~ObjectNudge() { + // @@protoc_insertion_point(destructor:apollo.decision.ObjectNudge) + SharedDtor(); +} + +void ObjectNudge::SharedDtor() { + if (this != internal_default_instance()) delete preferred_distance_l_; +} + +void ObjectNudge::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ObjectNudge::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ObjectNudge& ObjectNudge::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectNudge.base); + return *internal_default_instance(); +} + + +void ObjectNudge::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.ObjectNudge) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && preferred_distance_l_ != NULL) { + delete preferred_distance_l_; + } + preferred_distance_l_ = NULL; + ::memset(&distance_l_, 0, static_cast( + reinterpret_cast(&type_) - + reinterpret_cast(&distance_l_)) + sizeof(type_)); + _internal_metadata_.Clear(); +} + +bool ObjectNudge::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.ObjectNudge) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double distance_l = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &distance_l_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectNudge.Type type = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_type(static_cast< ::apollo::decision::ObjectNudge_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.Range preferred_distance_l = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_preferred_distance_l())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.ObjectNudge) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.ObjectNudge) + return false; +#undef DO_ +} + +void ObjectNudge::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.ObjectNudge) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double distance_l = 1; + if (this->distance_l() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->distance_l(), output); + } + + // .apollo.decision.ObjectNudge.Type type = 2; + if (this->type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 2, this->type(), output); + } + + // .apollo.decision.Range preferred_distance_l = 3; + if (this->has_preferred_distance_l()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_preferred_distance_l(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.ObjectNudge) +} + +::google::protobuf::uint8* ObjectNudge::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.ObjectNudge) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double distance_l = 1; + if (this->distance_l() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->distance_l(), target); + } + + // .apollo.decision.ObjectNudge.Type type = 2; + if (this->type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 2, this->type(), target); + } + + // .apollo.decision.Range preferred_distance_l = 3; + if (this->has_preferred_distance_l()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_preferred_distance_l(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.ObjectNudge) + return target; +} + +size_t ObjectNudge::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.ObjectNudge) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.decision.Range preferred_distance_l = 3; + if (this->has_preferred_distance_l()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *preferred_distance_l_); + } + + // double distance_l = 1; + if (this->distance_l() != 0) { + total_size += 1 + 8; + } + + // .apollo.decision.ObjectNudge.Type type = 2; + if (this->type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->type()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ObjectNudge::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.ObjectNudge) + GOOGLE_DCHECK_NE(&from, this); + const ObjectNudge* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.ObjectNudge) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.ObjectNudge) + MergeFrom(*source); + } +} + +void ObjectNudge::MergeFrom(const ObjectNudge& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.ObjectNudge) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_preferred_distance_l()) { + mutable_preferred_distance_l()->::apollo::decision::Range::MergeFrom(from.preferred_distance_l()); + } + if (from.distance_l() != 0) { + set_distance_l(from.distance_l()); + } + if (from.type() != 0) { + set_type(from.type()); + } +} + +void ObjectNudge::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.ObjectNudge) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObjectNudge::CopyFrom(const ObjectNudge& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.ObjectNudge) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObjectNudge::IsInitialized() const { + return true; +} + +void ObjectNudge::Swap(ObjectNudge* other) { + if (other == this) return; + InternalSwap(other); +} +void ObjectNudge::InternalSwap(ObjectNudge* other) { + using std::swap; + swap(preferred_distance_l_, other->preferred_distance_l_); + swap(distance_l_, other->distance_l_); + swap(type_, other->type_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ObjectNudge::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ObjectYield::InitAsDefaultInstance() { + ::apollo::decision::_ObjectYield_default_instance_._instance.get_mutable()->preferred_distance_s_ = const_cast< ::apollo::decision::Range*>( + ::apollo::decision::Range::internal_default_instance()); + ::apollo::decision::_ObjectYield_default_instance_._instance.get_mutable()->yield_point_ = const_cast< ::apollo::common::PointENU*>( + ::apollo::common::PointENU::internal_default_instance()); +} +void ObjectYield::clear_yield_point() { + if (GetArenaNoVirtual() == NULL && yield_point_ != NULL) { + delete yield_point_; + } + yield_point_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ObjectYield::kDistanceSFieldNumber; +const int ObjectYield::kPreferredDistanceSFieldNumber; +const int ObjectYield::kYieldPointFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ObjectYield::ObjectYield() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectYield.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.ObjectYield) +} +ObjectYield::ObjectYield(const ObjectYield& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_preferred_distance_s()) { + preferred_distance_s_ = new ::apollo::decision::Range(*from.preferred_distance_s_); + } else { + preferred_distance_s_ = NULL; + } + if (from.has_yield_point()) { + yield_point_ = new ::apollo::common::PointENU(*from.yield_point_); + } else { + yield_point_ = NULL; + } + distance_s_ = from.distance_s_; + // @@protoc_insertion_point(copy_constructor:apollo.decision.ObjectYield) +} + +void ObjectYield::SharedCtor() { + ::memset(&preferred_distance_s_, 0, static_cast( + reinterpret_cast(&distance_s_) - + reinterpret_cast(&preferred_distance_s_)) + sizeof(distance_s_)); +} + +ObjectYield::~ObjectYield() { + // @@protoc_insertion_point(destructor:apollo.decision.ObjectYield) + SharedDtor(); +} + +void ObjectYield::SharedDtor() { + if (this != internal_default_instance()) delete preferred_distance_s_; + if (this != internal_default_instance()) delete yield_point_; +} + +void ObjectYield::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ObjectYield::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ObjectYield& ObjectYield::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectYield.base); + return *internal_default_instance(); +} + + +void ObjectYield::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.ObjectYield) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && preferred_distance_s_ != NULL) { + delete preferred_distance_s_; + } + preferred_distance_s_ = NULL; + if (GetArenaNoVirtual() == NULL && yield_point_ != NULL) { + delete yield_point_; + } + yield_point_ = NULL; + distance_s_ = 0; + _internal_metadata_.Clear(); +} + +bool ObjectYield::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.ObjectYield) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double distance_s = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &distance_s_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.Range preferred_distance_s = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_preferred_distance_s())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.PointENU yield_point = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_yield_point())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.ObjectYield) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.ObjectYield) + return false; +#undef DO_ +} + +void ObjectYield::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.ObjectYield) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double distance_s = 1; + if (this->distance_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->distance_s(), output); + } + + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_preferred_distance_s(), output); + } + + // .apollo.common.PointENU yield_point = 3; + if (this->has_yield_point()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_yield_point(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.ObjectYield) +} + +::google::protobuf::uint8* ObjectYield::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.ObjectYield) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double distance_s = 1; + if (this->distance_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->distance_s(), target); + } + + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_preferred_distance_s(), deterministic, target); + } + + // .apollo.common.PointENU yield_point = 3; + if (this->has_yield_point()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_yield_point(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.ObjectYield) + return target; +} + +size_t ObjectYield::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.ObjectYield) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *preferred_distance_s_); + } + + // .apollo.common.PointENU yield_point = 3; + if (this->has_yield_point()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *yield_point_); + } + + // double distance_s = 1; + if (this->distance_s() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ObjectYield::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.ObjectYield) + GOOGLE_DCHECK_NE(&from, this); + const ObjectYield* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.ObjectYield) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.ObjectYield) + MergeFrom(*source); + } +} + +void ObjectYield::MergeFrom(const ObjectYield& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.ObjectYield) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_preferred_distance_s()) { + mutable_preferred_distance_s()->::apollo::decision::Range::MergeFrom(from.preferred_distance_s()); + } + if (from.has_yield_point()) { + mutable_yield_point()->::apollo::common::PointENU::MergeFrom(from.yield_point()); + } + if (from.distance_s() != 0) { + set_distance_s(from.distance_s()); + } +} + +void ObjectYield::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.ObjectYield) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObjectYield::CopyFrom(const ObjectYield& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.ObjectYield) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObjectYield::IsInitialized() const { + return true; +} + +void ObjectYield::Swap(ObjectYield* other) { + if (other == this) return; + InternalSwap(other); +} +void ObjectYield::InternalSwap(ObjectYield* other) { + using std::swap; + swap(preferred_distance_s_, other->preferred_distance_s_); + swap(yield_point_, other->yield_point_); + swap(distance_s_, other->distance_s_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ObjectYield::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ObjectFollow::InitAsDefaultInstance() { + ::apollo::decision::_ObjectFollow_default_instance_._instance.get_mutable()->preferred_distance_s_ = const_cast< ::apollo::decision::Range*>( + ::apollo::decision::Range::internal_default_instance()); + ::apollo::decision::_ObjectFollow_default_instance_._instance.get_mutable()->follow_point_ = const_cast< ::apollo::common::PointENU*>( + ::apollo::common::PointENU::internal_default_instance()); +} +void ObjectFollow::clear_follow_point() { + if (GetArenaNoVirtual() == NULL && follow_point_ != NULL) { + delete follow_point_; + } + follow_point_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ObjectFollow::kDistanceSFieldNumber; +const int ObjectFollow::kPreferredDistanceSFieldNumber; +const int ObjectFollow::kFollowPointFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ObjectFollow::ObjectFollow() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectFollow.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.ObjectFollow) +} +ObjectFollow::ObjectFollow(const ObjectFollow& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_preferred_distance_s()) { + preferred_distance_s_ = new ::apollo::decision::Range(*from.preferred_distance_s_); + } else { + preferred_distance_s_ = NULL; + } + if (from.has_follow_point()) { + follow_point_ = new ::apollo::common::PointENU(*from.follow_point_); + } else { + follow_point_ = NULL; + } + distance_s_ = from.distance_s_; + // @@protoc_insertion_point(copy_constructor:apollo.decision.ObjectFollow) +} + +void ObjectFollow::SharedCtor() { + ::memset(&preferred_distance_s_, 0, static_cast( + reinterpret_cast(&distance_s_) - + reinterpret_cast(&preferred_distance_s_)) + sizeof(distance_s_)); +} + +ObjectFollow::~ObjectFollow() { + // @@protoc_insertion_point(destructor:apollo.decision.ObjectFollow) + SharedDtor(); +} + +void ObjectFollow::SharedDtor() { + if (this != internal_default_instance()) delete preferred_distance_s_; + if (this != internal_default_instance()) delete follow_point_; +} + +void ObjectFollow::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ObjectFollow::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ObjectFollow& ObjectFollow::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectFollow.base); + return *internal_default_instance(); +} + + +void ObjectFollow::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.ObjectFollow) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && preferred_distance_s_ != NULL) { + delete preferred_distance_s_; + } + preferred_distance_s_ = NULL; + if (GetArenaNoVirtual() == NULL && follow_point_ != NULL) { + delete follow_point_; + } + follow_point_ = NULL; + distance_s_ = 0; + _internal_metadata_.Clear(); +} + +bool ObjectFollow::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.ObjectFollow) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double distance_s = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &distance_s_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.Range preferred_distance_s = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_preferred_distance_s())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.PointENU follow_point = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_follow_point())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.ObjectFollow) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.ObjectFollow) + return false; +#undef DO_ +} + +void ObjectFollow::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.ObjectFollow) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double distance_s = 1; + if (this->distance_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->distance_s(), output); + } + + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_preferred_distance_s(), output); + } + + // .apollo.common.PointENU follow_point = 3; + if (this->has_follow_point()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_follow_point(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.ObjectFollow) +} + +::google::protobuf::uint8* ObjectFollow::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.ObjectFollow) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double distance_s = 1; + if (this->distance_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->distance_s(), target); + } + + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_preferred_distance_s(), deterministic, target); + } + + // .apollo.common.PointENU follow_point = 3; + if (this->has_follow_point()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_follow_point(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.ObjectFollow) + return target; +} + +size_t ObjectFollow::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.ObjectFollow) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *preferred_distance_s_); + } + + // .apollo.common.PointENU follow_point = 3; + if (this->has_follow_point()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *follow_point_); + } + + // double distance_s = 1; + if (this->distance_s() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ObjectFollow::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.ObjectFollow) + GOOGLE_DCHECK_NE(&from, this); + const ObjectFollow* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.ObjectFollow) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.ObjectFollow) + MergeFrom(*source); + } +} + +void ObjectFollow::MergeFrom(const ObjectFollow& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.ObjectFollow) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_preferred_distance_s()) { + mutable_preferred_distance_s()->::apollo::decision::Range::MergeFrom(from.preferred_distance_s()); + } + if (from.has_follow_point()) { + mutable_follow_point()->::apollo::common::PointENU::MergeFrom(from.follow_point()); + } + if (from.distance_s() != 0) { + set_distance_s(from.distance_s()); + } +} + +void ObjectFollow::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.ObjectFollow) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObjectFollow::CopyFrom(const ObjectFollow& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.ObjectFollow) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObjectFollow::IsInitialized() const { + return true; +} + +void ObjectFollow::Swap(ObjectFollow* other) { + if (other == this) return; + InternalSwap(other); +} +void ObjectFollow::InternalSwap(ObjectFollow* other) { + using std::swap; + swap(preferred_distance_s_, other->preferred_distance_s_); + swap(follow_point_, other->follow_point_); + swap(distance_s_, other->distance_s_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ObjectFollow::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ObjectOvertake::InitAsDefaultInstance() { + ::apollo::decision::_ObjectOvertake_default_instance_._instance.get_mutable()->preferred_distance_s_ = const_cast< ::apollo::decision::Range*>( + ::apollo::decision::Range::internal_default_instance()); + ::apollo::decision::_ObjectOvertake_default_instance_._instance.get_mutable()->overtake_point_ = const_cast< ::apollo::common::PointENU*>( + ::apollo::common::PointENU::internal_default_instance()); +} +void ObjectOvertake::clear_overtake_point() { + if (GetArenaNoVirtual() == NULL && overtake_point_ != NULL) { + delete overtake_point_; + } + overtake_point_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ObjectOvertake::kDistanceSFieldNumber; +const int ObjectOvertake::kPreferredDistanceSFieldNumber; +const int ObjectOvertake::kOvertakePointFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ObjectOvertake::ObjectOvertake() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectOvertake.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.ObjectOvertake) +} +ObjectOvertake::ObjectOvertake(const ObjectOvertake& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_preferred_distance_s()) { + preferred_distance_s_ = new ::apollo::decision::Range(*from.preferred_distance_s_); + } else { + preferred_distance_s_ = NULL; + } + if (from.has_overtake_point()) { + overtake_point_ = new ::apollo::common::PointENU(*from.overtake_point_); + } else { + overtake_point_ = NULL; + } + distance_s_ = from.distance_s_; + // @@protoc_insertion_point(copy_constructor:apollo.decision.ObjectOvertake) +} + +void ObjectOvertake::SharedCtor() { + ::memset(&preferred_distance_s_, 0, static_cast( + reinterpret_cast(&distance_s_) - + reinterpret_cast(&preferred_distance_s_)) + sizeof(distance_s_)); +} + +ObjectOvertake::~ObjectOvertake() { + // @@protoc_insertion_point(destructor:apollo.decision.ObjectOvertake) + SharedDtor(); +} + +void ObjectOvertake::SharedDtor() { + if (this != internal_default_instance()) delete preferred_distance_s_; + if (this != internal_default_instance()) delete overtake_point_; +} + +void ObjectOvertake::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ObjectOvertake::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ObjectOvertake& ObjectOvertake::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectOvertake.base); + return *internal_default_instance(); +} + + +void ObjectOvertake::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.ObjectOvertake) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && preferred_distance_s_ != NULL) { + delete preferred_distance_s_; + } + preferred_distance_s_ = NULL; + if (GetArenaNoVirtual() == NULL && overtake_point_ != NULL) { + delete overtake_point_; + } + overtake_point_ = NULL; + distance_s_ = 0; + _internal_metadata_.Clear(); +} + +bool ObjectOvertake::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.ObjectOvertake) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double distance_s = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &distance_s_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.Range preferred_distance_s = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_preferred_distance_s())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.PointENU overtake_point = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_overtake_point())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.ObjectOvertake) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.ObjectOvertake) + return false; +#undef DO_ +} + +void ObjectOvertake::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.ObjectOvertake) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double distance_s = 1; + if (this->distance_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->distance_s(), output); + } + + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_preferred_distance_s(), output); + } + + // .apollo.common.PointENU overtake_point = 3; + if (this->has_overtake_point()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_overtake_point(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.ObjectOvertake) +} + +::google::protobuf::uint8* ObjectOvertake::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.ObjectOvertake) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double distance_s = 1; + if (this->distance_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->distance_s(), target); + } + + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_preferred_distance_s(), deterministic, target); + } + + // .apollo.common.PointENU overtake_point = 3; + if (this->has_overtake_point()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_overtake_point(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.ObjectOvertake) + return target; +} + +size_t ObjectOvertake::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.ObjectOvertake) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *preferred_distance_s_); + } + + // .apollo.common.PointENU overtake_point = 3; + if (this->has_overtake_point()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *overtake_point_); + } + + // double distance_s = 1; + if (this->distance_s() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ObjectOvertake::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.ObjectOvertake) + GOOGLE_DCHECK_NE(&from, this); + const ObjectOvertake* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.ObjectOvertake) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.ObjectOvertake) + MergeFrom(*source); + } +} + +void ObjectOvertake::MergeFrom(const ObjectOvertake& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.ObjectOvertake) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_preferred_distance_s()) { + mutable_preferred_distance_s()->::apollo::decision::Range::MergeFrom(from.preferred_distance_s()); + } + if (from.has_overtake_point()) { + mutable_overtake_point()->::apollo::common::PointENU::MergeFrom(from.overtake_point()); + } + if (from.distance_s() != 0) { + set_distance_s(from.distance_s()); + } +} + +void ObjectOvertake::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.ObjectOvertake) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObjectOvertake::CopyFrom(const ObjectOvertake& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.ObjectOvertake) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObjectOvertake::IsInitialized() const { + return true; +} + +void ObjectOvertake::Swap(ObjectOvertake* other) { + if (other == this) return; + InternalSwap(other); +} +void ObjectOvertake::InternalSwap(ObjectOvertake* other) { + using std::swap; + swap(preferred_distance_s_, other->preferred_distance_s_); + swap(overtake_point_, other->overtake_point_); + swap(distance_s_, other->distance_s_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ObjectOvertake::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ObjectSidePass::InitAsDefaultInstance() { + ::apollo::decision::_ObjectSidePass_default_instance_._instance.get_mutable()->preferred_distance_s_ = const_cast< ::apollo::decision::Range*>( + ::apollo::decision::Range::internal_default_instance()); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ObjectSidePass::kDistanceSFieldNumber; +const int ObjectSidePass::kPreferredDistanceSFieldNumber; +const int ObjectSidePass::kTypeFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ObjectSidePass::ObjectSidePass() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectSidePass.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.ObjectSidePass) +} +ObjectSidePass::ObjectSidePass(const ObjectSidePass& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_preferred_distance_s()) { + preferred_distance_s_ = new ::apollo::decision::Range(*from.preferred_distance_s_); + } else { + preferred_distance_s_ = NULL; + } + ::memcpy(&distance_s_, &from.distance_s_, + static_cast(reinterpret_cast(&type_) - + reinterpret_cast(&distance_s_)) + sizeof(type_)); + // @@protoc_insertion_point(copy_constructor:apollo.decision.ObjectSidePass) +} + +void ObjectSidePass::SharedCtor() { + ::memset(&preferred_distance_s_, 0, static_cast( + reinterpret_cast(&type_) - + reinterpret_cast(&preferred_distance_s_)) + sizeof(type_)); +} + +ObjectSidePass::~ObjectSidePass() { + // @@protoc_insertion_point(destructor:apollo.decision.ObjectSidePass) + SharedDtor(); +} + +void ObjectSidePass::SharedDtor() { + if (this != internal_default_instance()) delete preferred_distance_s_; +} + +void ObjectSidePass::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ObjectSidePass::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ObjectSidePass& ObjectSidePass::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectSidePass.base); + return *internal_default_instance(); +} + + +void ObjectSidePass::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.ObjectSidePass) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && preferred_distance_s_ != NULL) { + delete preferred_distance_s_; + } + preferred_distance_s_ = NULL; + ::memset(&distance_s_, 0, static_cast( + reinterpret_cast(&type_) - + reinterpret_cast(&distance_s_)) + sizeof(type_)); + _internal_metadata_.Clear(); +} + +bool ObjectSidePass::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.ObjectSidePass) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double distance_s = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &distance_s_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.Range preferred_distance_s = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_preferred_distance_s())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectSidePass.Type type = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_type(static_cast< ::apollo::decision::ObjectSidePass_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.ObjectSidePass) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.ObjectSidePass) + return false; +#undef DO_ +} + +void ObjectSidePass::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.ObjectSidePass) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double distance_s = 1; + if (this->distance_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->distance_s(), output); + } + + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_preferred_distance_s(), output); + } + + // .apollo.decision.ObjectSidePass.Type type = 3; + if (this->type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 3, this->type(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.ObjectSidePass) +} + +::google::protobuf::uint8* ObjectSidePass::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.ObjectSidePass) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double distance_s = 1; + if (this->distance_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->distance_s(), target); + } + + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_preferred_distance_s(), deterministic, target); + } + + // .apollo.decision.ObjectSidePass.Type type = 3; + if (this->type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 3, this->type(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.ObjectSidePass) + return target; +} + +size_t ObjectSidePass::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.ObjectSidePass) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.decision.Range preferred_distance_s = 2; + if (this->has_preferred_distance_s()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *preferred_distance_s_); + } + + // double distance_s = 1; + if (this->distance_s() != 0) { + total_size += 1 + 8; + } + + // .apollo.decision.ObjectSidePass.Type type = 3; + if (this->type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->type()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ObjectSidePass::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.ObjectSidePass) + GOOGLE_DCHECK_NE(&from, this); + const ObjectSidePass* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.ObjectSidePass) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.ObjectSidePass) + MergeFrom(*source); + } +} + +void ObjectSidePass::MergeFrom(const ObjectSidePass& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.ObjectSidePass) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_preferred_distance_s()) { + mutable_preferred_distance_s()->::apollo::decision::Range::MergeFrom(from.preferred_distance_s()); + } + if (from.distance_s() != 0) { + set_distance_s(from.distance_s()); + } + if (from.type() != 0) { + set_type(from.type()); + } +} + +void ObjectSidePass::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.ObjectSidePass) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObjectSidePass::CopyFrom(const ObjectSidePass& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.ObjectSidePass) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObjectSidePass::IsInitialized() const { + return true; +} + +void ObjectSidePass::Swap(ObjectSidePass* other) { + if (other == this) return; + InternalSwap(other); +} +void ObjectSidePass::InternalSwap(ObjectSidePass* other) { + using std::swap; + swap(preferred_distance_s_, other->preferred_distance_s_); + swap(distance_s_, other->distance_s_); + swap(type_, other->type_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ObjectSidePass::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ObjectAvoid::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ObjectAvoid::ObjectAvoid() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectAvoid.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.ObjectAvoid) +} +ObjectAvoid::ObjectAvoid(const ObjectAvoid& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:apollo.decision.ObjectAvoid) +} + +void ObjectAvoid::SharedCtor() { +} + +ObjectAvoid::~ObjectAvoid() { + // @@protoc_insertion_point(destructor:apollo.decision.ObjectAvoid) + SharedDtor(); +} + +void ObjectAvoid::SharedDtor() { +} + +void ObjectAvoid::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ObjectAvoid::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ObjectAvoid& ObjectAvoid::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectAvoid.base); + return *internal_default_instance(); +} + + +void ObjectAvoid::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.ObjectAvoid) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _internal_metadata_.Clear(); +} + +bool ObjectAvoid::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.ObjectAvoid) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.ObjectAvoid) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.ObjectAvoid) + return false; +#undef DO_ +} + +void ObjectAvoid::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.ObjectAvoid) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.ObjectAvoid) +} + +::google::protobuf::uint8* ObjectAvoid::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.ObjectAvoid) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.ObjectAvoid) + return target; +} + +size_t ObjectAvoid::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.ObjectAvoid) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ObjectAvoid::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.ObjectAvoid) + GOOGLE_DCHECK_NE(&from, this); + const ObjectAvoid* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.ObjectAvoid) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.ObjectAvoid) + MergeFrom(*source); + } +} + +void ObjectAvoid::MergeFrom(const ObjectAvoid& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.ObjectAvoid) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + +} + +void ObjectAvoid::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.ObjectAvoid) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObjectAvoid::CopyFrom(const ObjectAvoid& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.ObjectAvoid) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObjectAvoid::IsInitialized() const { + return true; +} + +void ObjectAvoid::Swap(ObjectAvoid* other) { + if (other == this) return; + InternalSwap(other); +} +void ObjectAvoid::InternalSwap(ObjectAvoid* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ObjectAvoid::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ObjectDecisionType::InitAsDefaultInstance() { + ::apollo::decision::_ObjectDecisionType_default_instance_.ignore_ = const_cast< ::apollo::decision::ObjectIgnore*>( + ::apollo::decision::ObjectIgnore::internal_default_instance()); + ::apollo::decision::_ObjectDecisionType_default_instance_.stop_ = const_cast< ::apollo::decision::ObjectStop*>( + ::apollo::decision::ObjectStop::internal_default_instance()); + ::apollo::decision::_ObjectDecisionType_default_instance_.follow_ = const_cast< ::apollo::decision::ObjectFollow*>( + ::apollo::decision::ObjectFollow::internal_default_instance()); + ::apollo::decision::_ObjectDecisionType_default_instance_.yield_ = const_cast< ::apollo::decision::ObjectYield*>( + ::apollo::decision::ObjectYield::internal_default_instance()); + ::apollo::decision::_ObjectDecisionType_default_instance_.overtake_ = const_cast< ::apollo::decision::ObjectOvertake*>( + ::apollo::decision::ObjectOvertake::internal_default_instance()); + ::apollo::decision::_ObjectDecisionType_default_instance_.nudge_ = const_cast< ::apollo::decision::ObjectNudge*>( + ::apollo::decision::ObjectNudge::internal_default_instance()); + ::apollo::decision::_ObjectDecisionType_default_instance_.sidepass_ = const_cast< ::apollo::decision::ObjectSidePass*>( + ::apollo::decision::ObjectSidePass::internal_default_instance()); + ::apollo::decision::_ObjectDecisionType_default_instance_.avoid_ = const_cast< ::apollo::decision::ObjectAvoid*>( + ::apollo::decision::ObjectAvoid::internal_default_instance()); +} +void ObjectDecisionType::set_allocated_ignore(::apollo::decision::ObjectIgnore* ignore) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_object_tag(); + if (ignore) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + ignore = ::google::protobuf::internal::GetOwnedMessage( + message_arena, ignore, submessage_arena); + } + set_has_ignore(); + object_tag_.ignore_ = ignore; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDecisionType.ignore) +} +void ObjectDecisionType::set_allocated_stop(::apollo::decision::ObjectStop* stop) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_object_tag(); + if (stop) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + stop = ::google::protobuf::internal::GetOwnedMessage( + message_arena, stop, submessage_arena); + } + set_has_stop(); + object_tag_.stop_ = stop; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDecisionType.stop) +} +void ObjectDecisionType::set_allocated_follow(::apollo::decision::ObjectFollow* follow) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_object_tag(); + if (follow) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + follow = ::google::protobuf::internal::GetOwnedMessage( + message_arena, follow, submessage_arena); + } + set_has_follow(); + object_tag_.follow_ = follow; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDecisionType.follow) +} +void ObjectDecisionType::set_allocated_yield(::apollo::decision::ObjectYield* yield) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_object_tag(); + if (yield) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + yield = ::google::protobuf::internal::GetOwnedMessage( + message_arena, yield, submessage_arena); + } + set_has_yield(); + object_tag_.yield_ = yield; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDecisionType.yield) +} +void ObjectDecisionType::set_allocated_overtake(::apollo::decision::ObjectOvertake* overtake) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_object_tag(); + if (overtake) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + overtake = ::google::protobuf::internal::GetOwnedMessage( + message_arena, overtake, submessage_arena); + } + set_has_overtake(); + object_tag_.overtake_ = overtake; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDecisionType.overtake) +} +void ObjectDecisionType::set_allocated_nudge(::apollo::decision::ObjectNudge* nudge) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_object_tag(); + if (nudge) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + nudge = ::google::protobuf::internal::GetOwnedMessage( + message_arena, nudge, submessage_arena); + } + set_has_nudge(); + object_tag_.nudge_ = nudge; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDecisionType.nudge) +} +void ObjectDecisionType::set_allocated_sidepass(::apollo::decision::ObjectSidePass* sidepass) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_object_tag(); + if (sidepass) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + sidepass = ::google::protobuf::internal::GetOwnedMessage( + message_arena, sidepass, submessage_arena); + } + set_has_sidepass(); + object_tag_.sidepass_ = sidepass; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDecisionType.sidepass) +} +void ObjectDecisionType::set_allocated_avoid(::apollo::decision::ObjectAvoid* avoid) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_object_tag(); + if (avoid) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + avoid = ::google::protobuf::internal::GetOwnedMessage( + message_arena, avoid, submessage_arena); + } + set_has_avoid(); + object_tag_.avoid_ = avoid; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDecisionType.avoid) +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ObjectDecisionType::kIgnoreFieldNumber; +const int ObjectDecisionType::kStopFieldNumber; +const int ObjectDecisionType::kFollowFieldNumber; +const int ObjectDecisionType::kYieldFieldNumber; +const int ObjectDecisionType::kOvertakeFieldNumber; +const int ObjectDecisionType::kNudgeFieldNumber; +const int ObjectDecisionType::kSidepassFieldNumber; +const int ObjectDecisionType::kAvoidFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ObjectDecisionType::ObjectDecisionType() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectDecisionType.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.ObjectDecisionType) +} +ObjectDecisionType::ObjectDecisionType(const ObjectDecisionType& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + clear_has_object_tag(); + switch (from.object_tag_case()) { + case kIgnore: { + mutable_ignore()->::apollo::decision::ObjectIgnore::MergeFrom(from.ignore()); + break; + } + case kStop: { + mutable_stop()->::apollo::decision::ObjectStop::MergeFrom(from.stop()); + break; + } + case kFollow: { + mutable_follow()->::apollo::decision::ObjectFollow::MergeFrom(from.follow()); + break; + } + case kYield: { + mutable_yield()->::apollo::decision::ObjectYield::MergeFrom(from.yield()); + break; + } + case kOvertake: { + mutable_overtake()->::apollo::decision::ObjectOvertake::MergeFrom(from.overtake()); + break; + } + case kNudge: { + mutable_nudge()->::apollo::decision::ObjectNudge::MergeFrom(from.nudge()); + break; + } + case kSidepass: { + mutable_sidepass()->::apollo::decision::ObjectSidePass::MergeFrom(from.sidepass()); + break; + } + case kAvoid: { + mutable_avoid()->::apollo::decision::ObjectAvoid::MergeFrom(from.avoid()); + break; + } + case OBJECT_TAG_NOT_SET: { + break; + } + } + // @@protoc_insertion_point(copy_constructor:apollo.decision.ObjectDecisionType) +} + +void ObjectDecisionType::SharedCtor() { + clear_has_object_tag(); +} + +ObjectDecisionType::~ObjectDecisionType() { + // @@protoc_insertion_point(destructor:apollo.decision.ObjectDecisionType) + SharedDtor(); +} + +void ObjectDecisionType::SharedDtor() { + if (has_object_tag()) { + clear_object_tag(); + } +} + +void ObjectDecisionType::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ObjectDecisionType::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ObjectDecisionType& ObjectDecisionType::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectDecisionType.base); + return *internal_default_instance(); +} + + +void ObjectDecisionType::clear_object_tag() { +// @@protoc_insertion_point(one_of_clear_start:apollo.decision.ObjectDecisionType) + switch (object_tag_case()) { + case kIgnore: { + delete object_tag_.ignore_; + break; + } + case kStop: { + delete object_tag_.stop_; + break; + } + case kFollow: { + delete object_tag_.follow_; + break; + } + case kYield: { + delete object_tag_.yield_; + break; + } + case kOvertake: { + delete object_tag_.overtake_; + break; + } + case kNudge: { + delete object_tag_.nudge_; + break; + } + case kSidepass: { + delete object_tag_.sidepass_; + break; + } + case kAvoid: { + delete object_tag_.avoid_; + break; + } + case OBJECT_TAG_NOT_SET: { + break; + } + } + _oneof_case_[0] = OBJECT_TAG_NOT_SET; +} + + +void ObjectDecisionType::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.ObjectDecisionType) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + clear_object_tag(); + _internal_metadata_.Clear(); +} + +bool ObjectDecisionType::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.ObjectDecisionType) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.decision.ObjectIgnore ignore = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_ignore())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectStop stop = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_stop())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectFollow follow = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_follow())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectYield yield = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_yield())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectOvertake overtake = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_overtake())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectNudge nudge = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(50u /* 50 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_nudge())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectSidePass sidepass = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(58u /* 58 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_sidepass())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectAvoid avoid = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(66u /* 66 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_avoid())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.ObjectDecisionType) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.ObjectDecisionType) + return false; +#undef DO_ +} + +void ObjectDecisionType::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.ObjectDecisionType) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.ObjectIgnore ignore = 1; + if (has_ignore()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_ignore(), output); + } + + // .apollo.decision.ObjectStop stop = 2; + if (has_stop()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_stop(), output); + } + + // .apollo.decision.ObjectFollow follow = 3; + if (has_follow()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_follow(), output); + } + + // .apollo.decision.ObjectYield yield = 4; + if (has_yield()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, this->_internal_yield(), output); + } + + // .apollo.decision.ObjectOvertake overtake = 5; + if (has_overtake()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, this->_internal_overtake(), output); + } + + // .apollo.decision.ObjectNudge nudge = 6; + if (has_nudge()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 6, this->_internal_nudge(), output); + } + + // .apollo.decision.ObjectSidePass sidepass = 7; + if (has_sidepass()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 7, this->_internal_sidepass(), output); + } + + // .apollo.decision.ObjectAvoid avoid = 8; + if (has_avoid()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 8, this->_internal_avoid(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.ObjectDecisionType) +} + +::google::protobuf::uint8* ObjectDecisionType::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.ObjectDecisionType) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.ObjectIgnore ignore = 1; + if (has_ignore()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_ignore(), deterministic, target); + } + + // .apollo.decision.ObjectStop stop = 2; + if (has_stop()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_stop(), deterministic, target); + } + + // .apollo.decision.ObjectFollow follow = 3; + if (has_follow()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_follow(), deterministic, target); + } + + // .apollo.decision.ObjectYield yield = 4; + if (has_yield()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->_internal_yield(), deterministic, target); + } + + // .apollo.decision.ObjectOvertake overtake = 5; + if (has_overtake()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 5, this->_internal_overtake(), deterministic, target); + } + + // .apollo.decision.ObjectNudge nudge = 6; + if (has_nudge()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 6, this->_internal_nudge(), deterministic, target); + } + + // .apollo.decision.ObjectSidePass sidepass = 7; + if (has_sidepass()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 7, this->_internal_sidepass(), deterministic, target); + } + + // .apollo.decision.ObjectAvoid avoid = 8; + if (has_avoid()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 8, this->_internal_avoid(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.ObjectDecisionType) + return target; +} + +size_t ObjectDecisionType::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.ObjectDecisionType) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + switch (object_tag_case()) { + // .apollo.decision.ObjectIgnore ignore = 1; + case kIgnore: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *object_tag_.ignore_); + break; + } + // .apollo.decision.ObjectStop stop = 2; + case kStop: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *object_tag_.stop_); + break; + } + // .apollo.decision.ObjectFollow follow = 3; + case kFollow: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *object_tag_.follow_); + break; + } + // .apollo.decision.ObjectYield yield = 4; + case kYield: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *object_tag_.yield_); + break; + } + // .apollo.decision.ObjectOvertake overtake = 5; + case kOvertake: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *object_tag_.overtake_); + break; + } + // .apollo.decision.ObjectNudge nudge = 6; + case kNudge: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *object_tag_.nudge_); + break; + } + // .apollo.decision.ObjectSidePass sidepass = 7; + case kSidepass: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *object_tag_.sidepass_); + break; + } + // .apollo.decision.ObjectAvoid avoid = 8; + case kAvoid: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *object_tag_.avoid_); + break; + } + case OBJECT_TAG_NOT_SET: { + break; + } + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ObjectDecisionType::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.ObjectDecisionType) + GOOGLE_DCHECK_NE(&from, this); + const ObjectDecisionType* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.ObjectDecisionType) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.ObjectDecisionType) + MergeFrom(*source); + } +} + +void ObjectDecisionType::MergeFrom(const ObjectDecisionType& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.ObjectDecisionType) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + switch (from.object_tag_case()) { + case kIgnore: { + mutable_ignore()->::apollo::decision::ObjectIgnore::MergeFrom(from.ignore()); + break; + } + case kStop: { + mutable_stop()->::apollo::decision::ObjectStop::MergeFrom(from.stop()); + break; + } + case kFollow: { + mutable_follow()->::apollo::decision::ObjectFollow::MergeFrom(from.follow()); + break; + } + case kYield: { + mutable_yield()->::apollo::decision::ObjectYield::MergeFrom(from.yield()); + break; + } + case kOvertake: { + mutable_overtake()->::apollo::decision::ObjectOvertake::MergeFrom(from.overtake()); + break; + } + case kNudge: { + mutable_nudge()->::apollo::decision::ObjectNudge::MergeFrom(from.nudge()); + break; + } + case kSidepass: { + mutable_sidepass()->::apollo::decision::ObjectSidePass::MergeFrom(from.sidepass()); + break; + } + case kAvoid: { + mutable_avoid()->::apollo::decision::ObjectAvoid::MergeFrom(from.avoid()); + break; + } + case OBJECT_TAG_NOT_SET: { + break; + } + } +} + +void ObjectDecisionType::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.ObjectDecisionType) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObjectDecisionType::CopyFrom(const ObjectDecisionType& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.ObjectDecisionType) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObjectDecisionType::IsInitialized() const { + return true; +} + +void ObjectDecisionType::Swap(ObjectDecisionType* other) { + if (other == this) return; + InternalSwap(other); +} +void ObjectDecisionType::InternalSwap(ObjectDecisionType* other) { + using std::swap; + swap(object_tag_, other->object_tag_); + swap(_oneof_case_[0], other->_oneof_case_[0]); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ObjectDecisionType::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ObjectDecision::InitAsDefaultInstance() { + ::apollo::decision::_ObjectDecision_default_instance_._instance.get_mutable()->prediction_ = const_cast< ::apollo::prediction::PredictionObstacle*>( + ::apollo::prediction::PredictionObstacle::internal_default_instance()); + ::apollo::decision::_ObjectDecision_default_instance_._instance.get_mutable()->decision_ = const_cast< ::apollo::decision::ObjectDecisionType*>( + ::apollo::decision::ObjectDecisionType::internal_default_instance()); +} +void ObjectDecision::clear_prediction() { + if (GetArenaNoVirtual() == NULL && prediction_ != NULL) { + delete prediction_; + } + prediction_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ObjectDecision::kPredictionFieldNumber; +const int ObjectDecision::kIdFieldNumber; +const int ObjectDecision::kTypeFieldNumber; +const int ObjectDecision::kDecisionFieldNumber; +const int ObjectDecision::kObjectDecisionFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ObjectDecision::ObjectDecision() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectDecision.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.ObjectDecision) +} +ObjectDecision::ObjectDecision(const ObjectDecision& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + object_decision_(from.object_decision_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.id().size() > 0) { + id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.id_); + } + if (from.has_prediction()) { + prediction_ = new ::apollo::prediction::PredictionObstacle(*from.prediction_); + } else { + prediction_ = NULL; + } + if (from.has_decision()) { + decision_ = new ::apollo::decision::ObjectDecisionType(*from.decision_); + } else { + decision_ = NULL; + } + type_ = from.type_; + // @@protoc_insertion_point(copy_constructor:apollo.decision.ObjectDecision) +} + +void ObjectDecision::SharedCtor() { + id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&prediction_, 0, static_cast( + reinterpret_cast(&type_) - + reinterpret_cast(&prediction_)) + sizeof(type_)); +} + +ObjectDecision::~ObjectDecision() { + // @@protoc_insertion_point(destructor:apollo.decision.ObjectDecision) + SharedDtor(); +} + +void ObjectDecision::SharedDtor() { + id_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (this != internal_default_instance()) delete prediction_; + if (this != internal_default_instance()) delete decision_; +} + +void ObjectDecision::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ObjectDecision::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ObjectDecision& ObjectDecision::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectDecision.base); + return *internal_default_instance(); +} + + +void ObjectDecision::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.ObjectDecision) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + object_decision_.Clear(); + id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (GetArenaNoVirtual() == NULL && prediction_ != NULL) { + delete prediction_; + } + prediction_ = NULL; + if (GetArenaNoVirtual() == NULL && decision_ != NULL) { + delete decision_; + } + decision_ = NULL; + type_ = 0; + _internal_metadata_.Clear(); +} + +bool ObjectDecision::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.ObjectDecision) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.prediction.PredictionObstacle prediction = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_prediction())); + } else { + goto handle_unusual; + } + break; + } + + // string id = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_id())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->id().data(), static_cast(this->id().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.decision.ObjectDecision.id")); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectDecision.ObjectType type = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_type(static_cast< ::apollo::decision::ObjectDecision_ObjectType >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectDecisionType decision = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_decision())); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.decision.ObjectDecisionType object_decision = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_object_decision())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.ObjectDecision) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.ObjectDecision) + return false; +#undef DO_ +} + +void ObjectDecision::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.ObjectDecision) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.prediction.PredictionObstacle prediction = 1; + if (this->has_prediction()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_prediction(), output); + } + + // string id = 2; + if (this->id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->id().data(), static_cast(this->id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.ObjectDecision.id"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 2, this->id(), output); + } + + // .apollo.decision.ObjectDecision.ObjectType type = 3; + if (this->type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 3, this->type(), output); + } + + // .apollo.decision.ObjectDecisionType decision = 4; + if (this->has_decision()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, this->_internal_decision(), output); + } + + // repeated .apollo.decision.ObjectDecisionType object_decision = 5; + for (unsigned int i = 0, + n = static_cast(this->object_decision_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, + this->object_decision(static_cast(i)), + output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.ObjectDecision) +} + +::google::protobuf::uint8* ObjectDecision::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.ObjectDecision) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.prediction.PredictionObstacle prediction = 1; + if (this->has_prediction()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_prediction(), deterministic, target); + } + + // string id = 2; + if (this->id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->id().data(), static_cast(this->id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.ObjectDecision.id"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 2, this->id(), target); + } + + // .apollo.decision.ObjectDecision.ObjectType type = 3; + if (this->type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 3, this->type(), target); + } + + // .apollo.decision.ObjectDecisionType decision = 4; + if (this->has_decision()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->_internal_decision(), deterministic, target); + } + + // repeated .apollo.decision.ObjectDecisionType object_decision = 5; + for (unsigned int i = 0, + n = static_cast(this->object_decision_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 5, this->object_decision(static_cast(i)), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.ObjectDecision) + return target; +} + +size_t ObjectDecision::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.ObjectDecision) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.decision.ObjectDecisionType object_decision = 5; + { + unsigned int count = static_cast(this->object_decision_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->object_decision(static_cast(i))); + } + } + + // string id = 2; + if (this->id().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->id()); + } + + // .apollo.prediction.PredictionObstacle prediction = 1; + if (this->has_prediction()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *prediction_); + } + + // .apollo.decision.ObjectDecisionType decision = 4; + if (this->has_decision()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *decision_); + } + + // .apollo.decision.ObjectDecision.ObjectType type = 3; + if (this->type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->type()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ObjectDecision::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.ObjectDecision) + GOOGLE_DCHECK_NE(&from, this); + const ObjectDecision* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.ObjectDecision) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.ObjectDecision) + MergeFrom(*source); + } +} + +void ObjectDecision::MergeFrom(const ObjectDecision& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.ObjectDecision) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + object_decision_.MergeFrom(from.object_decision_); + if (from.id().size() > 0) { + + id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.id_); + } + if (from.has_prediction()) { + mutable_prediction()->::apollo::prediction::PredictionObstacle::MergeFrom(from.prediction()); + } + if (from.has_decision()) { + mutable_decision()->::apollo::decision::ObjectDecisionType::MergeFrom(from.decision()); + } + if (from.type() != 0) { + set_type(from.type()); + } +} + +void ObjectDecision::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.ObjectDecision) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObjectDecision::CopyFrom(const ObjectDecision& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.ObjectDecision) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObjectDecision::IsInitialized() const { + return true; +} + +void ObjectDecision::Swap(ObjectDecision* other) { + if (other == this) return; + InternalSwap(other); +} +void ObjectDecision::InternalSwap(ObjectDecision* other) { + using std::swap; + CastToBase(&object_decision_)->InternalSwap(CastToBase(&other->object_decision_)); + id_.Swap(&other->id_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(prediction_, other->prediction_); + swap(decision_, other->decision_); + swap(type_, other->type_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ObjectDecision::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ObjectDecisions::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ObjectDecisions::kDecisionFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ObjectDecisions::ObjectDecisions() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectDecisions.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.ObjectDecisions) +} +ObjectDecisions::ObjectDecisions(const ObjectDecisions& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + decision_(from.decision_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:apollo.decision.ObjectDecisions) +} + +void ObjectDecisions::SharedCtor() { +} + +ObjectDecisions::~ObjectDecisions() { + // @@protoc_insertion_point(destructor:apollo.decision.ObjectDecisions) + SharedDtor(); +} + +void ObjectDecisions::SharedDtor() { +} + +void ObjectDecisions::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ObjectDecisions::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ObjectDecisions& ObjectDecisions::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectDecisions.base); + return *internal_default_instance(); +} + + +void ObjectDecisions::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.ObjectDecisions) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + decision_.Clear(); + _internal_metadata_.Clear(); +} + +bool ObjectDecisions::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.ObjectDecisions) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // repeated .apollo.decision.ObjectDecision decision = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_decision())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.ObjectDecisions) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.ObjectDecisions) + return false; +#undef DO_ +} + +void ObjectDecisions::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.ObjectDecisions) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.decision.ObjectDecision decision = 1; + for (unsigned int i = 0, + n = static_cast(this->decision_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, + this->decision(static_cast(i)), + output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.ObjectDecisions) +} + +::google::protobuf::uint8* ObjectDecisions::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.ObjectDecisions) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.decision.ObjectDecision decision = 1; + for (unsigned int i = 0, + n = static_cast(this->decision_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->decision(static_cast(i)), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.ObjectDecisions) + return target; +} + +size_t ObjectDecisions::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.ObjectDecisions) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.decision.ObjectDecision decision = 1; + { + unsigned int count = static_cast(this->decision_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->decision(static_cast(i))); + } + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ObjectDecisions::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.ObjectDecisions) + GOOGLE_DCHECK_NE(&from, this); + const ObjectDecisions* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.ObjectDecisions) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.ObjectDecisions) + MergeFrom(*source); + } +} + +void ObjectDecisions::MergeFrom(const ObjectDecisions& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.ObjectDecisions) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + decision_.MergeFrom(from.decision_); +} + +void ObjectDecisions::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.ObjectDecisions) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObjectDecisions::CopyFrom(const ObjectDecisions& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.ObjectDecisions) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObjectDecisions::IsInitialized() const { + return true; +} + +void ObjectDecisions::Swap(ObjectDecisions* other) { + if (other == this) return; + InternalSwap(other); +} +void ObjectDecisions::InternalSwap(ObjectDecisions* other) { + using std::swap; + CastToBase(&decision_)->InternalSwap(CastToBase(&other->decision_)); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ObjectDecisions::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void StopLine::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int StopLine::kLaneIdFieldNumber; +const int StopLine::kDistanceSFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +StopLine::StopLine() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_StopLine.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.StopLine) +} +StopLine::StopLine(const StopLine& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + lane_id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.lane_id().size() > 0) { + lane_id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.lane_id_); + } + distance_s_ = from.distance_s_; + // @@protoc_insertion_point(copy_constructor:apollo.decision.StopLine) +} + +void StopLine::SharedCtor() { + lane_id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + distance_s_ = 0; +} + +StopLine::~StopLine() { + // @@protoc_insertion_point(destructor:apollo.decision.StopLine) + SharedDtor(); +} + +void StopLine::SharedDtor() { + lane_id_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + +void StopLine::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* StopLine::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const StopLine& StopLine::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_StopLine.base); + return *internal_default_instance(); +} + + +void StopLine::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.StopLine) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + lane_id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + distance_s_ = 0; + _internal_metadata_.Clear(); +} + +bool StopLine::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.StopLine) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // string lane_id = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_lane_id())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->lane_id().data(), static_cast(this->lane_id().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.decision.StopLine.lane_id")); + } else { + goto handle_unusual; + } + break; + } + + // double distance_s = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &distance_s_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.StopLine) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.StopLine) + return false; +#undef DO_ +} + +void StopLine::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.StopLine) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // string lane_id = 1; + if (this->lane_id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->lane_id().data(), static_cast(this->lane_id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.StopLine.lane_id"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 1, this->lane_id(), output); + } + + // double distance_s = 2; + if (this->distance_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->distance_s(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.StopLine) +} + +::google::protobuf::uint8* StopLine::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.StopLine) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // string lane_id = 1; + if (this->lane_id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->lane_id().data(), static_cast(this->lane_id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.StopLine.lane_id"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 1, this->lane_id(), target); + } + + // double distance_s = 2; + if (this->distance_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->distance_s(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.StopLine) + return target; +} + +size_t StopLine::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.StopLine) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // string lane_id = 1; + if (this->lane_id().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->lane_id()); + } + + // double distance_s = 2; + if (this->distance_s() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void StopLine::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.StopLine) + GOOGLE_DCHECK_NE(&from, this); + const StopLine* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.StopLine) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.StopLine) + MergeFrom(*source); + } +} + +void StopLine::MergeFrom(const StopLine& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.StopLine) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.lane_id().size() > 0) { + + lane_id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.lane_id_); + } + if (from.distance_s() != 0) { + set_distance_s(from.distance_s()); + } +} + +void StopLine::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.StopLine) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void StopLine::CopyFrom(const StopLine& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.StopLine) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool StopLine::IsInitialized() const { + return true; +} + +void StopLine::Swap(StopLine* other) { + if (other == this) return; + InternalSwap(other); +} +void StopLine::InternalSwap(StopLine* other) { + using std::swap; + lane_id_.Swap(&other->lane_id_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(distance_s_, other->distance_s_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata StopLine::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void MainStop::InitAsDefaultInstance() { + ::apollo::decision::_MainStop_default_instance_._instance.get_mutable()->enforced_line_ = const_cast< ::apollo::decision::StopLine*>( + ::apollo::decision::StopLine::internal_default_instance()); + ::apollo::decision::_MainStop_default_instance_._instance.get_mutable()->preferred_start_ = const_cast< ::apollo::decision::StopLine*>( + ::apollo::decision::StopLine::internal_default_instance()); + ::apollo::decision::_MainStop_default_instance_._instance.get_mutable()->preferred_end_ = const_cast< ::apollo::decision::StopLine*>( + ::apollo::decision::StopLine::internal_default_instance()); + ::apollo::decision::_MainStop_default_instance_._instance.get_mutable()->stop_point_ = const_cast< ::apollo::common::PointENU*>( + ::apollo::common::PointENU::internal_default_instance()); +} +void MainStop::clear_stop_point() { + if (GetArenaNoVirtual() == NULL && stop_point_ != NULL) { + delete stop_point_; + } + stop_point_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int MainStop::kEnforcedLineFieldNumber; +const int MainStop::kPreferredStartFieldNumber; +const int MainStop::kPreferredEndFieldNumber; +const int MainStop::kReasonFieldNumber; +const int MainStop::kReasonCodeFieldNumber; +const int MainStop::kStopPointFieldNumber; +const int MainStop::kStopHeadingFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +MainStop::MainStop() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainStop.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.MainStop) +} +MainStop::MainStop(const MainStop& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + reason_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.reason().size() > 0) { + reason_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.reason_); + } + if (from.has_enforced_line()) { + enforced_line_ = new ::apollo::decision::StopLine(*from.enforced_line_); + } else { + enforced_line_ = NULL; + } + if (from.has_preferred_start()) { + preferred_start_ = new ::apollo::decision::StopLine(*from.preferred_start_); + } else { + preferred_start_ = NULL; + } + if (from.has_preferred_end()) { + preferred_end_ = new ::apollo::decision::StopLine(*from.preferred_end_); + } else { + preferred_end_ = NULL; + } + if (from.has_stop_point()) { + stop_point_ = new ::apollo::common::PointENU(*from.stop_point_); + } else { + stop_point_ = NULL; + } + ::memcpy(&stop_heading_, &from.stop_heading_, + static_cast(reinterpret_cast(&reason_code_) - + reinterpret_cast(&stop_heading_)) + sizeof(reason_code_)); + // @@protoc_insertion_point(copy_constructor:apollo.decision.MainStop) +} + +void MainStop::SharedCtor() { + reason_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&enforced_line_, 0, static_cast( + reinterpret_cast(&reason_code_) - + reinterpret_cast(&enforced_line_)) + sizeof(reason_code_)); +} + +MainStop::~MainStop() { + // @@protoc_insertion_point(destructor:apollo.decision.MainStop) + SharedDtor(); +} + +void MainStop::SharedDtor() { + reason_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (this != internal_default_instance()) delete enforced_line_; + if (this != internal_default_instance()) delete preferred_start_; + if (this != internal_default_instance()) delete preferred_end_; + if (this != internal_default_instance()) delete stop_point_; +} + +void MainStop::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* MainStop::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const MainStop& MainStop::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainStop.base); + return *internal_default_instance(); +} + + +void MainStop::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.MainStop) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + reason_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (GetArenaNoVirtual() == NULL && enforced_line_ != NULL) { + delete enforced_line_; + } + enforced_line_ = NULL; + if (GetArenaNoVirtual() == NULL && preferred_start_ != NULL) { + delete preferred_start_; + } + preferred_start_ = NULL; + if (GetArenaNoVirtual() == NULL && preferred_end_ != NULL) { + delete preferred_end_; + } + preferred_end_ = NULL; + if (GetArenaNoVirtual() == NULL && stop_point_ != NULL) { + delete stop_point_; + } + stop_point_ = NULL; + ::memset(&stop_heading_, 0, static_cast( + reinterpret_cast(&reason_code_) - + reinterpret_cast(&stop_heading_)) + sizeof(reason_code_)); + _internal_metadata_.Clear(); +} + +bool MainStop::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.MainStop) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.decision.StopLine enforced_line = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_enforced_line())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.StopLine preferred_start = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_preferred_start())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.StopLine preferred_end = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_preferred_end())); + } else { + goto handle_unusual; + } + break; + } + + // string reason = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_reason())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->reason().data(), static_cast(this->reason().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.decision.MainStop.reason")); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.StopReasonCode reason_code = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(40u /* 40 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_reason_code(static_cast< ::apollo::decision::StopReasonCode >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.PointENU stop_point = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(50u /* 50 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_stop_point())); + } else { + goto handle_unusual; + } + break; + } + + // double stop_heading = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &stop_heading_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.MainStop) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.MainStop) + return false; +#undef DO_ +} + +void MainStop::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.MainStop) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.StopLine enforced_line = 1; + if (this->has_enforced_line()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_enforced_line(), output); + } + + // .apollo.decision.StopLine preferred_start = 2; + if (this->has_preferred_start()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_preferred_start(), output); + } + + // .apollo.decision.StopLine preferred_end = 3; + if (this->has_preferred_end()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_preferred_end(), output); + } + + // string reason = 4; + if (this->reason().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->reason().data(), static_cast(this->reason().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.MainStop.reason"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 4, this->reason(), output); + } + + // .apollo.decision.StopReasonCode reason_code = 5; + if (this->reason_code() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 5, this->reason_code(), output); + } + + // .apollo.common.PointENU stop_point = 6; + if (this->has_stop_point()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 6, this->_internal_stop_point(), output); + } + + // double stop_heading = 7; + if (this->stop_heading() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->stop_heading(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.MainStop) +} + +::google::protobuf::uint8* MainStop::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.MainStop) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.StopLine enforced_line = 1; + if (this->has_enforced_line()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_enforced_line(), deterministic, target); + } + + // .apollo.decision.StopLine preferred_start = 2; + if (this->has_preferred_start()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_preferred_start(), deterministic, target); + } + + // .apollo.decision.StopLine preferred_end = 3; + if (this->has_preferred_end()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_preferred_end(), deterministic, target); + } + + // string reason = 4; + if (this->reason().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->reason().data(), static_cast(this->reason().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.MainStop.reason"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 4, this->reason(), target); + } + + // .apollo.decision.StopReasonCode reason_code = 5; + if (this->reason_code() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 5, this->reason_code(), target); + } + + // .apollo.common.PointENU stop_point = 6; + if (this->has_stop_point()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 6, this->_internal_stop_point(), deterministic, target); + } + + // double stop_heading = 7; + if (this->stop_heading() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->stop_heading(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.MainStop) + return target; +} + +size_t MainStop::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.MainStop) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // string reason = 4; + if (this->reason().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->reason()); + } + + // .apollo.decision.StopLine enforced_line = 1; + if (this->has_enforced_line()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *enforced_line_); + } + + // .apollo.decision.StopLine preferred_start = 2; + if (this->has_preferred_start()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *preferred_start_); + } + + // .apollo.decision.StopLine preferred_end = 3; + if (this->has_preferred_end()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *preferred_end_); + } + + // .apollo.common.PointENU stop_point = 6; + if (this->has_stop_point()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *stop_point_); + } + + // double stop_heading = 7; + if (this->stop_heading() != 0) { + total_size += 1 + 8; + } + + // .apollo.decision.StopReasonCode reason_code = 5; + if (this->reason_code() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->reason_code()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void MainStop::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.MainStop) + GOOGLE_DCHECK_NE(&from, this); + const MainStop* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.MainStop) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.MainStop) + MergeFrom(*source); + } +} + +void MainStop::MergeFrom(const MainStop& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.MainStop) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.reason().size() > 0) { + + reason_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.reason_); + } + if (from.has_enforced_line()) { + mutable_enforced_line()->::apollo::decision::StopLine::MergeFrom(from.enforced_line()); + } + if (from.has_preferred_start()) { + mutable_preferred_start()->::apollo::decision::StopLine::MergeFrom(from.preferred_start()); + } + if (from.has_preferred_end()) { + mutable_preferred_end()->::apollo::decision::StopLine::MergeFrom(from.preferred_end()); + } + if (from.has_stop_point()) { + mutable_stop_point()->::apollo::common::PointENU::MergeFrom(from.stop_point()); + } + if (from.stop_heading() != 0) { + set_stop_heading(from.stop_heading()); + } + if (from.reason_code() != 0) { + set_reason_code(from.reason_code()); + } +} + +void MainStop::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.MainStop) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void MainStop::CopyFrom(const MainStop& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.MainStop) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool MainStop::IsInitialized() const { + return true; +} + +void MainStop::Swap(MainStop* other) { + if (other == this) return; + InternalSwap(other); +} +void MainStop::InternalSwap(MainStop* other) { + using std::swap; + reason_.Swap(&other->reason_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(enforced_line_, other->enforced_line_); + swap(preferred_start_, other->preferred_start_); + swap(preferred_end_, other->preferred_end_); + swap(stop_point_, other->stop_point_); + swap(stop_heading_, other->stop_heading_); + swap(reason_code_, other->reason_code_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata MainStop::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void EmergencyStopHardBrake::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +EmergencyStopHardBrake::EmergencyStopHardBrake() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_EmergencyStopHardBrake.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.EmergencyStopHardBrake) +} +EmergencyStopHardBrake::EmergencyStopHardBrake(const EmergencyStopHardBrake& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:apollo.decision.EmergencyStopHardBrake) +} + +void EmergencyStopHardBrake::SharedCtor() { +} + +EmergencyStopHardBrake::~EmergencyStopHardBrake() { + // @@protoc_insertion_point(destructor:apollo.decision.EmergencyStopHardBrake) + SharedDtor(); +} + +void EmergencyStopHardBrake::SharedDtor() { +} + +void EmergencyStopHardBrake::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* EmergencyStopHardBrake::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const EmergencyStopHardBrake& EmergencyStopHardBrake::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_EmergencyStopHardBrake.base); + return *internal_default_instance(); +} + + +void EmergencyStopHardBrake::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.EmergencyStopHardBrake) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _internal_metadata_.Clear(); +} + +bool EmergencyStopHardBrake::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.EmergencyStopHardBrake) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.EmergencyStopHardBrake) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.EmergencyStopHardBrake) + return false; +#undef DO_ +} + +void EmergencyStopHardBrake::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.EmergencyStopHardBrake) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.EmergencyStopHardBrake) +} + +::google::protobuf::uint8* EmergencyStopHardBrake::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.EmergencyStopHardBrake) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.EmergencyStopHardBrake) + return target; +} + +size_t EmergencyStopHardBrake::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.EmergencyStopHardBrake) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void EmergencyStopHardBrake::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.EmergencyStopHardBrake) + GOOGLE_DCHECK_NE(&from, this); + const EmergencyStopHardBrake* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.EmergencyStopHardBrake) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.EmergencyStopHardBrake) + MergeFrom(*source); + } +} + +void EmergencyStopHardBrake::MergeFrom(const EmergencyStopHardBrake& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.EmergencyStopHardBrake) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + +} + +void EmergencyStopHardBrake::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.EmergencyStopHardBrake) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void EmergencyStopHardBrake::CopyFrom(const EmergencyStopHardBrake& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.EmergencyStopHardBrake) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool EmergencyStopHardBrake::IsInitialized() const { + return true; +} + +void EmergencyStopHardBrake::Swap(EmergencyStopHardBrake* other) { + if (other == this) return; + InternalSwap(other); +} +void EmergencyStopHardBrake::InternalSwap(EmergencyStopHardBrake* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata EmergencyStopHardBrake::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void EmergencyStopCruiseToStop::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +EmergencyStopCruiseToStop::EmergencyStopCruiseToStop() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_EmergencyStopCruiseToStop.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.EmergencyStopCruiseToStop) +} +EmergencyStopCruiseToStop::EmergencyStopCruiseToStop(const EmergencyStopCruiseToStop& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:apollo.decision.EmergencyStopCruiseToStop) +} + +void EmergencyStopCruiseToStop::SharedCtor() { +} + +EmergencyStopCruiseToStop::~EmergencyStopCruiseToStop() { + // @@protoc_insertion_point(destructor:apollo.decision.EmergencyStopCruiseToStop) + SharedDtor(); +} + +void EmergencyStopCruiseToStop::SharedDtor() { +} + +void EmergencyStopCruiseToStop::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* EmergencyStopCruiseToStop::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const EmergencyStopCruiseToStop& EmergencyStopCruiseToStop::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_EmergencyStopCruiseToStop.base); + return *internal_default_instance(); +} + + +void EmergencyStopCruiseToStop::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.EmergencyStopCruiseToStop) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _internal_metadata_.Clear(); +} + +bool EmergencyStopCruiseToStop::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.EmergencyStopCruiseToStop) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.EmergencyStopCruiseToStop) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.EmergencyStopCruiseToStop) + return false; +#undef DO_ +} + +void EmergencyStopCruiseToStop::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.EmergencyStopCruiseToStop) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.EmergencyStopCruiseToStop) +} + +::google::protobuf::uint8* EmergencyStopCruiseToStop::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.EmergencyStopCruiseToStop) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.EmergencyStopCruiseToStop) + return target; +} + +size_t EmergencyStopCruiseToStop::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.EmergencyStopCruiseToStop) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void EmergencyStopCruiseToStop::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.EmergencyStopCruiseToStop) + GOOGLE_DCHECK_NE(&from, this); + const EmergencyStopCruiseToStop* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.EmergencyStopCruiseToStop) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.EmergencyStopCruiseToStop) + MergeFrom(*source); + } +} + +void EmergencyStopCruiseToStop::MergeFrom(const EmergencyStopCruiseToStop& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.EmergencyStopCruiseToStop) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + +} + +void EmergencyStopCruiseToStop::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.EmergencyStopCruiseToStop) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void EmergencyStopCruiseToStop::CopyFrom(const EmergencyStopCruiseToStop& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.EmergencyStopCruiseToStop) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool EmergencyStopCruiseToStop::IsInitialized() const { + return true; +} + +void EmergencyStopCruiseToStop::Swap(EmergencyStopCruiseToStop* other) { + if (other == this) return; + InternalSwap(other); +} +void EmergencyStopCruiseToStop::InternalSwap(EmergencyStopCruiseToStop* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata EmergencyStopCruiseToStop::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void MainEmergencyStop::InitAsDefaultInstance() { + ::apollo::decision::_MainEmergencyStop_default_instance_.hard_brake_ = const_cast< ::apollo::decision::EmergencyStopHardBrake*>( + ::apollo::decision::EmergencyStopHardBrake::internal_default_instance()); + ::apollo::decision::_MainEmergencyStop_default_instance_.cruise_to_stop_ = const_cast< ::apollo::decision::EmergencyStopCruiseToStop*>( + ::apollo::decision::EmergencyStopCruiseToStop::internal_default_instance()); +} +void MainEmergencyStop::set_allocated_hard_brake(::apollo::decision::EmergencyStopHardBrake* hard_brake) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_task(); + if (hard_brake) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + hard_brake = ::google::protobuf::internal::GetOwnedMessage( + message_arena, hard_brake, submessage_arena); + } + set_has_hard_brake(); + task_.hard_brake_ = hard_brake; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainEmergencyStop.hard_brake) +} +void MainEmergencyStop::set_allocated_cruise_to_stop(::apollo::decision::EmergencyStopCruiseToStop* cruise_to_stop) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_task(); + if (cruise_to_stop) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + cruise_to_stop = ::google::protobuf::internal::GetOwnedMessage( + message_arena, cruise_to_stop, submessage_arena); + } + set_has_cruise_to_stop(); + task_.cruise_to_stop_ = cruise_to_stop; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainEmergencyStop.cruise_to_stop) +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int MainEmergencyStop::kReasonFieldNumber; +const int MainEmergencyStop::kReasonCodeFieldNumber; +const int MainEmergencyStop::kHardBrakeFieldNumber; +const int MainEmergencyStop::kCruiseToStopFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +MainEmergencyStop::MainEmergencyStop() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainEmergencyStop.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.MainEmergencyStop) +} +MainEmergencyStop::MainEmergencyStop(const MainEmergencyStop& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + reason_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.reason().size() > 0) { + reason_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.reason_); + } + reason_code_ = from.reason_code_; + clear_has_task(); + switch (from.task_case()) { + case kHardBrake: { + mutable_hard_brake()->::apollo::decision::EmergencyStopHardBrake::MergeFrom(from.hard_brake()); + break; + } + case kCruiseToStop: { + mutable_cruise_to_stop()->::apollo::decision::EmergencyStopCruiseToStop::MergeFrom(from.cruise_to_stop()); + break; + } + case TASK_NOT_SET: { + break; + } + } + // @@protoc_insertion_point(copy_constructor:apollo.decision.MainEmergencyStop) +} + +void MainEmergencyStop::SharedCtor() { + reason_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + reason_code_ = 0; + clear_has_task(); +} + +MainEmergencyStop::~MainEmergencyStop() { + // @@protoc_insertion_point(destructor:apollo.decision.MainEmergencyStop) + SharedDtor(); +} + +void MainEmergencyStop::SharedDtor() { + reason_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (has_task()) { + clear_task(); + } +} + +void MainEmergencyStop::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* MainEmergencyStop::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const MainEmergencyStop& MainEmergencyStop::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainEmergencyStop.base); + return *internal_default_instance(); +} + + +void MainEmergencyStop::clear_task() { +// @@protoc_insertion_point(one_of_clear_start:apollo.decision.MainEmergencyStop) + switch (task_case()) { + case kHardBrake: { + delete task_.hard_brake_; + break; + } + case kCruiseToStop: { + delete task_.cruise_to_stop_; + break; + } + case TASK_NOT_SET: { + break; + } + } + _oneof_case_[0] = TASK_NOT_SET; +} + + +void MainEmergencyStop::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.MainEmergencyStop) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + reason_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + reason_code_ = 0; + clear_task(); + _internal_metadata_.Clear(); +} + +bool MainEmergencyStop::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.MainEmergencyStop) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // string reason = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_reason())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->reason().data(), static_cast(this->reason().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.decision.MainEmergencyStop.reason")); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.MainEmergencyStop.ReasonCode reason_code = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_reason_code(static_cast< ::apollo::decision::MainEmergencyStop_ReasonCode >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.EmergencyStopHardBrake hard_brake = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_hard_brake())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.EmergencyStopCruiseToStop cruise_to_stop = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_cruise_to_stop())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.MainEmergencyStop) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.MainEmergencyStop) + return false; +#undef DO_ +} + +void MainEmergencyStop::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.MainEmergencyStop) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // string reason = 1; + if (this->reason().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->reason().data(), static_cast(this->reason().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.MainEmergencyStop.reason"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 1, this->reason(), output); + } + + // .apollo.decision.MainEmergencyStop.ReasonCode reason_code = 2; + if (this->reason_code() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 2, this->reason_code(), output); + } + + // .apollo.decision.EmergencyStopHardBrake hard_brake = 3; + if (has_hard_brake()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_hard_brake(), output); + } + + // .apollo.decision.EmergencyStopCruiseToStop cruise_to_stop = 4; + if (has_cruise_to_stop()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, this->_internal_cruise_to_stop(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.MainEmergencyStop) +} + +::google::protobuf::uint8* MainEmergencyStop::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.MainEmergencyStop) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // string reason = 1; + if (this->reason().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->reason().data(), static_cast(this->reason().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.MainEmergencyStop.reason"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 1, this->reason(), target); + } + + // .apollo.decision.MainEmergencyStop.ReasonCode reason_code = 2; + if (this->reason_code() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 2, this->reason_code(), target); + } + + // .apollo.decision.EmergencyStopHardBrake hard_brake = 3; + if (has_hard_brake()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_hard_brake(), deterministic, target); + } + + // .apollo.decision.EmergencyStopCruiseToStop cruise_to_stop = 4; + if (has_cruise_to_stop()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->_internal_cruise_to_stop(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.MainEmergencyStop) + return target; +} + +size_t MainEmergencyStop::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.MainEmergencyStop) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // string reason = 1; + if (this->reason().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->reason()); + } + + // .apollo.decision.MainEmergencyStop.ReasonCode reason_code = 2; + if (this->reason_code() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->reason_code()); + } + + switch (task_case()) { + // .apollo.decision.EmergencyStopHardBrake hard_brake = 3; + case kHardBrake: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *task_.hard_brake_); + break; + } + // .apollo.decision.EmergencyStopCruiseToStop cruise_to_stop = 4; + case kCruiseToStop: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *task_.cruise_to_stop_); + break; + } + case TASK_NOT_SET: { + break; + } + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void MainEmergencyStop::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.MainEmergencyStop) + GOOGLE_DCHECK_NE(&from, this); + const MainEmergencyStop* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.MainEmergencyStop) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.MainEmergencyStop) + MergeFrom(*source); + } +} + +void MainEmergencyStop::MergeFrom(const MainEmergencyStop& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.MainEmergencyStop) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.reason().size() > 0) { + + reason_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.reason_); + } + if (from.reason_code() != 0) { + set_reason_code(from.reason_code()); + } + switch (from.task_case()) { + case kHardBrake: { + mutable_hard_brake()->::apollo::decision::EmergencyStopHardBrake::MergeFrom(from.hard_brake()); + break; + } + case kCruiseToStop: { + mutable_cruise_to_stop()->::apollo::decision::EmergencyStopCruiseToStop::MergeFrom(from.cruise_to_stop()); + break; + } + case TASK_NOT_SET: { + break; + } + } +} + +void MainEmergencyStop::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.MainEmergencyStop) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void MainEmergencyStop::CopyFrom(const MainEmergencyStop& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.MainEmergencyStop) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool MainEmergencyStop::IsInitialized() const { + return true; +} + +void MainEmergencyStop::Swap(MainEmergencyStop* other) { + if (other == this) return; + InternalSwap(other); +} +void MainEmergencyStop::InternalSwap(MainEmergencyStop* other) { + using std::swap; + reason_.Swap(&other->reason_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(reason_code_, other->reason_code_); + swap(task_, other->task_); + swap(_oneof_case_[0], other->_oneof_case_[0]); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata MainEmergencyStop::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void MainCruise::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +MainCruise::MainCruise() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainCruise.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.MainCruise) +} +MainCruise::MainCruise(const MainCruise& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:apollo.decision.MainCruise) +} + +void MainCruise::SharedCtor() { +} + +MainCruise::~MainCruise() { + // @@protoc_insertion_point(destructor:apollo.decision.MainCruise) + SharedDtor(); +} + +void MainCruise::SharedDtor() { +} + +void MainCruise::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* MainCruise::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const MainCruise& MainCruise::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainCruise.base); + return *internal_default_instance(); +} + + +void MainCruise::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.MainCruise) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _internal_metadata_.Clear(); +} + +bool MainCruise::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.MainCruise) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.MainCruise) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.MainCruise) + return false; +#undef DO_ +} + +void MainCruise::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.MainCruise) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.MainCruise) +} + +::google::protobuf::uint8* MainCruise::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.MainCruise) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.MainCruise) + return target; +} + +size_t MainCruise::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.MainCruise) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void MainCruise::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.MainCruise) + GOOGLE_DCHECK_NE(&from, this); + const MainCruise* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.MainCruise) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.MainCruise) + MergeFrom(*source); + } +} + +void MainCruise::MergeFrom(const MainCruise& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.MainCruise) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + +} + +void MainCruise::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.MainCruise) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void MainCruise::CopyFrom(const MainCruise& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.MainCruise) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool MainCruise::IsInitialized() const { + return true; +} + +void MainCruise::Swap(MainCruise* other) { + if (other == this) return; + InternalSwap(other); +} +void MainCruise::InternalSwap(MainCruise* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata MainCruise::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void MainChangeLane::InitAsDefaultInstance() { + ::apollo::decision::_MainChangeLane_default_instance_._instance.get_mutable()->default_lane_stop_ = const_cast< ::apollo::decision::MainStop*>( + ::apollo::decision::MainStop::internal_default_instance()); + ::apollo::decision::_MainChangeLane_default_instance_._instance.get_mutable()->target_lane_stop_ = const_cast< ::apollo::decision::MainStop*>( + ::apollo::decision::MainStop::internal_default_instance()); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int MainChangeLane::kTypeFieldNumber; +const int MainChangeLane::kDefaultLaneFieldNumber; +const int MainChangeLane::kDefaultLaneStopFieldNumber; +const int MainChangeLane::kTargetLaneStopFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +MainChangeLane::MainChangeLane() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainChangeLane.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.MainChangeLane) +} +MainChangeLane::MainChangeLane(const MainChangeLane& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + default_lane_(from.default_lane_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_default_lane_stop()) { + default_lane_stop_ = new ::apollo::decision::MainStop(*from.default_lane_stop_); + } else { + default_lane_stop_ = NULL; + } + if (from.has_target_lane_stop()) { + target_lane_stop_ = new ::apollo::decision::MainStop(*from.target_lane_stop_); + } else { + target_lane_stop_ = NULL; + } + type_ = from.type_; + // @@protoc_insertion_point(copy_constructor:apollo.decision.MainChangeLane) +} + +void MainChangeLane::SharedCtor() { + ::memset(&default_lane_stop_, 0, static_cast( + reinterpret_cast(&type_) - + reinterpret_cast(&default_lane_stop_)) + sizeof(type_)); +} + +MainChangeLane::~MainChangeLane() { + // @@protoc_insertion_point(destructor:apollo.decision.MainChangeLane) + SharedDtor(); +} + +void MainChangeLane::SharedDtor() { + if (this != internal_default_instance()) delete default_lane_stop_; + if (this != internal_default_instance()) delete target_lane_stop_; +} + +void MainChangeLane::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* MainChangeLane::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const MainChangeLane& MainChangeLane::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainChangeLane.base); + return *internal_default_instance(); +} + + +void MainChangeLane::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.MainChangeLane) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + default_lane_.Clear(); + if (GetArenaNoVirtual() == NULL && default_lane_stop_ != NULL) { + delete default_lane_stop_; + } + default_lane_stop_ = NULL; + if (GetArenaNoVirtual() == NULL && target_lane_stop_ != NULL) { + delete target_lane_stop_; + } + target_lane_stop_ = NULL; + type_ = 0; + _internal_metadata_.Clear(); +} + +bool MainChangeLane::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.MainChangeLane) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.decision.MainChangeLane.Type type = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_type(static_cast< ::apollo::decision::MainChangeLane_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.decision.TargetLane default_lane = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_default_lane())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.MainStop default_lane_stop = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_default_lane_stop())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.MainStop target_lane_stop = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_target_lane_stop())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.MainChangeLane) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.MainChangeLane) + return false; +#undef DO_ +} + +void MainChangeLane::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.MainChangeLane) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.MainChangeLane.Type type = 1; + if (this->type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->type(), output); + } + + // repeated .apollo.decision.TargetLane default_lane = 2; + for (unsigned int i = 0, + n = static_cast(this->default_lane_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, + this->default_lane(static_cast(i)), + output); + } + + // .apollo.decision.MainStop default_lane_stop = 3; + if (this->has_default_lane_stop()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_default_lane_stop(), output); + } + + // .apollo.decision.MainStop target_lane_stop = 4; + if (this->has_target_lane_stop()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, this->_internal_target_lane_stop(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.MainChangeLane) +} + +::google::protobuf::uint8* MainChangeLane::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.MainChangeLane) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.MainChangeLane.Type type = 1; + if (this->type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->type(), target); + } + + // repeated .apollo.decision.TargetLane default_lane = 2; + for (unsigned int i = 0, + n = static_cast(this->default_lane_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->default_lane(static_cast(i)), deterministic, target); + } + + // .apollo.decision.MainStop default_lane_stop = 3; + if (this->has_default_lane_stop()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_default_lane_stop(), deterministic, target); + } + + // .apollo.decision.MainStop target_lane_stop = 4; + if (this->has_target_lane_stop()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->_internal_target_lane_stop(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.MainChangeLane) + return target; +} + +size_t MainChangeLane::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.MainChangeLane) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.decision.TargetLane default_lane = 2; + { + unsigned int count = static_cast(this->default_lane_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->default_lane(static_cast(i))); + } + } + + // .apollo.decision.MainStop default_lane_stop = 3; + if (this->has_default_lane_stop()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *default_lane_stop_); + } + + // .apollo.decision.MainStop target_lane_stop = 4; + if (this->has_target_lane_stop()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *target_lane_stop_); + } + + // .apollo.decision.MainChangeLane.Type type = 1; + if (this->type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->type()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void MainChangeLane::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.MainChangeLane) + GOOGLE_DCHECK_NE(&from, this); + const MainChangeLane* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.MainChangeLane) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.MainChangeLane) + MergeFrom(*source); + } +} + +void MainChangeLane::MergeFrom(const MainChangeLane& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.MainChangeLane) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + default_lane_.MergeFrom(from.default_lane_); + if (from.has_default_lane_stop()) { + mutable_default_lane_stop()->::apollo::decision::MainStop::MergeFrom(from.default_lane_stop()); + } + if (from.has_target_lane_stop()) { + mutable_target_lane_stop()->::apollo::decision::MainStop::MergeFrom(from.target_lane_stop()); + } + if (from.type() != 0) { + set_type(from.type()); + } +} + +void MainChangeLane::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.MainChangeLane) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void MainChangeLane::CopyFrom(const MainChangeLane& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.MainChangeLane) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool MainChangeLane::IsInitialized() const { + return true; +} + +void MainChangeLane::Swap(MainChangeLane* other) { + if (other == this) return; + InternalSwap(other); +} +void MainChangeLane::InternalSwap(MainChangeLane* other) { + using std::swap; + CastToBase(&default_lane_)->InternalSwap(CastToBase(&other->default_lane_)); + swap(default_lane_stop_, other->default_lane_stop_); + swap(target_lane_stop_, other->target_lane_stop_); + swap(type_, other->type_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata MainChangeLane::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void MainMissionComplete::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +MainMissionComplete::MainMissionComplete() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainMissionComplete.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.MainMissionComplete) +} +MainMissionComplete::MainMissionComplete(const MainMissionComplete& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:apollo.decision.MainMissionComplete) +} + +void MainMissionComplete::SharedCtor() { +} + +MainMissionComplete::~MainMissionComplete() { + // @@protoc_insertion_point(destructor:apollo.decision.MainMissionComplete) + SharedDtor(); +} + +void MainMissionComplete::SharedDtor() { +} + +void MainMissionComplete::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* MainMissionComplete::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const MainMissionComplete& MainMissionComplete::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainMissionComplete.base); + return *internal_default_instance(); +} + + +void MainMissionComplete::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.MainMissionComplete) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _internal_metadata_.Clear(); +} + +bool MainMissionComplete::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.MainMissionComplete) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.MainMissionComplete) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.MainMissionComplete) + return false; +#undef DO_ +} + +void MainMissionComplete::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.MainMissionComplete) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.MainMissionComplete) +} + +::google::protobuf::uint8* MainMissionComplete::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.MainMissionComplete) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.MainMissionComplete) + return target; +} + +size_t MainMissionComplete::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.MainMissionComplete) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void MainMissionComplete::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.MainMissionComplete) + GOOGLE_DCHECK_NE(&from, this); + const MainMissionComplete* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.MainMissionComplete) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.MainMissionComplete) + MergeFrom(*source); + } +} + +void MainMissionComplete::MergeFrom(const MainMissionComplete& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.MainMissionComplete) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + +} + +void MainMissionComplete::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.MainMissionComplete) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void MainMissionComplete::CopyFrom(const MainMissionComplete& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.MainMissionComplete) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool MainMissionComplete::IsInitialized() const { + return true; +} + +void MainMissionComplete::Swap(MainMissionComplete* other) { + if (other == this) return; + InternalSwap(other); +} +void MainMissionComplete::InternalSwap(MainMissionComplete* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata MainMissionComplete::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void MainNotReady::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int MainNotReady::kReasonFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +MainNotReady::MainNotReady() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainNotReady.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.MainNotReady) +} +MainNotReady::MainNotReady(const MainNotReady& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + reason_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.reason().size() > 0) { + reason_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.reason_); + } + // @@protoc_insertion_point(copy_constructor:apollo.decision.MainNotReady) +} + +void MainNotReady::SharedCtor() { + reason_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + +MainNotReady::~MainNotReady() { + // @@protoc_insertion_point(destructor:apollo.decision.MainNotReady) + SharedDtor(); +} + +void MainNotReady::SharedDtor() { + reason_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + +void MainNotReady::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* MainNotReady::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const MainNotReady& MainNotReady::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainNotReady.base); + return *internal_default_instance(); +} + + +void MainNotReady::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.MainNotReady) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + reason_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + _internal_metadata_.Clear(); +} + +bool MainNotReady::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.MainNotReady) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // string reason = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_reason())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->reason().data(), static_cast(this->reason().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.decision.MainNotReady.reason")); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.MainNotReady) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.MainNotReady) + return false; +#undef DO_ +} + +void MainNotReady::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.MainNotReady) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // string reason = 1; + if (this->reason().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->reason().data(), static_cast(this->reason().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.MainNotReady.reason"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 1, this->reason(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.MainNotReady) +} + +::google::protobuf::uint8* MainNotReady::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.MainNotReady) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // string reason = 1; + if (this->reason().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->reason().data(), static_cast(this->reason().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.MainNotReady.reason"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 1, this->reason(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.MainNotReady) + return target; +} + +size_t MainNotReady::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.MainNotReady) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // string reason = 1; + if (this->reason().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->reason()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void MainNotReady::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.MainNotReady) + GOOGLE_DCHECK_NE(&from, this); + const MainNotReady* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.MainNotReady) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.MainNotReady) + MergeFrom(*source); + } +} + +void MainNotReady::MergeFrom(const MainNotReady& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.MainNotReady) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.reason().size() > 0) { + + reason_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.reason_); + } +} + +void MainNotReady::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.MainNotReady) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void MainNotReady::CopyFrom(const MainNotReady& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.MainNotReady) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool MainNotReady::IsInitialized() const { + return true; +} + +void MainNotReady::Swap(MainNotReady* other) { + if (other == this) return; + InternalSwap(other); +} +void MainNotReady::InternalSwap(MainNotReady* other) { + using std::swap; + reason_.Swap(&other->reason_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata MainNotReady::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void MainParking::InitAsDefaultInstance() { + ::apollo::decision::_MainParking_default_instance_._instance.get_mutable()->stop_point_ = const_cast< ::apollo::common::PointENU*>( + ::apollo::common::PointENU::internal_default_instance()); +} +void MainParking::clear_stop_point() { + if (GetArenaNoVirtual() == NULL && stop_point_ != NULL) { + delete stop_point_; + } + stop_point_ = NULL; +} +void MainParking::clear_parking_polygon() { + parking_polygon_.Clear(); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int MainParking::kTypeFieldNumber; +const int MainParking::kHeadingFieldNumber; +const int MainParking::kStopPointFieldNumber; +const int MainParking::kParkingPolygonFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +MainParking::MainParking() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainParking.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.MainParking) +} +MainParking::MainParking(const MainParking& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + parking_polygon_(from.parking_polygon_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_stop_point()) { + stop_point_ = new ::apollo::common::PointENU(*from.stop_point_); + } else { + stop_point_ = NULL; + } + ::memcpy(&heading_, &from.heading_, + static_cast(reinterpret_cast(&type_) - + reinterpret_cast(&heading_)) + sizeof(type_)); + // @@protoc_insertion_point(copy_constructor:apollo.decision.MainParking) +} + +void MainParking::SharedCtor() { + ::memset(&stop_point_, 0, static_cast( + reinterpret_cast(&type_) - + reinterpret_cast(&stop_point_)) + sizeof(type_)); +} + +MainParking::~MainParking() { + // @@protoc_insertion_point(destructor:apollo.decision.MainParking) + SharedDtor(); +} + +void MainParking::SharedDtor() { + if (this != internal_default_instance()) delete stop_point_; +} + +void MainParking::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* MainParking::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const MainParking& MainParking::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainParking.base); + return *internal_default_instance(); +} + + +void MainParking::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.MainParking) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + parking_polygon_.Clear(); + if (GetArenaNoVirtual() == NULL && stop_point_ != NULL) { + delete stop_point_; + } + stop_point_ = NULL; + ::memset(&heading_, 0, static_cast( + reinterpret_cast(&type_) - + reinterpret_cast(&heading_)) + sizeof(type_)); + _internal_metadata_.Clear(); +} + +bool MainParking::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.MainParking) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.decision.MainParking.Type type = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_type(static_cast< ::apollo::decision::MainParking_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // double heading = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &heading_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.PointENU stop_point = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_stop_point())); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.common.PointENU parking_polygon = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_parking_polygon())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.MainParking) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.MainParking) + return false; +#undef DO_ +} + +void MainParking::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.MainParking) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.MainParking.Type type = 1; + if (this->type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->type(), output); + } + + // double heading = 2; + if (this->heading() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->heading(), output); + } + + // .apollo.common.PointENU stop_point = 3; + if (this->has_stop_point()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_stop_point(), output); + } + + // repeated .apollo.common.PointENU parking_polygon = 4; + for (unsigned int i = 0, + n = static_cast(this->parking_polygon_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, + this->parking_polygon(static_cast(i)), + output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.MainParking) +} + +::google::protobuf::uint8* MainParking::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.MainParking) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.MainParking.Type type = 1; + if (this->type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->type(), target); + } + + // double heading = 2; + if (this->heading() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->heading(), target); + } + + // .apollo.common.PointENU stop_point = 3; + if (this->has_stop_point()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_stop_point(), deterministic, target); + } + + // repeated .apollo.common.PointENU parking_polygon = 4; + for (unsigned int i = 0, + n = static_cast(this->parking_polygon_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->parking_polygon(static_cast(i)), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.MainParking) + return target; +} + +size_t MainParking::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.MainParking) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.common.PointENU parking_polygon = 4; + { + unsigned int count = static_cast(this->parking_polygon_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->parking_polygon(static_cast(i))); + } + } + + // .apollo.common.PointENU stop_point = 3; + if (this->has_stop_point()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *stop_point_); + } + + // double heading = 2; + if (this->heading() != 0) { + total_size += 1 + 8; + } + + // .apollo.decision.MainParking.Type type = 1; + if (this->type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->type()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void MainParking::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.MainParking) + GOOGLE_DCHECK_NE(&from, this); + const MainParking* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.MainParking) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.MainParking) + MergeFrom(*source); + } +} + +void MainParking::MergeFrom(const MainParking& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.MainParking) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + parking_polygon_.MergeFrom(from.parking_polygon_); + if (from.has_stop_point()) { + mutable_stop_point()->::apollo::common::PointENU::MergeFrom(from.stop_point()); + } + if (from.heading() != 0) { + set_heading(from.heading()); + } + if (from.type() != 0) { + set_type(from.type()); + } +} + +void MainParking::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.MainParking) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void MainParking::CopyFrom(const MainParking& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.MainParking) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool MainParking::IsInitialized() const { + return true; +} + +void MainParking::Swap(MainParking* other) { + if (other == this) return; + InternalSwap(other); +} +void MainParking::InternalSwap(MainParking* other) { + using std::swap; + CastToBase(&parking_polygon_)->InternalSwap(CastToBase(&other->parking_polygon_)); + swap(stop_point_, other->stop_point_); + swap(heading_, other->heading_); + swap(type_, other->type_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata MainParking::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void MainDecision::InitAsDefaultInstance() { + ::apollo::decision::_MainDecision_default_instance_.cruise_ = const_cast< ::apollo::decision::MainCruise*>( + ::apollo::decision::MainCruise::internal_default_instance()); + ::apollo::decision::_MainDecision_default_instance_.stop_ = const_cast< ::apollo::decision::MainStop*>( + ::apollo::decision::MainStop::internal_default_instance()); + ::apollo::decision::_MainDecision_default_instance_.estop_ = const_cast< ::apollo::decision::MainEmergencyStop*>( + ::apollo::decision::MainEmergencyStop::internal_default_instance()); + ::apollo::decision::_MainDecision_default_instance_.change_lane_ = const_cast< ::apollo::decision::MainChangeLane*>( + ::apollo::decision::MainChangeLane::internal_default_instance()); + ::apollo::decision::_MainDecision_default_instance_.mission_complete_ = const_cast< ::apollo::decision::MainMissionComplete*>( + ::apollo::decision::MainMissionComplete::internal_default_instance()); + ::apollo::decision::_MainDecision_default_instance_.not_ready_ = const_cast< ::apollo::decision::MainNotReady*>( + ::apollo::decision::MainNotReady::internal_default_instance()); + ::apollo::decision::_MainDecision_default_instance_.parking_ = const_cast< ::apollo::decision::MainParking*>( + ::apollo::decision::MainParking::internal_default_instance()); +} +void MainDecision::set_allocated_cruise(::apollo::decision::MainCruise* cruise) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_task(); + if (cruise) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + cruise = ::google::protobuf::internal::GetOwnedMessage( + message_arena, cruise, submessage_arena); + } + set_has_cruise(); + task_.cruise_ = cruise; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainDecision.cruise) +} +void MainDecision::set_allocated_stop(::apollo::decision::MainStop* stop) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_task(); + if (stop) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + stop = ::google::protobuf::internal::GetOwnedMessage( + message_arena, stop, submessage_arena); + } + set_has_stop(); + task_.stop_ = stop; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainDecision.stop) +} +void MainDecision::set_allocated_estop(::apollo::decision::MainEmergencyStop* estop) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_task(); + if (estop) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + estop = ::google::protobuf::internal::GetOwnedMessage( + message_arena, estop, submessage_arena); + } + set_has_estop(); + task_.estop_ = estop; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainDecision.estop) +} +void MainDecision::set_allocated_change_lane(::apollo::decision::MainChangeLane* change_lane) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_task(); + if (change_lane) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + change_lane = ::google::protobuf::internal::GetOwnedMessage( + message_arena, change_lane, submessage_arena); + } + set_has_change_lane(); + task_.change_lane_ = change_lane; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainDecision.change_lane) +} +void MainDecision::set_allocated_mission_complete(::apollo::decision::MainMissionComplete* mission_complete) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_task(); + if (mission_complete) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + mission_complete = ::google::protobuf::internal::GetOwnedMessage( + message_arena, mission_complete, submessage_arena); + } + set_has_mission_complete(); + task_.mission_complete_ = mission_complete; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainDecision.mission_complete) +} +void MainDecision::set_allocated_not_ready(::apollo::decision::MainNotReady* not_ready) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_task(); + if (not_ready) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + not_ready = ::google::protobuf::internal::GetOwnedMessage( + message_arena, not_ready, submessage_arena); + } + set_has_not_ready(); + task_.not_ready_ = not_ready; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainDecision.not_ready) +} +void MainDecision::set_allocated_parking(::apollo::decision::MainParking* parking) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + clear_task(); + if (parking) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + parking = ::google::protobuf::internal::GetOwnedMessage( + message_arena, parking, submessage_arena); + } + set_has_parking(); + task_.parking_ = parking; + } + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainDecision.parking) +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int MainDecision::kCruiseFieldNumber; +const int MainDecision::kStopFieldNumber; +const int MainDecision::kEstopFieldNumber; +const int MainDecision::kChangeLaneFieldNumber; +const int MainDecision::kMissionCompleteFieldNumber; +const int MainDecision::kNotReadyFieldNumber; +const int MainDecision::kParkingFieldNumber; +const int MainDecision::kTargetLaneFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +MainDecision::MainDecision() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainDecision.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.MainDecision) +} +MainDecision::MainDecision(const MainDecision& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + target_lane_(from.target_lane_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + clear_has_task(); + switch (from.task_case()) { + case kCruise: { + mutable_cruise()->::apollo::decision::MainCruise::MergeFrom(from.cruise()); + break; + } + case kStop: { + mutable_stop()->::apollo::decision::MainStop::MergeFrom(from.stop()); + break; + } + case kEstop: { + mutable_estop()->::apollo::decision::MainEmergencyStop::MergeFrom(from.estop()); + break; + } + case kChangeLane: { + mutable_change_lane()->::apollo::decision::MainChangeLane::MergeFrom(from.change_lane()); + break; + } + case kMissionComplete: { + mutable_mission_complete()->::apollo::decision::MainMissionComplete::MergeFrom(from.mission_complete()); + break; + } + case kNotReady: { + mutable_not_ready()->::apollo::decision::MainNotReady::MergeFrom(from.not_ready()); + break; + } + case kParking: { + mutable_parking()->::apollo::decision::MainParking::MergeFrom(from.parking()); + break; + } + case TASK_NOT_SET: { + break; + } + } + // @@protoc_insertion_point(copy_constructor:apollo.decision.MainDecision) +} + +void MainDecision::SharedCtor() { + clear_has_task(); +} + +MainDecision::~MainDecision() { + // @@protoc_insertion_point(destructor:apollo.decision.MainDecision) + SharedDtor(); +} + +void MainDecision::SharedDtor() { + if (has_task()) { + clear_task(); + } +} + +void MainDecision::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* MainDecision::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const MainDecision& MainDecision::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainDecision.base); + return *internal_default_instance(); +} + + +void MainDecision::clear_task() { +// @@protoc_insertion_point(one_of_clear_start:apollo.decision.MainDecision) + switch (task_case()) { + case kCruise: { + delete task_.cruise_; + break; + } + case kStop: { + delete task_.stop_; + break; + } + case kEstop: { + delete task_.estop_; + break; + } + case kChangeLane: { + delete task_.change_lane_; + break; + } + case kMissionComplete: { + delete task_.mission_complete_; + break; + } + case kNotReady: { + delete task_.not_ready_; + break; + } + case kParking: { + delete task_.parking_; + break; + } + case TASK_NOT_SET: { + break; + } + } + _oneof_case_[0] = TASK_NOT_SET; +} + + +void MainDecision::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.MainDecision) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + target_lane_.Clear(); + clear_task(); + _internal_metadata_.Clear(); +} + +bool MainDecision::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.MainDecision) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.decision.MainCruise cruise = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_cruise())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.MainStop stop = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_stop())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.MainEmergencyStop estop = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_estop())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.MainChangeLane change_lane = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_change_lane())); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.decision.TargetLane target_lane = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_target_lane())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.MainMissionComplete mission_complete = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(50u /* 50 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_mission_complete())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.MainNotReady not_ready = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(58u /* 58 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_not_ready())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.MainParking parking = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(66u /* 66 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_parking())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.MainDecision) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.MainDecision) + return false; +#undef DO_ +} + +void MainDecision::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.MainDecision) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.MainCruise cruise = 1; + if (has_cruise()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_cruise(), output); + } + + // .apollo.decision.MainStop stop = 2; + if (has_stop()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_stop(), output); + } + + // .apollo.decision.MainEmergencyStop estop = 3; + if (has_estop()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_estop(), output); + } + + // .apollo.decision.MainChangeLane change_lane = 4; + if (has_change_lane()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, this->_internal_change_lane(), output); + } + + // repeated .apollo.decision.TargetLane target_lane = 5; + for (unsigned int i = 0, + n = static_cast(this->target_lane_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, + this->target_lane(static_cast(i)), + output); + } + + // .apollo.decision.MainMissionComplete mission_complete = 6; + if (has_mission_complete()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 6, this->_internal_mission_complete(), output); + } + + // .apollo.decision.MainNotReady not_ready = 7; + if (has_not_ready()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 7, this->_internal_not_ready(), output); + } + + // .apollo.decision.MainParking parking = 8; + if (has_parking()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 8, this->_internal_parking(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.MainDecision) +} + +::google::protobuf::uint8* MainDecision::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.MainDecision) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.MainCruise cruise = 1; + if (has_cruise()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_cruise(), deterministic, target); + } + + // .apollo.decision.MainStop stop = 2; + if (has_stop()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_stop(), deterministic, target); + } + + // .apollo.decision.MainEmergencyStop estop = 3; + if (has_estop()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_estop(), deterministic, target); + } + + // .apollo.decision.MainChangeLane change_lane = 4; + if (has_change_lane()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->_internal_change_lane(), deterministic, target); + } + + // repeated .apollo.decision.TargetLane target_lane = 5; + for (unsigned int i = 0, + n = static_cast(this->target_lane_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 5, this->target_lane(static_cast(i)), deterministic, target); + } + + // .apollo.decision.MainMissionComplete mission_complete = 6; + if (has_mission_complete()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 6, this->_internal_mission_complete(), deterministic, target); + } + + // .apollo.decision.MainNotReady not_ready = 7; + if (has_not_ready()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 7, this->_internal_not_ready(), deterministic, target); + } + + // .apollo.decision.MainParking parking = 8; + if (has_parking()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 8, this->_internal_parking(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.MainDecision) + return target; +} + +size_t MainDecision::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.MainDecision) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.decision.TargetLane target_lane = 5; + { + unsigned int count = static_cast(this->target_lane_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->target_lane(static_cast(i))); + } + } + + switch (task_case()) { + // .apollo.decision.MainCruise cruise = 1; + case kCruise: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *task_.cruise_); + break; + } + // .apollo.decision.MainStop stop = 2; + case kStop: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *task_.stop_); + break; + } + // .apollo.decision.MainEmergencyStop estop = 3; + case kEstop: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *task_.estop_); + break; + } + // .apollo.decision.MainChangeLane change_lane = 4; + case kChangeLane: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *task_.change_lane_); + break; + } + // .apollo.decision.MainMissionComplete mission_complete = 6; + case kMissionComplete: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *task_.mission_complete_); + break; + } + // .apollo.decision.MainNotReady not_ready = 7; + case kNotReady: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *task_.not_ready_); + break; + } + // .apollo.decision.MainParking parking = 8; + case kParking: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *task_.parking_); + break; + } + case TASK_NOT_SET: { + break; + } + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void MainDecision::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.MainDecision) + GOOGLE_DCHECK_NE(&from, this); + const MainDecision* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.MainDecision) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.MainDecision) + MergeFrom(*source); + } +} + +void MainDecision::MergeFrom(const MainDecision& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.MainDecision) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + target_lane_.MergeFrom(from.target_lane_); + switch (from.task_case()) { + case kCruise: { + mutable_cruise()->::apollo::decision::MainCruise::MergeFrom(from.cruise()); + break; + } + case kStop: { + mutable_stop()->::apollo::decision::MainStop::MergeFrom(from.stop()); + break; + } + case kEstop: { + mutable_estop()->::apollo::decision::MainEmergencyStop::MergeFrom(from.estop()); + break; + } + case kChangeLane: { + mutable_change_lane()->::apollo::decision::MainChangeLane::MergeFrom(from.change_lane()); + break; + } + case kMissionComplete: { + mutable_mission_complete()->::apollo::decision::MainMissionComplete::MergeFrom(from.mission_complete()); + break; + } + case kNotReady: { + mutable_not_ready()->::apollo::decision::MainNotReady::MergeFrom(from.not_ready()); + break; + } + case kParking: { + mutable_parking()->::apollo::decision::MainParking::MergeFrom(from.parking()); + break; + } + case TASK_NOT_SET: { + break; + } + } +} + +void MainDecision::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.MainDecision) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void MainDecision::CopyFrom(const MainDecision& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.MainDecision) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool MainDecision::IsInitialized() const { + return true; +} + +void MainDecision::Swap(MainDecision* other) { + if (other == this) return; + InternalSwap(other); +} +void MainDecision::InternalSwap(MainDecision* other) { + using std::swap; + CastToBase(&target_lane_)->InternalSwap(CastToBase(&other->target_lane_)); + swap(task_, other->task_); + swap(_oneof_case_[0], other->_oneof_case_[0]); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata MainDecision::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void MasterVehicleDebug::InitAsDefaultInstance() { + ::apollo::decision::_MasterVehicleDebug_default_instance_._instance.get_mutable()->position_ = const_cast< ::apollo::common::PointENU*>( + ::apollo::common::PointENU::internal_default_instance()); + ::apollo::decision::_MasterVehicleDebug_default_instance_._instance.get_mutable()->route_s_range_ = const_cast< ::apollo::decision::Range*>( + ::apollo::decision::Range::internal_default_instance()); + ::apollo::decision::_MasterVehicleDebug_default_instance_._instance.get_mutable()->route_l_range_ = const_cast< ::apollo::decision::Range*>( + ::apollo::decision::Range::internal_default_instance()); +} +void MasterVehicleDebug::clear_position() { + if (GetArenaNoVirtual() == NULL && position_ != NULL) { + delete position_; + } + position_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int MasterVehicleDebug::kPositionFieldNumber; +const int MasterVehicleDebug::kCurrentLaneIdFieldNumber; +const int MasterVehicleDebug::kLaneSFieldNumber; +const int MasterVehicleDebug::kLaneLFieldNumber; +const int MasterVehicleDebug::kRouteSFieldNumber; +const int MasterVehicleDebug::kRouteLFieldNumber; +const int MasterVehicleDebug::kHeadingFieldNumber; +const int MasterVehicleDebug::kHeadingSpeedFieldNumber; +const int MasterVehicleDebug::kHeadingAccelerationFieldNumber; +const int MasterVehicleDebug::kRouteSRangeFieldNumber; +const int MasterVehicleDebug::kRouteLRangeFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +MasterVehicleDebug::MasterVehicleDebug() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MasterVehicleDebug.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.MasterVehicleDebug) +} +MasterVehicleDebug::MasterVehicleDebug(const MasterVehicleDebug& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + current_lane_id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.current_lane_id().size() > 0) { + current_lane_id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.current_lane_id_); + } + if (from.has_position()) { + position_ = new ::apollo::common::PointENU(*from.position_); + } else { + position_ = NULL; + } + if (from.has_route_s_range()) { + route_s_range_ = new ::apollo::decision::Range(*from.route_s_range_); + } else { + route_s_range_ = NULL; + } + if (from.has_route_l_range()) { + route_l_range_ = new ::apollo::decision::Range(*from.route_l_range_); + } else { + route_l_range_ = NULL; + } + ::memcpy(&lane_s_, &from.lane_s_, + static_cast(reinterpret_cast(&heading_acceleration_) - + reinterpret_cast(&lane_s_)) + sizeof(heading_acceleration_)); + // @@protoc_insertion_point(copy_constructor:apollo.decision.MasterVehicleDebug) +} + +void MasterVehicleDebug::SharedCtor() { + current_lane_id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&position_, 0, static_cast( + reinterpret_cast(&heading_acceleration_) - + reinterpret_cast(&position_)) + sizeof(heading_acceleration_)); +} + +MasterVehicleDebug::~MasterVehicleDebug() { + // @@protoc_insertion_point(destructor:apollo.decision.MasterVehicleDebug) + SharedDtor(); +} + +void MasterVehicleDebug::SharedDtor() { + current_lane_id_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (this != internal_default_instance()) delete position_; + if (this != internal_default_instance()) delete route_s_range_; + if (this != internal_default_instance()) delete route_l_range_; +} + +void MasterVehicleDebug::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* MasterVehicleDebug::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const MasterVehicleDebug& MasterVehicleDebug::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MasterVehicleDebug.base); + return *internal_default_instance(); +} + + +void MasterVehicleDebug::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.MasterVehicleDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + current_lane_id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (GetArenaNoVirtual() == NULL && position_ != NULL) { + delete position_; + } + position_ = NULL; + if (GetArenaNoVirtual() == NULL && route_s_range_ != NULL) { + delete route_s_range_; + } + route_s_range_ = NULL; + if (GetArenaNoVirtual() == NULL && route_l_range_ != NULL) { + delete route_l_range_; + } + route_l_range_ = NULL; + ::memset(&lane_s_, 0, static_cast( + reinterpret_cast(&heading_acceleration_) - + reinterpret_cast(&lane_s_)) + sizeof(heading_acceleration_)); + _internal_metadata_.Clear(); +} + +bool MasterVehicleDebug::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.MasterVehicleDebug) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.PointENU position = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_position())); + } else { + goto handle_unusual; + } + break; + } + + // string current_lane_id = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_current_lane_id())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->current_lane_id().data(), static_cast(this->current_lane_id().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.decision.MasterVehicleDebug.current_lane_id")); + } else { + goto handle_unusual; + } + break; + } + + // double lane_s = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lane_s_))); + } else { + goto handle_unusual; + } + break; + } + + // double lane_l = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lane_l_))); + } else { + goto handle_unusual; + } + break; + } + + // double route_s = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &route_s_))); + } else { + goto handle_unusual; + } + break; + } + + // double route_l = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &route_l_))); + } else { + goto handle_unusual; + } + break; + } + + // double heading = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &heading_))); + } else { + goto handle_unusual; + } + break; + } + + // double heading_speed = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(65u /* 65 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &heading_speed_))); + } else { + goto handle_unusual; + } + break; + } + + // double heading_acceleration = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(73u /* 73 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &heading_acceleration_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.Range route_s_range = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(82u /* 82 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_route_s_range())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.Range route_l_range = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(90u /* 90 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_route_l_range())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.MasterVehicleDebug) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.MasterVehicleDebug) + return false; +#undef DO_ +} + +void MasterVehicleDebug::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.MasterVehicleDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.PointENU position = 1; + if (this->has_position()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_position(), output); + } + + // string current_lane_id = 2; + if (this->current_lane_id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->current_lane_id().data(), static_cast(this->current_lane_id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.MasterVehicleDebug.current_lane_id"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 2, this->current_lane_id(), output); + } + + // double lane_s = 3; + if (this->lane_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->lane_s(), output); + } + + // double lane_l = 4; + if (this->lane_l() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->lane_l(), output); + } + + // double route_s = 5; + if (this->route_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->route_s(), output); + } + + // double route_l = 6; + if (this->route_l() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->route_l(), output); + } + + // double heading = 7; + if (this->heading() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->heading(), output); + } + + // double heading_speed = 8; + if (this->heading_speed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(8, this->heading_speed(), output); + } + + // double heading_acceleration = 9; + if (this->heading_acceleration() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->heading_acceleration(), output); + } + + // .apollo.decision.Range route_s_range = 10; + if (this->has_route_s_range()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 10, this->_internal_route_s_range(), output); + } + + // .apollo.decision.Range route_l_range = 11; + if (this->has_route_l_range()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 11, this->_internal_route_l_range(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.MasterVehicleDebug) +} + +::google::protobuf::uint8* MasterVehicleDebug::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.MasterVehicleDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.PointENU position = 1; + if (this->has_position()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_position(), deterministic, target); + } + + // string current_lane_id = 2; + if (this->current_lane_id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->current_lane_id().data(), static_cast(this->current_lane_id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.MasterVehicleDebug.current_lane_id"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 2, this->current_lane_id(), target); + } + + // double lane_s = 3; + if (this->lane_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->lane_s(), target); + } + + // double lane_l = 4; + if (this->lane_l() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->lane_l(), target); + } + + // double route_s = 5; + if (this->route_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->route_s(), target); + } + + // double route_l = 6; + if (this->route_l() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->route_l(), target); + } + + // double heading = 7; + if (this->heading() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->heading(), target); + } + + // double heading_speed = 8; + if (this->heading_speed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(8, this->heading_speed(), target); + } + + // double heading_acceleration = 9; + if (this->heading_acceleration() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->heading_acceleration(), target); + } + + // .apollo.decision.Range route_s_range = 10; + if (this->has_route_s_range()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 10, this->_internal_route_s_range(), deterministic, target); + } + + // .apollo.decision.Range route_l_range = 11; + if (this->has_route_l_range()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 11, this->_internal_route_l_range(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.MasterVehicleDebug) + return target; +} + +size_t MasterVehicleDebug::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.MasterVehicleDebug) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // string current_lane_id = 2; + if (this->current_lane_id().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->current_lane_id()); + } + + // .apollo.common.PointENU position = 1; + if (this->has_position()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *position_); + } + + // .apollo.decision.Range route_s_range = 10; + if (this->has_route_s_range()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *route_s_range_); + } + + // .apollo.decision.Range route_l_range = 11; + if (this->has_route_l_range()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *route_l_range_); + } + + // double lane_s = 3; + if (this->lane_s() != 0) { + total_size += 1 + 8; + } + + // double lane_l = 4; + if (this->lane_l() != 0) { + total_size += 1 + 8; + } + + // double route_s = 5; + if (this->route_s() != 0) { + total_size += 1 + 8; + } + + // double route_l = 6; + if (this->route_l() != 0) { + total_size += 1 + 8; + } + + // double heading = 7; + if (this->heading() != 0) { + total_size += 1 + 8; + } + + // double heading_speed = 8; + if (this->heading_speed() != 0) { + total_size += 1 + 8; + } + + // double heading_acceleration = 9; + if (this->heading_acceleration() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void MasterVehicleDebug::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.MasterVehicleDebug) + GOOGLE_DCHECK_NE(&from, this); + const MasterVehicleDebug* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.MasterVehicleDebug) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.MasterVehicleDebug) + MergeFrom(*source); + } +} + +void MasterVehicleDebug::MergeFrom(const MasterVehicleDebug& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.MasterVehicleDebug) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.current_lane_id().size() > 0) { + + current_lane_id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.current_lane_id_); + } + if (from.has_position()) { + mutable_position()->::apollo::common::PointENU::MergeFrom(from.position()); + } + if (from.has_route_s_range()) { + mutable_route_s_range()->::apollo::decision::Range::MergeFrom(from.route_s_range()); + } + if (from.has_route_l_range()) { + mutable_route_l_range()->::apollo::decision::Range::MergeFrom(from.route_l_range()); + } + if (from.lane_s() != 0) { + set_lane_s(from.lane_s()); + } + if (from.lane_l() != 0) { + set_lane_l(from.lane_l()); + } + if (from.route_s() != 0) { + set_route_s(from.route_s()); + } + if (from.route_l() != 0) { + set_route_l(from.route_l()); + } + if (from.heading() != 0) { + set_heading(from.heading()); + } + if (from.heading_speed() != 0) { + set_heading_speed(from.heading_speed()); + } + if (from.heading_acceleration() != 0) { + set_heading_acceleration(from.heading_acceleration()); + } +} + +void MasterVehicleDebug::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.MasterVehicleDebug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void MasterVehicleDebug::CopyFrom(const MasterVehicleDebug& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.MasterVehicleDebug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool MasterVehicleDebug::IsInitialized() const { + return true; +} + +void MasterVehicleDebug::Swap(MasterVehicleDebug* other) { + if (other == this) return; + InternalSwap(other); +} +void MasterVehicleDebug::InternalSwap(MasterVehicleDebug* other) { + using std::swap; + current_lane_id_.Swap(&other->current_lane_id_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(position_, other->position_); + swap(route_s_range_, other->route_s_range_); + swap(route_l_range_, other->route_l_range_); + swap(lane_s_, other->lane_s_); + swap(lane_l_, other->lane_l_); + swap(route_s_, other->route_s_); + swap(route_l_, other->route_l_); + swap(heading_, other->heading_); + swap(heading_speed_, other->heading_speed_); + swap(heading_acceleration_, other->heading_acceleration_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata MasterVehicleDebug::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ObjectDebug::InitAsDefaultInstance() { + ::apollo::decision::_ObjectDebug_default_instance_._instance.get_mutable()->route_s_ = const_cast< ::apollo::decision::Range*>( + ::apollo::decision::Range::internal_default_instance()); + ::apollo::decision::_ObjectDebug_default_instance_._instance.get_mutable()->route_l_ = const_cast< ::apollo::decision::Range*>( + ::apollo::decision::Range::internal_default_instance()); +} +void ObjectDebug::clear_st_region() { + st_region_.Clear(); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ObjectDebug::kIdFieldNumber; +const int ObjectDebug::kPathIdFieldNumber; +const int ObjectDebug::kRouteSFieldNumber; +const int ObjectDebug::kRouteLFieldNumber; +const int ObjectDebug::kOnRouteFieldNumber; +const int ObjectDebug::kLaneIdFieldNumber; +const int ObjectDebug::kLaneSFieldNumber; +const int ObjectDebug::kOnLaneFieldNumber; +const int ObjectDebug::kPathSpeedFieldNumber; +const int ObjectDebug::kStRegionFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ObjectDebug::ObjectDebug() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectDebug.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.ObjectDebug) +} +ObjectDebug::ObjectDebug(const ObjectDebug& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + st_region_(from.st_region_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.id().size() > 0) { + id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.id_); + } + path_id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.path_id().size() > 0) { + path_id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.path_id_); + } + lane_id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.lane_id().size() > 0) { + lane_id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.lane_id_); + } + if (from.has_route_s()) { + route_s_ = new ::apollo::decision::Range(*from.route_s_); + } else { + route_s_ = NULL; + } + if (from.has_route_l()) { + route_l_ = new ::apollo::decision::Range(*from.route_l_); + } else { + route_l_ = NULL; + } + ::memcpy(&lane_s_, &from.lane_s_, + static_cast(reinterpret_cast(&on_lane_) - + reinterpret_cast(&lane_s_)) + sizeof(on_lane_)); + // @@protoc_insertion_point(copy_constructor:apollo.decision.ObjectDebug) +} + +void ObjectDebug::SharedCtor() { + id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + path_id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + lane_id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&route_s_, 0, static_cast( + reinterpret_cast(&on_lane_) - + reinterpret_cast(&route_s_)) + sizeof(on_lane_)); +} + +ObjectDebug::~ObjectDebug() { + // @@protoc_insertion_point(destructor:apollo.decision.ObjectDebug) + SharedDtor(); +} + +void ObjectDebug::SharedDtor() { + id_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + path_id_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + lane_id_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (this != internal_default_instance()) delete route_s_; + if (this != internal_default_instance()) delete route_l_; +} + +void ObjectDebug::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ObjectDebug::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ObjectDebug& ObjectDebug::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectDebug.base); + return *internal_default_instance(); +} + + +void ObjectDebug::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.ObjectDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + st_region_.Clear(); + id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + path_id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + lane_id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (GetArenaNoVirtual() == NULL && route_s_ != NULL) { + delete route_s_; + } + route_s_ = NULL; + if (GetArenaNoVirtual() == NULL && route_l_ != NULL) { + delete route_l_; + } + route_l_ = NULL; + ::memset(&lane_s_, 0, static_cast( + reinterpret_cast(&on_lane_) - + reinterpret_cast(&lane_s_)) + sizeof(on_lane_)); + _internal_metadata_.Clear(); +} + +bool ObjectDebug::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.ObjectDebug) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // string id = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_id())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->id().data(), static_cast(this->id().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.decision.ObjectDebug.id")); + } else { + goto handle_unusual; + } + break; + } + + // string path_id = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_path_id())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->path_id().data(), static_cast(this->path_id().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.decision.ObjectDebug.path_id")); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.Range route_s = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_route_s())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.Range route_l = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_route_l())); + } else { + goto handle_unusual; + } + break; + } + + // bool on_route = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(40u /* 40 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &on_route_))); + } else { + goto handle_unusual; + } + break; + } + + // string lane_id = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(50u /* 50 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_lane_id())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->lane_id().data(), static_cast(this->lane_id().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.decision.ObjectDebug.lane_id")); + } else { + goto handle_unusual; + } + break; + } + + // double lane_s = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &lane_s_))); + } else { + goto handle_unusual; + } + break; + } + + // bool on_lane = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(64u /* 64 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &on_lane_))); + } else { + goto handle_unusual; + } + break; + } + + // double path_speed = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(73u /* 73 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &path_speed_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.common.Point3D st_region = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(82u /* 82 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_st_region())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.ObjectDebug) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.ObjectDebug) + return false; +#undef DO_ +} + +void ObjectDebug::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.ObjectDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // string id = 1; + if (this->id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->id().data(), static_cast(this->id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.ObjectDebug.id"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 1, this->id(), output); + } + + // string path_id = 2; + if (this->path_id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->path_id().data(), static_cast(this->path_id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.ObjectDebug.path_id"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 2, this->path_id(), output); + } + + // .apollo.decision.Range route_s = 3; + if (this->has_route_s()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_route_s(), output); + } + + // .apollo.decision.Range route_l = 4; + if (this->has_route_l()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, this->_internal_route_l(), output); + } + + // bool on_route = 5; + if (this->on_route() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(5, this->on_route(), output); + } + + // string lane_id = 6; + if (this->lane_id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->lane_id().data(), static_cast(this->lane_id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.ObjectDebug.lane_id"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 6, this->lane_id(), output); + } + + // double lane_s = 7; + if (this->lane_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->lane_s(), output); + } + + // bool on_lane = 8; + if (this->on_lane() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(8, this->on_lane(), output); + } + + // double path_speed = 9; + if (this->path_speed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->path_speed(), output); + } + + // repeated .apollo.common.Point3D st_region = 10; + for (unsigned int i = 0, + n = static_cast(this->st_region_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 10, + this->st_region(static_cast(i)), + output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.ObjectDebug) +} + +::google::protobuf::uint8* ObjectDebug::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.ObjectDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // string id = 1; + if (this->id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->id().data(), static_cast(this->id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.ObjectDebug.id"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 1, this->id(), target); + } + + // string path_id = 2; + if (this->path_id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->path_id().data(), static_cast(this->path_id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.ObjectDebug.path_id"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 2, this->path_id(), target); + } + + // .apollo.decision.Range route_s = 3; + if (this->has_route_s()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_route_s(), deterministic, target); + } + + // .apollo.decision.Range route_l = 4; + if (this->has_route_l()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->_internal_route_l(), deterministic, target); + } + + // bool on_route = 5; + if (this->on_route() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(5, this->on_route(), target); + } + + // string lane_id = 6; + if (this->lane_id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->lane_id().data(), static_cast(this->lane_id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.decision.ObjectDebug.lane_id"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 6, this->lane_id(), target); + } + + // double lane_s = 7; + if (this->lane_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->lane_s(), target); + } + + // bool on_lane = 8; + if (this->on_lane() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(8, this->on_lane(), target); + } + + // double path_speed = 9; + if (this->path_speed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->path_speed(), target); + } + + // repeated .apollo.common.Point3D st_region = 10; + for (unsigned int i = 0, + n = static_cast(this->st_region_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 10, this->st_region(static_cast(i)), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.ObjectDebug) + return target; +} + +size_t ObjectDebug::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.ObjectDebug) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.common.Point3D st_region = 10; + { + unsigned int count = static_cast(this->st_region_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->st_region(static_cast(i))); + } + } + + // string id = 1; + if (this->id().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->id()); + } + + // string path_id = 2; + if (this->path_id().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->path_id()); + } + + // string lane_id = 6; + if (this->lane_id().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->lane_id()); + } + + // .apollo.decision.Range route_s = 3; + if (this->has_route_s()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *route_s_); + } + + // .apollo.decision.Range route_l = 4; + if (this->has_route_l()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *route_l_); + } + + // double lane_s = 7; + if (this->lane_s() != 0) { + total_size += 1 + 8; + } + + // double path_speed = 9; + if (this->path_speed() != 0) { + total_size += 1 + 8; + } + + // bool on_route = 5; + if (this->on_route() != 0) { + total_size += 1 + 1; + } + + // bool on_lane = 8; + if (this->on_lane() != 0) { + total_size += 1 + 1; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ObjectDebug::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.ObjectDebug) + GOOGLE_DCHECK_NE(&from, this); + const ObjectDebug* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.ObjectDebug) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.ObjectDebug) + MergeFrom(*source); + } +} + +void ObjectDebug::MergeFrom(const ObjectDebug& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.ObjectDebug) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + st_region_.MergeFrom(from.st_region_); + if (from.id().size() > 0) { + + id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.id_); + } + if (from.path_id().size() > 0) { + + path_id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.path_id_); + } + if (from.lane_id().size() > 0) { + + lane_id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.lane_id_); + } + if (from.has_route_s()) { + mutable_route_s()->::apollo::decision::Range::MergeFrom(from.route_s()); + } + if (from.has_route_l()) { + mutable_route_l()->::apollo::decision::Range::MergeFrom(from.route_l()); + } + if (from.lane_s() != 0) { + set_lane_s(from.lane_s()); + } + if (from.path_speed() != 0) { + set_path_speed(from.path_speed()); + } + if (from.on_route() != 0) { + set_on_route(from.on_route()); + } + if (from.on_lane() != 0) { + set_on_lane(from.on_lane()); + } +} + +void ObjectDebug::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.ObjectDebug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ObjectDebug::CopyFrom(const ObjectDebug& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.ObjectDebug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ObjectDebug::IsInitialized() const { + return true; +} + +void ObjectDebug::Swap(ObjectDebug* other) { + if (other == this) return; + InternalSwap(other); +} +void ObjectDebug::InternalSwap(ObjectDebug* other) { + using std::swap; + CastToBase(&st_region_)->InternalSwap(CastToBase(&other->st_region_)); + id_.Swap(&other->id_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + path_id_.Swap(&other->path_id_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + lane_id_.Swap(&other->lane_id_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(route_s_, other->route_s_); + swap(route_l_, other->route_l_); + swap(lane_s_, other->lane_s_); + swap(path_speed_, other->path_speed_); + swap(on_route_, other->on_route_); + swap(on_lane_, other->on_lane_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ObjectDebug::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void LatencyStats::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int LatencyStats::kTotalTimeMsFieldNumber; +const int LatencyStats::kSensorReadTimeMsFieldNumber; +const int LatencyStats::kAdcPrepareTimeMsFieldNumber; +const int LatencyStats::kObjPrepareTimeMsFieldNumber; +const int LatencyStats::kWorldRuleTimeMsFieldNumber; +const int LatencyStats::kStGraphTimeMsFieldNumber; +const int LatencyStats::kGatewayReceiveDelayMsFieldNumber; +const int LatencyStats::kPerceptionReceiveDelayMsFieldNumber; +const int LatencyStats::kPredictionReceiveDelayMsFieldNumber; +const int LatencyStats::kSignalReceiveDelayMsFieldNumber; +const int LatencyStats::kPerceptionIntervalMsFieldNumber; +const int LatencyStats::kPredictionIntervalMsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +LatencyStats::LatencyStats() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_LatencyStats.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.LatencyStats) +} +LatencyStats::LatencyStats(const LatencyStats& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&total_time_ms_, &from.total_time_ms_, + static_cast(reinterpret_cast(&prediction_interval_ms_) - + reinterpret_cast(&total_time_ms_)) + sizeof(prediction_interval_ms_)); + // @@protoc_insertion_point(copy_constructor:apollo.decision.LatencyStats) +} + +void LatencyStats::SharedCtor() { + ::memset(&total_time_ms_, 0, static_cast( + reinterpret_cast(&prediction_interval_ms_) - + reinterpret_cast(&total_time_ms_)) + sizeof(prediction_interval_ms_)); +} + +LatencyStats::~LatencyStats() { + // @@protoc_insertion_point(destructor:apollo.decision.LatencyStats) + SharedDtor(); +} + +void LatencyStats::SharedDtor() { +} + +void LatencyStats::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* LatencyStats::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const LatencyStats& LatencyStats::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_LatencyStats.base); + return *internal_default_instance(); +} + + +void LatencyStats::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.LatencyStats) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&total_time_ms_, 0, static_cast( + reinterpret_cast(&prediction_interval_ms_) - + reinterpret_cast(&total_time_ms_)) + sizeof(prediction_interval_ms_)); + _internal_metadata_.Clear(); +} + +bool LatencyStats::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.LatencyStats) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double total_time_ms = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &total_time_ms_))); + } else { + goto handle_unusual; + } + break; + } + + // double sensor_read_time_ms = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &sensor_read_time_ms_))); + } else { + goto handle_unusual; + } + break; + } + + // double adc_prepare_time_ms = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &adc_prepare_time_ms_))); + } else { + goto handle_unusual; + } + break; + } + + // double obj_prepare_time_ms = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &obj_prepare_time_ms_))); + } else { + goto handle_unusual; + } + break; + } + + // double world_rule_time_ms = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &world_rule_time_ms_))); + } else { + goto handle_unusual; + } + break; + } + + // double st_graph_time_ms = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &st_graph_time_ms_))); + } else { + goto handle_unusual; + } + break; + } + + // double gateway_receive_delay_ms = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(65u /* 65 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &gateway_receive_delay_ms_))); + } else { + goto handle_unusual; + } + break; + } + + // double perception_receive_delay_ms = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(73u /* 73 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &perception_receive_delay_ms_))); + } else { + goto handle_unusual; + } + break; + } + + // double prediction_receive_delay_ms = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(81u /* 81 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &prediction_receive_delay_ms_))); + } else { + goto handle_unusual; + } + break; + } + + // double signal_receive_delay_ms = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(89u /* 89 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &signal_receive_delay_ms_))); + } else { + goto handle_unusual; + } + break; + } + + // double perception_interval_ms = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(97u /* 97 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &perception_interval_ms_))); + } else { + goto handle_unusual; + } + break; + } + + // double prediction_interval_ms = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(105u /* 105 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &prediction_interval_ms_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.LatencyStats) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.LatencyStats) + return false; +#undef DO_ +} + +void LatencyStats::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.LatencyStats) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double total_time_ms = 1; + if (this->total_time_ms() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->total_time_ms(), output); + } + + // double sensor_read_time_ms = 2; + if (this->sensor_read_time_ms() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->sensor_read_time_ms(), output); + } + + // double adc_prepare_time_ms = 3; + if (this->adc_prepare_time_ms() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->adc_prepare_time_ms(), output); + } + + // double obj_prepare_time_ms = 4; + if (this->obj_prepare_time_ms() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->obj_prepare_time_ms(), output); + } + + // double world_rule_time_ms = 5; + if (this->world_rule_time_ms() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->world_rule_time_ms(), output); + } + + // double st_graph_time_ms = 6; + if (this->st_graph_time_ms() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->st_graph_time_ms(), output); + } + + // double gateway_receive_delay_ms = 8; + if (this->gateway_receive_delay_ms() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(8, this->gateway_receive_delay_ms(), output); + } + + // double perception_receive_delay_ms = 9; + if (this->perception_receive_delay_ms() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->perception_receive_delay_ms(), output); + } + + // double prediction_receive_delay_ms = 10; + if (this->prediction_receive_delay_ms() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(10, this->prediction_receive_delay_ms(), output); + } + + // double signal_receive_delay_ms = 11; + if (this->signal_receive_delay_ms() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(11, this->signal_receive_delay_ms(), output); + } + + // double perception_interval_ms = 12; + if (this->perception_interval_ms() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(12, this->perception_interval_ms(), output); + } + + // double prediction_interval_ms = 13; + if (this->prediction_interval_ms() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(13, this->prediction_interval_ms(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.LatencyStats) +} + +::google::protobuf::uint8* LatencyStats::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.LatencyStats) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double total_time_ms = 1; + if (this->total_time_ms() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->total_time_ms(), target); + } + + // double sensor_read_time_ms = 2; + if (this->sensor_read_time_ms() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->sensor_read_time_ms(), target); + } + + // double adc_prepare_time_ms = 3; + if (this->adc_prepare_time_ms() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->adc_prepare_time_ms(), target); + } + + // double obj_prepare_time_ms = 4; + if (this->obj_prepare_time_ms() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->obj_prepare_time_ms(), target); + } + + // double world_rule_time_ms = 5; + if (this->world_rule_time_ms() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->world_rule_time_ms(), target); + } + + // double st_graph_time_ms = 6; + if (this->st_graph_time_ms() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->st_graph_time_ms(), target); + } + + // double gateway_receive_delay_ms = 8; + if (this->gateway_receive_delay_ms() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(8, this->gateway_receive_delay_ms(), target); + } + + // double perception_receive_delay_ms = 9; + if (this->perception_receive_delay_ms() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->perception_receive_delay_ms(), target); + } + + // double prediction_receive_delay_ms = 10; + if (this->prediction_receive_delay_ms() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(10, this->prediction_receive_delay_ms(), target); + } + + // double signal_receive_delay_ms = 11; + if (this->signal_receive_delay_ms() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(11, this->signal_receive_delay_ms(), target); + } + + // double perception_interval_ms = 12; + if (this->perception_interval_ms() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(12, this->perception_interval_ms(), target); + } + + // double prediction_interval_ms = 13; + if (this->prediction_interval_ms() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(13, this->prediction_interval_ms(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.LatencyStats) + return target; +} + +size_t LatencyStats::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.LatencyStats) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double total_time_ms = 1; + if (this->total_time_ms() != 0) { + total_size += 1 + 8; + } + + // double sensor_read_time_ms = 2; + if (this->sensor_read_time_ms() != 0) { + total_size += 1 + 8; + } + + // double adc_prepare_time_ms = 3; + if (this->adc_prepare_time_ms() != 0) { + total_size += 1 + 8; + } + + // double obj_prepare_time_ms = 4; + if (this->obj_prepare_time_ms() != 0) { + total_size += 1 + 8; + } + + // double world_rule_time_ms = 5; + if (this->world_rule_time_ms() != 0) { + total_size += 1 + 8; + } + + // double st_graph_time_ms = 6; + if (this->st_graph_time_ms() != 0) { + total_size += 1 + 8; + } + + // double gateway_receive_delay_ms = 8; + if (this->gateway_receive_delay_ms() != 0) { + total_size += 1 + 8; + } + + // double perception_receive_delay_ms = 9; + if (this->perception_receive_delay_ms() != 0) { + total_size += 1 + 8; + } + + // double prediction_receive_delay_ms = 10; + if (this->prediction_receive_delay_ms() != 0) { + total_size += 1 + 8; + } + + // double signal_receive_delay_ms = 11; + if (this->signal_receive_delay_ms() != 0) { + total_size += 1 + 8; + } + + // double perception_interval_ms = 12; + if (this->perception_interval_ms() != 0) { + total_size += 1 + 8; + } + + // double prediction_interval_ms = 13; + if (this->prediction_interval_ms() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void LatencyStats::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.LatencyStats) + GOOGLE_DCHECK_NE(&from, this); + const LatencyStats* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.LatencyStats) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.LatencyStats) + MergeFrom(*source); + } +} + +void LatencyStats::MergeFrom(const LatencyStats& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.LatencyStats) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.total_time_ms() != 0) { + set_total_time_ms(from.total_time_ms()); + } + if (from.sensor_read_time_ms() != 0) { + set_sensor_read_time_ms(from.sensor_read_time_ms()); + } + if (from.adc_prepare_time_ms() != 0) { + set_adc_prepare_time_ms(from.adc_prepare_time_ms()); + } + if (from.obj_prepare_time_ms() != 0) { + set_obj_prepare_time_ms(from.obj_prepare_time_ms()); + } + if (from.world_rule_time_ms() != 0) { + set_world_rule_time_ms(from.world_rule_time_ms()); + } + if (from.st_graph_time_ms() != 0) { + set_st_graph_time_ms(from.st_graph_time_ms()); + } + if (from.gateway_receive_delay_ms() != 0) { + set_gateway_receive_delay_ms(from.gateway_receive_delay_ms()); + } + if (from.perception_receive_delay_ms() != 0) { + set_perception_receive_delay_ms(from.perception_receive_delay_ms()); + } + if (from.prediction_receive_delay_ms() != 0) { + set_prediction_receive_delay_ms(from.prediction_receive_delay_ms()); + } + if (from.signal_receive_delay_ms() != 0) { + set_signal_receive_delay_ms(from.signal_receive_delay_ms()); + } + if (from.perception_interval_ms() != 0) { + set_perception_interval_ms(from.perception_interval_ms()); + } + if (from.prediction_interval_ms() != 0) { + set_prediction_interval_ms(from.prediction_interval_ms()); + } +} + +void LatencyStats::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.LatencyStats) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void LatencyStats::CopyFrom(const LatencyStats& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.LatencyStats) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool LatencyStats::IsInitialized() const { + return true; +} + +void LatencyStats::Swap(LatencyStats* other) { + if (other == this) return; + InternalSwap(other); +} +void LatencyStats::InternalSwap(LatencyStats* other) { + using std::swap; + swap(total_time_ms_, other->total_time_ms_); + swap(sensor_read_time_ms_, other->sensor_read_time_ms_); + swap(adc_prepare_time_ms_, other->adc_prepare_time_ms_); + swap(obj_prepare_time_ms_, other->obj_prepare_time_ms_); + swap(world_rule_time_ms_, other->world_rule_time_ms_); + swap(st_graph_time_ms_, other->st_graph_time_ms_); + swap(gateway_receive_delay_ms_, other->gateway_receive_delay_ms_); + swap(perception_receive_delay_ms_, other->perception_receive_delay_ms_); + swap(prediction_receive_delay_ms_, other->prediction_receive_delay_ms_); + swap(signal_receive_delay_ms_, other->signal_receive_delay_ms_); + swap(perception_interval_ms_, other->perception_interval_ms_); + swap(prediction_interval_ms_, other->prediction_interval_ms_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata LatencyStats::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Stats::InitAsDefaultInstance() { + ::apollo::decision::_Stats_default_instance_._instance.get_mutable()->latency_stats_ = const_cast< ::apollo::decision::LatencyStats*>( + ::apollo::decision::LatencyStats::internal_default_instance()); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Stats::kLatencyStatsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Stats::Stats() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Stats.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.Stats) +} +Stats::Stats(const Stats& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_latency_stats()) { + latency_stats_ = new ::apollo::decision::LatencyStats(*from.latency_stats_); + } else { + latency_stats_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.decision.Stats) +} + +void Stats::SharedCtor() { + latency_stats_ = NULL; +} + +Stats::~Stats() { + // @@protoc_insertion_point(destructor:apollo.decision.Stats) + SharedDtor(); +} + +void Stats::SharedDtor() { + if (this != internal_default_instance()) delete latency_stats_; +} + +void Stats::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Stats::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Stats& Stats::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Stats.base); + return *internal_default_instance(); +} + + +void Stats::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.Stats) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && latency_stats_ != NULL) { + delete latency_stats_; + } + latency_stats_ = NULL; + _internal_metadata_.Clear(); +} + +bool Stats::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.Stats) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.decision.LatencyStats latency_stats = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_latency_stats())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.Stats) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.Stats) + return false; +#undef DO_ +} + +void Stats::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.Stats) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.LatencyStats latency_stats = 1; + if (this->has_latency_stats()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_latency_stats(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.Stats) +} + +::google::protobuf::uint8* Stats::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.Stats) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.LatencyStats latency_stats = 1; + if (this->has_latency_stats()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_latency_stats(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.Stats) + return target; +} + +size_t Stats::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.Stats) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.decision.LatencyStats latency_stats = 1; + if (this->has_latency_stats()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *latency_stats_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Stats::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.Stats) + GOOGLE_DCHECK_NE(&from, this); + const Stats* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.Stats) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.Stats) + MergeFrom(*source); + } +} + +void Stats::MergeFrom(const Stats& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.Stats) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_latency_stats()) { + mutable_latency_stats()->::apollo::decision::LatencyStats::MergeFrom(from.latency_stats()); + } +} + +void Stats::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.Stats) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Stats::CopyFrom(const Stats& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.Stats) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Stats::IsInitialized() const { + return true; +} + +void Stats::Swap(Stats* other) { + if (other == this) return; + InternalSwap(other); +} +void Stats::InternalSwap(Stats* other) { + using std::swap; + swap(latency_stats_, other->latency_stats_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Stats::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ModuleDebug::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ModuleDebug::kGatewaySequenceNumFieldNumber; +const int ModuleDebug::kPerceptionSequenceNumFieldNumber; +const int ModuleDebug::kPredictionSequenceNumFieldNumber; +const int ModuleDebug::kSignalSequenceNumFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ModuleDebug::ModuleDebug() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ModuleDebug.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.ModuleDebug) +} +ModuleDebug::ModuleDebug(const ModuleDebug& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&gateway_sequence_num_, &from.gateway_sequence_num_, + static_cast(reinterpret_cast(&signal_sequence_num_) - + reinterpret_cast(&gateway_sequence_num_)) + sizeof(signal_sequence_num_)); + // @@protoc_insertion_point(copy_constructor:apollo.decision.ModuleDebug) +} + +void ModuleDebug::SharedCtor() { + ::memset(&gateway_sequence_num_, 0, static_cast( + reinterpret_cast(&signal_sequence_num_) - + reinterpret_cast(&gateway_sequence_num_)) + sizeof(signal_sequence_num_)); +} + +ModuleDebug::~ModuleDebug() { + // @@protoc_insertion_point(destructor:apollo.decision.ModuleDebug) + SharedDtor(); +} + +void ModuleDebug::SharedDtor() { +} + +void ModuleDebug::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ModuleDebug::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ModuleDebug& ModuleDebug::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ModuleDebug.base); + return *internal_default_instance(); +} + + +void ModuleDebug::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.ModuleDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&gateway_sequence_num_, 0, static_cast( + reinterpret_cast(&signal_sequence_num_) - + reinterpret_cast(&gateway_sequence_num_)) + sizeof(signal_sequence_num_)); + _internal_metadata_.Clear(); +} + +bool ModuleDebug::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.ModuleDebug) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // uint32 gateway_sequence_num = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &gateway_sequence_num_))); + } else { + goto handle_unusual; + } + break; + } + + // uint32 perception_sequence_num = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &perception_sequence_num_))); + } else { + goto handle_unusual; + } + break; + } + + // uint32 prediction_sequence_num = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &prediction_sequence_num_))); + } else { + goto handle_unusual; + } + break; + } + + // uint32 signal_sequence_num = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &signal_sequence_num_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.ModuleDebug) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.ModuleDebug) + return false; +#undef DO_ +} + +void ModuleDebug::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.ModuleDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // uint32 gateway_sequence_num = 1; + if (this->gateway_sequence_num() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(1, this->gateway_sequence_num(), output); + } + + // uint32 perception_sequence_num = 2; + if (this->perception_sequence_num() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(2, this->perception_sequence_num(), output); + } + + // uint32 prediction_sequence_num = 3; + if (this->prediction_sequence_num() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(3, this->prediction_sequence_num(), output); + } + + // uint32 signal_sequence_num = 4; + if (this->signal_sequence_num() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(4, this->signal_sequence_num(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.ModuleDebug) +} + +::google::protobuf::uint8* ModuleDebug::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.ModuleDebug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // uint32 gateway_sequence_num = 1; + if (this->gateway_sequence_num() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(1, this->gateway_sequence_num(), target); + } + + // uint32 perception_sequence_num = 2; + if (this->perception_sequence_num() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(2, this->perception_sequence_num(), target); + } + + // uint32 prediction_sequence_num = 3; + if (this->prediction_sequence_num() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(3, this->prediction_sequence_num(), target); + } + + // uint32 signal_sequence_num = 4; + if (this->signal_sequence_num() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(4, this->signal_sequence_num(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.ModuleDebug) + return target; +} + +size_t ModuleDebug::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.ModuleDebug) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // uint32 gateway_sequence_num = 1; + if (this->gateway_sequence_num() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->gateway_sequence_num()); + } + + // uint32 perception_sequence_num = 2; + if (this->perception_sequence_num() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->perception_sequence_num()); + } + + // uint32 prediction_sequence_num = 3; + if (this->prediction_sequence_num() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->prediction_sequence_num()); + } + + // uint32 signal_sequence_num = 4; + if (this->signal_sequence_num() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->signal_sequence_num()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ModuleDebug::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.ModuleDebug) + GOOGLE_DCHECK_NE(&from, this); + const ModuleDebug* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.ModuleDebug) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.ModuleDebug) + MergeFrom(*source); + } +} + +void ModuleDebug::MergeFrom(const ModuleDebug& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.ModuleDebug) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.gateway_sequence_num() != 0) { + set_gateway_sequence_num(from.gateway_sequence_num()); + } + if (from.perception_sequence_num() != 0) { + set_perception_sequence_num(from.perception_sequence_num()); + } + if (from.prediction_sequence_num() != 0) { + set_prediction_sequence_num(from.prediction_sequence_num()); + } + if (from.signal_sequence_num() != 0) { + set_signal_sequence_num(from.signal_sequence_num()); + } +} + +void ModuleDebug::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.ModuleDebug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ModuleDebug::CopyFrom(const ModuleDebug& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.ModuleDebug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ModuleDebug::IsInitialized() const { + return true; +} + +void ModuleDebug::Swap(ModuleDebug* other) { + if (other == this) return; + InternalSwap(other); +} +void ModuleDebug::InternalSwap(ModuleDebug* other) { + using std::swap; + swap(gateway_sequence_num_, other->gateway_sequence_num_); + swap(perception_sequence_num_, other->perception_sequence_num_); + swap(prediction_sequence_num_, other->prediction_sequence_num_); + swap(signal_sequence_num_, other->signal_sequence_num_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ModuleDebug::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Debug::InitAsDefaultInstance() { + ::apollo::decision::_Debug_default_instance_._instance.get_mutable()->master_vehicle_ = const_cast< ::apollo::decision::MasterVehicleDebug*>( + ::apollo::decision::MasterVehicleDebug::internal_default_instance()); + ::apollo::decision::_Debug_default_instance_._instance.get_mutable()->original_decision_ = const_cast< ::apollo::decision::MainDecision*>( + ::apollo::decision::MainDecision::internal_default_instance()); + ::apollo::decision::_Debug_default_instance_._instance.get_mutable()->module_debug_ = const_cast< ::apollo::decision::ModuleDebug*>( + ::apollo::decision::ModuleDebug::internal_default_instance()); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Debug::kMasterVehicleFieldNumber; +const int Debug::kOriginalDecisionFieldNumber; +const int Debug::kObjectFieldNumber; +const int Debug::kMapVersionFieldNumber; +const int Debug::kDecisionVersionFieldNumber; +const int Debug::kModuleDebugFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Debug::Debug() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Debug.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.Debug) +} +Debug::Debug(const Debug& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + object_(from.object_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + map_version_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.map_version().size() > 0) { + map_version_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.map_version_); + } + decision_version_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.decision_version().size() > 0) { + decision_version_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.decision_version_); + } + if (from.has_master_vehicle()) { + master_vehicle_ = new ::apollo::decision::MasterVehicleDebug(*from.master_vehicle_); + } else { + master_vehicle_ = NULL; + } + if (from.has_original_decision()) { + original_decision_ = new ::apollo::decision::MainDecision(*from.original_decision_); + } else { + original_decision_ = NULL; + } + if (from.has_module_debug()) { + module_debug_ = new ::apollo::decision::ModuleDebug(*from.module_debug_); + } else { + module_debug_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.decision.Debug) +} + +void Debug::SharedCtor() { + map_version_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + decision_version_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&master_vehicle_, 0, static_cast( + reinterpret_cast(&module_debug_) - + reinterpret_cast(&master_vehicle_)) + sizeof(module_debug_)); +} + +Debug::~Debug() { + // @@protoc_insertion_point(destructor:apollo.decision.Debug) + SharedDtor(); +} + +void Debug::SharedDtor() { + map_version_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + decision_version_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (this != internal_default_instance()) delete master_vehicle_; + if (this != internal_default_instance()) delete original_decision_; + if (this != internal_default_instance()) delete module_debug_; +} + +void Debug::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Debug::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Debug& Debug::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_Debug.base); + return *internal_default_instance(); +} + + +void Debug::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.Debug) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + object_.Clear(); + map_version_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + decision_version_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (GetArenaNoVirtual() == NULL && master_vehicle_ != NULL) { + delete master_vehicle_; + } + master_vehicle_ = NULL; + if (GetArenaNoVirtual() == NULL && original_decision_ != NULL) { + delete original_decision_; + } + original_decision_ = NULL; + if (GetArenaNoVirtual() == NULL && module_debug_ != NULL) { + delete module_debug_; + } + module_debug_ = NULL; + _internal_metadata_.Clear(); +} + +bool Debug::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.Debug) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.decision.MasterVehicleDebug master_vehicle = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_master_vehicle())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.MainDecision original_decision = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_original_decision())); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.decision.ObjectDebug object = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_object())); + } else { + goto handle_unusual; + } + break; + } + + // bytes map_version = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( + input, this->mutable_map_version())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ModuleDebug module_debug = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(50u /* 50 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_module_debug())); + } else { + goto handle_unusual; + } + break; + } + + // bytes decision_version = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(58u /* 58 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( + input, this->mutable_decision_version())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.Debug) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.Debug) + return false; +#undef DO_ +} + +void Debug::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.Debug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.MasterVehicleDebug master_vehicle = 1; + if (this->has_master_vehicle()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_master_vehicle(), output); + } + + // .apollo.decision.MainDecision original_decision = 2; + if (this->has_original_decision()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_original_decision(), output); + } + + // repeated .apollo.decision.ObjectDebug object = 3; + for (unsigned int i = 0, + n = static_cast(this->object_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, + this->object(static_cast(i)), + output); + } + + // bytes map_version = 5; + if (this->map_version().size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteBytesMaybeAliased( + 5, this->map_version(), output); + } + + // .apollo.decision.ModuleDebug module_debug = 6; + if (this->has_module_debug()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 6, this->_internal_module_debug(), output); + } + + // bytes decision_version = 7; + if (this->decision_version().size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteBytesMaybeAliased( + 7, this->decision_version(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.Debug) +} + +::google::protobuf::uint8* Debug::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.Debug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.decision.MasterVehicleDebug master_vehicle = 1; + if (this->has_master_vehicle()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_master_vehicle(), deterministic, target); + } + + // .apollo.decision.MainDecision original_decision = 2; + if (this->has_original_decision()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_original_decision(), deterministic, target); + } + + // repeated .apollo.decision.ObjectDebug object = 3; + for (unsigned int i = 0, + n = static_cast(this->object_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->object(static_cast(i)), deterministic, target); + } + + // bytes map_version = 5; + if (this->map_version().size() > 0) { + target = + ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( + 5, this->map_version(), target); + } + + // .apollo.decision.ModuleDebug module_debug = 6; + if (this->has_module_debug()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 6, this->_internal_module_debug(), deterministic, target); + } + + // bytes decision_version = 7; + if (this->decision_version().size() > 0) { + target = + ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( + 7, this->decision_version(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.Debug) + return target; +} + +size_t Debug::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.Debug) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.decision.ObjectDebug object = 3; + { + unsigned int count = static_cast(this->object_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->object(static_cast(i))); + } + } + + // bytes map_version = 5; + if (this->map_version().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::BytesSize( + this->map_version()); + } + + // bytes decision_version = 7; + if (this->decision_version().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::BytesSize( + this->decision_version()); + } + + // .apollo.decision.MasterVehicleDebug master_vehicle = 1; + if (this->has_master_vehicle()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *master_vehicle_); + } + + // .apollo.decision.MainDecision original_decision = 2; + if (this->has_original_decision()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *original_decision_); + } + + // .apollo.decision.ModuleDebug module_debug = 6; + if (this->has_module_debug()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *module_debug_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Debug::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.Debug) + GOOGLE_DCHECK_NE(&from, this); + const Debug* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.Debug) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.Debug) + MergeFrom(*source); + } +} + +void Debug::MergeFrom(const Debug& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.Debug) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + object_.MergeFrom(from.object_); + if (from.map_version().size() > 0) { + + map_version_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.map_version_); + } + if (from.decision_version().size() > 0) { + + decision_version_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.decision_version_); + } + if (from.has_master_vehicle()) { + mutable_master_vehicle()->::apollo::decision::MasterVehicleDebug::MergeFrom(from.master_vehicle()); + } + if (from.has_original_decision()) { + mutable_original_decision()->::apollo::decision::MainDecision::MergeFrom(from.original_decision()); + } + if (from.has_module_debug()) { + mutable_module_debug()->::apollo::decision::ModuleDebug::MergeFrom(from.module_debug()); + } +} + +void Debug::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.Debug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Debug::CopyFrom(const Debug& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.Debug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Debug::IsInitialized() const { + return true; +} + +void Debug::Swap(Debug* other) { + if (other == this) return; + InternalSwap(other); +} +void Debug::InternalSwap(Debug* other) { + using std::swap; + CastToBase(&object_)->InternalSwap(CastToBase(&other->object_)); + map_version_.Swap(&other->map_version_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + decision_version_.Swap(&other->decision_version_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(master_vehicle_, other->master_vehicle_); + swap(original_decision_, other->original_decision_); + swap(module_debug_, other->module_debug_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Debug::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void LightSignal::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int LightSignal::kEmergencyFieldNumber; +const int LightSignal::kTurnSignalFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +LightSignal::LightSignal() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_LightSignal.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.LightSignal) +} +LightSignal::LightSignal(const LightSignal& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&emergency_, &from.emergency_, + static_cast(reinterpret_cast(&turn_signal_) - + reinterpret_cast(&emergency_)) + sizeof(turn_signal_)); + // @@protoc_insertion_point(copy_constructor:apollo.decision.LightSignal) +} + +void LightSignal::SharedCtor() { + ::memset(&emergency_, 0, static_cast( + reinterpret_cast(&turn_signal_) - + reinterpret_cast(&emergency_)) + sizeof(turn_signal_)); +} + +LightSignal::~LightSignal() { + // @@protoc_insertion_point(destructor:apollo.decision.LightSignal) + SharedDtor(); +} + +void LightSignal::SharedDtor() { +} + +void LightSignal::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* LightSignal::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const LightSignal& LightSignal::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_LightSignal.base); + return *internal_default_instance(); +} + + +void LightSignal::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.LightSignal) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&emergency_, 0, static_cast( + reinterpret_cast(&turn_signal_) - + reinterpret_cast(&emergency_)) + sizeof(turn_signal_)); + _internal_metadata_.Clear(); +} + +bool LightSignal::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.LightSignal) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool emergency = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &emergency_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.LightSignal.TurnSignal turn_signal = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_turn_signal(static_cast< ::apollo::decision::LightSignal_TurnSignal >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.LightSignal) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.LightSignal) + return false; +#undef DO_ +} + +void LightSignal::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.LightSignal) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool emergency = 1; + if (this->emergency() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->emergency(), output); + } + + // .apollo.decision.LightSignal.TurnSignal turn_signal = 2; + if (this->turn_signal() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 2, this->turn_signal(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.LightSignal) +} + +::google::protobuf::uint8* LightSignal::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.LightSignal) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool emergency = 1; + if (this->emergency() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->emergency(), target); + } + + // .apollo.decision.LightSignal.TurnSignal turn_signal = 2; + if (this->turn_signal() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 2, this->turn_signal(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.LightSignal) + return target; +} + +size_t LightSignal::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.LightSignal) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // bool emergency = 1; + if (this->emergency() != 0) { + total_size += 1 + 1; + } + + // .apollo.decision.LightSignal.TurnSignal turn_signal = 2; + if (this->turn_signal() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->turn_signal()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void LightSignal::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.LightSignal) + GOOGLE_DCHECK_NE(&from, this); + const LightSignal* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.LightSignal) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.LightSignal) + MergeFrom(*source); + } +} + +void LightSignal::MergeFrom(const LightSignal& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.LightSignal) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.emergency() != 0) { + set_emergency(from.emergency()); + } + if (from.turn_signal() != 0) { + set_turn_signal(from.turn_signal()); + } +} + +void LightSignal::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.LightSignal) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void LightSignal::CopyFrom(const LightSignal& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.LightSignal) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool LightSignal::IsInitialized() const { + return true; +} + +void LightSignal::Swap(LightSignal* other) { + if (other == this) return; + InternalSwap(other); +} +void LightSignal::InternalSwap(LightSignal* other) { + using std::swap; + swap(emergency_, other->emergency_); + swap(turn_signal_, other->turn_signal_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata LightSignal::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void DecisionResult::InitAsDefaultInstance() { + ::apollo::decision::_DecisionResult_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); + ::apollo::decision::_DecisionResult_default_instance_._instance.get_mutable()->object_decision_ = const_cast< ::apollo::decision::ObjectDecisions*>( + ::apollo::decision::ObjectDecisions::internal_default_instance()); + ::apollo::decision::_DecisionResult_default_instance_._instance.get_mutable()->main_decision_ = const_cast< ::apollo::decision::MainDecision*>( + ::apollo::decision::MainDecision::internal_default_instance()); + ::apollo::decision::_DecisionResult_default_instance_._instance.get_mutable()->debug_ = const_cast< ::apollo::decision::Debug*>( + ::apollo::decision::Debug::internal_default_instance()); + ::apollo::decision::_DecisionResult_default_instance_._instance.get_mutable()->stats_ = const_cast< ::apollo::decision::Stats*>( + ::apollo::decision::Stats::internal_default_instance()); + ::apollo::decision::_DecisionResult_default_instance_._instance.get_mutable()->signal_ = const_cast< ::apollo::canbus::Signal*>( + ::apollo::canbus::Signal::internal_default_instance()); + ::apollo::decision::_DecisionResult_default_instance_._instance.get_mutable()->light_signal_ = const_cast< ::apollo::decision::LightSignal*>( + ::apollo::decision::LightSignal::internal_default_instance()); +} +void DecisionResult::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +void DecisionResult::clear_signal() { + if (GetArenaNoVirtual() == NULL && signal_ != NULL) { + delete signal_; + } + signal_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int DecisionResult::kHeaderFieldNumber; +const int DecisionResult::kObjectDecisionFieldNumber; +const int DecisionResult::kMainDecisionFieldNumber; +const int DecisionResult::kDebugFieldNumber; +const int DecisionResult::kStatsFieldNumber; +const int DecisionResult::kSignalFieldNumber; +const int DecisionResult::kLightSignalFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +DecisionResult::DecisionResult() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_DecisionResult.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.decision.DecisionResult) +} +DecisionResult::DecisionResult(const DecisionResult& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + if (from.has_object_decision()) { + object_decision_ = new ::apollo::decision::ObjectDecisions(*from.object_decision_); + } else { + object_decision_ = NULL; + } + if (from.has_main_decision()) { + main_decision_ = new ::apollo::decision::MainDecision(*from.main_decision_); + } else { + main_decision_ = NULL; + } + if (from.has_debug()) { + debug_ = new ::apollo::decision::Debug(*from.debug_); + } else { + debug_ = NULL; + } + if (from.has_light_signal()) { + light_signal_ = new ::apollo::decision::LightSignal(*from.light_signal_); + } else { + light_signal_ = NULL; + } + if (from.has_stats()) { + stats_ = new ::apollo::decision::Stats(*from.stats_); + } else { + stats_ = NULL; + } + if (from.has_signal()) { + signal_ = new ::apollo::canbus::Signal(*from.signal_); + } else { + signal_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.decision.DecisionResult) +} + +void DecisionResult::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&signal_) - + reinterpret_cast(&header_)) + sizeof(signal_)); +} + +DecisionResult::~DecisionResult() { + // @@protoc_insertion_point(destructor:apollo.decision.DecisionResult) + SharedDtor(); +} + +void DecisionResult::SharedDtor() { + if (this != internal_default_instance()) delete header_; + if (this != internal_default_instance()) delete object_decision_; + if (this != internal_default_instance()) delete main_decision_; + if (this != internal_default_instance()) delete debug_; + if (this != internal_default_instance()) delete light_signal_; + if (this != internal_default_instance()) delete stats_; + if (this != internal_default_instance()) delete signal_; +} + +void DecisionResult::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* DecisionResult::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const DecisionResult& DecisionResult::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_DecisionResult.base); + return *internal_default_instance(); +} + + +void DecisionResult::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.decision.DecisionResult) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + if (GetArenaNoVirtual() == NULL && object_decision_ != NULL) { + delete object_decision_; + } + object_decision_ = NULL; + if (GetArenaNoVirtual() == NULL && main_decision_ != NULL) { + delete main_decision_; + } + main_decision_ = NULL; + if (GetArenaNoVirtual() == NULL && debug_ != NULL) { + delete debug_; + } + debug_ = NULL; + if (GetArenaNoVirtual() == NULL && light_signal_ != NULL) { + delete light_signal_; + } + light_signal_ = NULL; + if (GetArenaNoVirtual() == NULL && stats_ != NULL) { + delete stats_; + } + stats_ = NULL; + if (GetArenaNoVirtual() == NULL && signal_ != NULL) { + delete signal_; + } + signal_ = NULL; + _internal_metadata_.Clear(); +} + +bool DecisionResult::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.decision.DecisionResult) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectDecisions object_decision = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_object_decision())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.MainDecision main_decision = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_main_decision())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.Debug debug = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_debug())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.LightSignal light_signal = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_light_signal())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.Stats stats = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(50u /* 50 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_stats())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Signal signal = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(58u /* 58 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_signal())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.decision.DecisionResult) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.decision.DecisionResult) + return false; +#undef DO_ +} + +void DecisionResult::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.decision.DecisionResult) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // .apollo.decision.ObjectDecisions object_decision = 2; + if (this->has_object_decision()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_object_decision(), output); + } + + // .apollo.decision.MainDecision main_decision = 3; + if (this->has_main_decision()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_main_decision(), output); + } + + // .apollo.decision.Debug debug = 4; + if (this->has_debug()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, this->_internal_debug(), output); + } + + // .apollo.decision.LightSignal light_signal = 5; + if (this->has_light_signal()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, this->_internal_light_signal(), output); + } + + // .apollo.decision.Stats stats = 6; + if (this->has_stats()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 6, this->_internal_stats(), output); + } + + // .apollo.canbus.Signal signal = 7; + if (this->has_signal()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 7, this->_internal_signal(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.decision.DecisionResult) +} + +::google::protobuf::uint8* DecisionResult::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.decision.DecisionResult) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // .apollo.decision.ObjectDecisions object_decision = 2; + if (this->has_object_decision()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_object_decision(), deterministic, target); + } + + // .apollo.decision.MainDecision main_decision = 3; + if (this->has_main_decision()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_main_decision(), deterministic, target); + } + + // .apollo.decision.Debug debug = 4; + if (this->has_debug()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->_internal_debug(), deterministic, target); + } + + // .apollo.decision.LightSignal light_signal = 5; + if (this->has_light_signal()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 5, this->_internal_light_signal(), deterministic, target); + } + + // .apollo.decision.Stats stats = 6; + if (this->has_stats()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 6, this->_internal_stats(), deterministic, target); + } + + // .apollo.canbus.Signal signal = 7; + if (this->has_signal()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 7, this->_internal_signal(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.decision.DecisionResult) + return target; +} + +size_t DecisionResult::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.decision.DecisionResult) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.decision.ObjectDecisions object_decision = 2; + if (this->has_object_decision()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *object_decision_); + } + + // .apollo.decision.MainDecision main_decision = 3; + if (this->has_main_decision()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *main_decision_); + } + + // .apollo.decision.Debug debug = 4; + if (this->has_debug()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *debug_); + } + + // .apollo.decision.LightSignal light_signal = 5; + if (this->has_light_signal()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *light_signal_); + } + + // .apollo.decision.Stats stats = 6; + if (this->has_stats()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *stats_); + } + + // .apollo.canbus.Signal signal = 7; + if (this->has_signal()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *signal_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void DecisionResult::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.decision.DecisionResult) + GOOGLE_DCHECK_NE(&from, this); + const DecisionResult* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.decision.DecisionResult) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.decision.DecisionResult) + MergeFrom(*source); + } +} + +void DecisionResult::MergeFrom(const DecisionResult& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.decision.DecisionResult) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.has_object_decision()) { + mutable_object_decision()->::apollo::decision::ObjectDecisions::MergeFrom(from.object_decision()); + } + if (from.has_main_decision()) { + mutable_main_decision()->::apollo::decision::MainDecision::MergeFrom(from.main_decision()); + } + if (from.has_debug()) { + mutable_debug()->::apollo::decision::Debug::MergeFrom(from.debug()); + } + if (from.has_light_signal()) { + mutable_light_signal()->::apollo::decision::LightSignal::MergeFrom(from.light_signal()); + } + if (from.has_stats()) { + mutable_stats()->::apollo::decision::Stats::MergeFrom(from.stats()); + } + if (from.has_signal()) { + mutable_signal()->::apollo::canbus::Signal::MergeFrom(from.signal()); + } +} + +void DecisionResult::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.decision.DecisionResult) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void DecisionResult::CopyFrom(const DecisionResult& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.decision.DecisionResult) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool DecisionResult::IsInitialized() const { + return true; +} + +void DecisionResult::Swap(DecisionResult* other) { + if (other == this) return; + InternalSwap(other); +} +void DecisionResult::InternalSwap(DecisionResult* other) { + using std::swap; + swap(header_, other->header_); + swap(object_decision_, other->object_decision_); + swap(main_decision_, other->main_decision_); + swap(debug_, other->debug_); + swap(light_signal_, other->light_signal_); + swap(stats_, other->stats_); + swap(signal_, other->signal_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata DecisionResult::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace decision +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::Range* Arena::CreateMaybeMessage< ::apollo::decision::Range >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::Range >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::TargetLane* Arena::CreateMaybeMessage< ::apollo::decision::TargetLane >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::TargetLane >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::ObjectIgnore* Arena::CreateMaybeMessage< ::apollo::decision::ObjectIgnore >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::ObjectIgnore >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::ObjectStop* Arena::CreateMaybeMessage< ::apollo::decision::ObjectStop >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::ObjectStop >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::ObjectNudge* Arena::CreateMaybeMessage< ::apollo::decision::ObjectNudge >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::ObjectNudge >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::ObjectYield* Arena::CreateMaybeMessage< ::apollo::decision::ObjectYield >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::ObjectYield >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::ObjectFollow* Arena::CreateMaybeMessage< ::apollo::decision::ObjectFollow >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::ObjectFollow >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::ObjectOvertake* Arena::CreateMaybeMessage< ::apollo::decision::ObjectOvertake >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::ObjectOvertake >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::ObjectSidePass* Arena::CreateMaybeMessage< ::apollo::decision::ObjectSidePass >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::ObjectSidePass >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::ObjectAvoid* Arena::CreateMaybeMessage< ::apollo::decision::ObjectAvoid >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::ObjectAvoid >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::ObjectDecisionType* Arena::CreateMaybeMessage< ::apollo::decision::ObjectDecisionType >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::ObjectDecisionType >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::ObjectDecision* Arena::CreateMaybeMessage< ::apollo::decision::ObjectDecision >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::ObjectDecision >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::ObjectDecisions* Arena::CreateMaybeMessage< ::apollo::decision::ObjectDecisions >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::ObjectDecisions >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::StopLine* Arena::CreateMaybeMessage< ::apollo::decision::StopLine >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::StopLine >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::MainStop* Arena::CreateMaybeMessage< ::apollo::decision::MainStop >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::MainStop >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::EmergencyStopHardBrake* Arena::CreateMaybeMessage< ::apollo::decision::EmergencyStopHardBrake >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::EmergencyStopHardBrake >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::EmergencyStopCruiseToStop* Arena::CreateMaybeMessage< ::apollo::decision::EmergencyStopCruiseToStop >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::EmergencyStopCruiseToStop >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::MainEmergencyStop* Arena::CreateMaybeMessage< ::apollo::decision::MainEmergencyStop >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::MainEmergencyStop >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::MainCruise* Arena::CreateMaybeMessage< ::apollo::decision::MainCruise >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::MainCruise >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::MainChangeLane* Arena::CreateMaybeMessage< ::apollo::decision::MainChangeLane >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::MainChangeLane >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::MainMissionComplete* Arena::CreateMaybeMessage< ::apollo::decision::MainMissionComplete >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::MainMissionComplete >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::MainNotReady* Arena::CreateMaybeMessage< ::apollo::decision::MainNotReady >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::MainNotReady >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::MainParking* Arena::CreateMaybeMessage< ::apollo::decision::MainParking >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::MainParking >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::MainDecision* Arena::CreateMaybeMessage< ::apollo::decision::MainDecision >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::MainDecision >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::MasterVehicleDebug* Arena::CreateMaybeMessage< ::apollo::decision::MasterVehicleDebug >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::MasterVehicleDebug >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::ObjectDebug* Arena::CreateMaybeMessage< ::apollo::decision::ObjectDebug >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::ObjectDebug >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::LatencyStats* Arena::CreateMaybeMessage< ::apollo::decision::LatencyStats >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::LatencyStats >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::Stats* Arena::CreateMaybeMessage< ::apollo::decision::Stats >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::Stats >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::ModuleDebug* Arena::CreateMaybeMessage< ::apollo::decision::ModuleDebug >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::ModuleDebug >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::Debug* Arena::CreateMaybeMessage< ::apollo::decision::Debug >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::Debug >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::LightSignal* Arena::CreateMaybeMessage< ::apollo::decision::LightSignal >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::LightSignal >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::decision::DecisionResult* Arena::CreateMaybeMessage< ::apollo::decision::DecisionResult >(Arena* arena) { + return Arena::CreateInternal< ::apollo::decision::DecisionResult >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/decision/decision.pb.h b/apollo_msgs/include/apollo_msgs/proto/decision/decision.pb.h new file mode 100644 index 0000000..ef03981 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/decision/decision.pb.h @@ -0,0 +1,9431 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/decision/decision.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "apollo_msgs/proto/common/header.pb.h" +#include "apollo_msgs/proto/common/geometry.pb.h" +#include "apollo_msgs/proto/prediction/prediction_obstacle.pb.h" +#include "apollo_msgs/proto/canbus/chassis.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[32]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto +namespace apollo { +namespace decision { +class Debug; +class DebugDefaultTypeInternal; +extern DebugDefaultTypeInternal _Debug_default_instance_; +class DecisionResult; +class DecisionResultDefaultTypeInternal; +extern DecisionResultDefaultTypeInternal _DecisionResult_default_instance_; +class EmergencyStopCruiseToStop; +class EmergencyStopCruiseToStopDefaultTypeInternal; +extern EmergencyStopCruiseToStopDefaultTypeInternal _EmergencyStopCruiseToStop_default_instance_; +class EmergencyStopHardBrake; +class EmergencyStopHardBrakeDefaultTypeInternal; +extern EmergencyStopHardBrakeDefaultTypeInternal _EmergencyStopHardBrake_default_instance_; +class LatencyStats; +class LatencyStatsDefaultTypeInternal; +extern LatencyStatsDefaultTypeInternal _LatencyStats_default_instance_; +class LightSignal; +class LightSignalDefaultTypeInternal; +extern LightSignalDefaultTypeInternal _LightSignal_default_instance_; +class MainChangeLane; +class MainChangeLaneDefaultTypeInternal; +extern MainChangeLaneDefaultTypeInternal _MainChangeLane_default_instance_; +class MainCruise; +class MainCruiseDefaultTypeInternal; +extern MainCruiseDefaultTypeInternal _MainCruise_default_instance_; +class MainDecision; +class MainDecisionDefaultTypeInternal; +extern MainDecisionDefaultTypeInternal _MainDecision_default_instance_; +class MainEmergencyStop; +class MainEmergencyStopDefaultTypeInternal; +extern MainEmergencyStopDefaultTypeInternal _MainEmergencyStop_default_instance_; +class MainMissionComplete; +class MainMissionCompleteDefaultTypeInternal; +extern MainMissionCompleteDefaultTypeInternal _MainMissionComplete_default_instance_; +class MainNotReady; +class MainNotReadyDefaultTypeInternal; +extern MainNotReadyDefaultTypeInternal _MainNotReady_default_instance_; +class MainParking; +class MainParkingDefaultTypeInternal; +extern MainParkingDefaultTypeInternal _MainParking_default_instance_; +class MainStop; +class MainStopDefaultTypeInternal; +extern MainStopDefaultTypeInternal _MainStop_default_instance_; +class MasterVehicleDebug; +class MasterVehicleDebugDefaultTypeInternal; +extern MasterVehicleDebugDefaultTypeInternal _MasterVehicleDebug_default_instance_; +class ModuleDebug; +class ModuleDebugDefaultTypeInternal; +extern ModuleDebugDefaultTypeInternal _ModuleDebug_default_instance_; +class ObjectAvoid; +class ObjectAvoidDefaultTypeInternal; +extern ObjectAvoidDefaultTypeInternal _ObjectAvoid_default_instance_; +class ObjectDebug; +class ObjectDebugDefaultTypeInternal; +extern ObjectDebugDefaultTypeInternal _ObjectDebug_default_instance_; +class ObjectDecision; +class ObjectDecisionDefaultTypeInternal; +extern ObjectDecisionDefaultTypeInternal _ObjectDecision_default_instance_; +class ObjectDecisionType; +class ObjectDecisionTypeDefaultTypeInternal; +extern ObjectDecisionTypeDefaultTypeInternal _ObjectDecisionType_default_instance_; +class ObjectDecisions; +class ObjectDecisionsDefaultTypeInternal; +extern ObjectDecisionsDefaultTypeInternal _ObjectDecisions_default_instance_; +class ObjectFollow; +class ObjectFollowDefaultTypeInternal; +extern ObjectFollowDefaultTypeInternal _ObjectFollow_default_instance_; +class ObjectIgnore; +class ObjectIgnoreDefaultTypeInternal; +extern ObjectIgnoreDefaultTypeInternal _ObjectIgnore_default_instance_; +class ObjectNudge; +class ObjectNudgeDefaultTypeInternal; +extern ObjectNudgeDefaultTypeInternal _ObjectNudge_default_instance_; +class ObjectOvertake; +class ObjectOvertakeDefaultTypeInternal; +extern ObjectOvertakeDefaultTypeInternal _ObjectOvertake_default_instance_; +class ObjectSidePass; +class ObjectSidePassDefaultTypeInternal; +extern ObjectSidePassDefaultTypeInternal _ObjectSidePass_default_instance_; +class ObjectStop; +class ObjectStopDefaultTypeInternal; +extern ObjectStopDefaultTypeInternal _ObjectStop_default_instance_; +class ObjectYield; +class ObjectYieldDefaultTypeInternal; +extern ObjectYieldDefaultTypeInternal _ObjectYield_default_instance_; +class Range; +class RangeDefaultTypeInternal; +extern RangeDefaultTypeInternal _Range_default_instance_; +class Stats; +class StatsDefaultTypeInternal; +extern StatsDefaultTypeInternal _Stats_default_instance_; +class StopLine; +class StopLineDefaultTypeInternal; +extern StopLineDefaultTypeInternal _StopLine_default_instance_; +class TargetLane; +class TargetLaneDefaultTypeInternal; +extern TargetLaneDefaultTypeInternal _TargetLane_default_instance_; +} // namespace decision +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::decision::Debug* Arena::CreateMaybeMessage<::apollo::decision::Debug>(Arena*); +template<> ::apollo::decision::DecisionResult* Arena::CreateMaybeMessage<::apollo::decision::DecisionResult>(Arena*); +template<> ::apollo::decision::EmergencyStopCruiseToStop* Arena::CreateMaybeMessage<::apollo::decision::EmergencyStopCruiseToStop>(Arena*); +template<> ::apollo::decision::EmergencyStopHardBrake* Arena::CreateMaybeMessage<::apollo::decision::EmergencyStopHardBrake>(Arena*); +template<> ::apollo::decision::LatencyStats* Arena::CreateMaybeMessage<::apollo::decision::LatencyStats>(Arena*); +template<> ::apollo::decision::LightSignal* Arena::CreateMaybeMessage<::apollo::decision::LightSignal>(Arena*); +template<> ::apollo::decision::MainChangeLane* Arena::CreateMaybeMessage<::apollo::decision::MainChangeLane>(Arena*); +template<> ::apollo::decision::MainCruise* Arena::CreateMaybeMessage<::apollo::decision::MainCruise>(Arena*); +template<> ::apollo::decision::MainDecision* Arena::CreateMaybeMessage<::apollo::decision::MainDecision>(Arena*); +template<> ::apollo::decision::MainEmergencyStop* Arena::CreateMaybeMessage<::apollo::decision::MainEmergencyStop>(Arena*); +template<> ::apollo::decision::MainMissionComplete* Arena::CreateMaybeMessage<::apollo::decision::MainMissionComplete>(Arena*); +template<> ::apollo::decision::MainNotReady* Arena::CreateMaybeMessage<::apollo::decision::MainNotReady>(Arena*); +template<> ::apollo::decision::MainParking* Arena::CreateMaybeMessage<::apollo::decision::MainParking>(Arena*); +template<> ::apollo::decision::MainStop* Arena::CreateMaybeMessage<::apollo::decision::MainStop>(Arena*); +template<> ::apollo::decision::MasterVehicleDebug* Arena::CreateMaybeMessage<::apollo::decision::MasterVehicleDebug>(Arena*); +template<> ::apollo::decision::ModuleDebug* Arena::CreateMaybeMessage<::apollo::decision::ModuleDebug>(Arena*); +template<> ::apollo::decision::ObjectAvoid* Arena::CreateMaybeMessage<::apollo::decision::ObjectAvoid>(Arena*); +template<> ::apollo::decision::ObjectDebug* Arena::CreateMaybeMessage<::apollo::decision::ObjectDebug>(Arena*); +template<> ::apollo::decision::ObjectDecision* Arena::CreateMaybeMessage<::apollo::decision::ObjectDecision>(Arena*); +template<> ::apollo::decision::ObjectDecisionType* Arena::CreateMaybeMessage<::apollo::decision::ObjectDecisionType>(Arena*); +template<> ::apollo::decision::ObjectDecisions* Arena::CreateMaybeMessage<::apollo::decision::ObjectDecisions>(Arena*); +template<> ::apollo::decision::ObjectFollow* Arena::CreateMaybeMessage<::apollo::decision::ObjectFollow>(Arena*); +template<> ::apollo::decision::ObjectIgnore* Arena::CreateMaybeMessage<::apollo::decision::ObjectIgnore>(Arena*); +template<> ::apollo::decision::ObjectNudge* Arena::CreateMaybeMessage<::apollo::decision::ObjectNudge>(Arena*); +template<> ::apollo::decision::ObjectOvertake* Arena::CreateMaybeMessage<::apollo::decision::ObjectOvertake>(Arena*); +template<> ::apollo::decision::ObjectSidePass* Arena::CreateMaybeMessage<::apollo::decision::ObjectSidePass>(Arena*); +template<> ::apollo::decision::ObjectStop* Arena::CreateMaybeMessage<::apollo::decision::ObjectStop>(Arena*); +template<> ::apollo::decision::ObjectYield* Arena::CreateMaybeMessage<::apollo::decision::ObjectYield>(Arena*); +template<> ::apollo::decision::Range* Arena::CreateMaybeMessage<::apollo::decision::Range>(Arena*); +template<> ::apollo::decision::Stats* Arena::CreateMaybeMessage<::apollo::decision::Stats>(Arena*); +template<> ::apollo::decision::StopLine* Arena::CreateMaybeMessage<::apollo::decision::StopLine>(Arena*); +template<> ::apollo::decision::TargetLane* Arena::CreateMaybeMessage<::apollo::decision::TargetLane>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace decision { + +enum ObjectNudge_Type { + ObjectNudge_Type_LEFT_NUDGE = 0, + ObjectNudge_Type_RIGHT_NUDGE = 1, + ObjectNudge_Type_ObjectNudge_Type_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + ObjectNudge_Type_ObjectNudge_Type_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool ObjectNudge_Type_IsValid(int value); +const ObjectNudge_Type ObjectNudge_Type_Type_MIN = ObjectNudge_Type_LEFT_NUDGE; +const ObjectNudge_Type ObjectNudge_Type_Type_MAX = ObjectNudge_Type_RIGHT_NUDGE; +const int ObjectNudge_Type_Type_ARRAYSIZE = ObjectNudge_Type_Type_MAX + 1; + +const ::google::protobuf::EnumDescriptor* ObjectNudge_Type_descriptor(); +inline const ::std::string& ObjectNudge_Type_Name(ObjectNudge_Type value) { + return ::google::protobuf::internal::NameOfEnum( + ObjectNudge_Type_descriptor(), value); +} +inline bool ObjectNudge_Type_Parse( + const ::std::string& name, ObjectNudge_Type* value) { + return ::google::protobuf::internal::ParseNamedEnum( + ObjectNudge_Type_descriptor(), name, value); +} +enum ObjectSidePass_Type { + ObjectSidePass_Type_FOLLOW = 0, + ObjectSidePass_Type_LEAD = 1, + ObjectSidePass_Type_ObjectSidePass_Type_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + ObjectSidePass_Type_ObjectSidePass_Type_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool ObjectSidePass_Type_IsValid(int value); +const ObjectSidePass_Type ObjectSidePass_Type_Type_MIN = ObjectSidePass_Type_FOLLOW; +const ObjectSidePass_Type ObjectSidePass_Type_Type_MAX = ObjectSidePass_Type_LEAD; +const int ObjectSidePass_Type_Type_ARRAYSIZE = ObjectSidePass_Type_Type_MAX + 1; + +const ::google::protobuf::EnumDescriptor* ObjectSidePass_Type_descriptor(); +inline const ::std::string& ObjectSidePass_Type_Name(ObjectSidePass_Type value) { + return ::google::protobuf::internal::NameOfEnum( + ObjectSidePass_Type_descriptor(), value); +} +inline bool ObjectSidePass_Type_Parse( + const ::std::string& name, ObjectSidePass_Type* value) { + return ::google::protobuf::internal::ParseNamedEnum( + ObjectSidePass_Type_descriptor(), name, value); +} +enum ObjectDecision_ObjectType { + ObjectDecision_ObjectType_PREDICTION = 0, + ObjectDecision_ObjectType_PERCEPTION = 1, + ObjectDecision_ObjectType_VIRTUAL = 2, + ObjectDecision_ObjectType_ObjectDecision_ObjectType_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + ObjectDecision_ObjectType_ObjectDecision_ObjectType_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool ObjectDecision_ObjectType_IsValid(int value); +const ObjectDecision_ObjectType ObjectDecision_ObjectType_ObjectType_MIN = ObjectDecision_ObjectType_PREDICTION; +const ObjectDecision_ObjectType ObjectDecision_ObjectType_ObjectType_MAX = ObjectDecision_ObjectType_VIRTUAL; +const int ObjectDecision_ObjectType_ObjectType_ARRAYSIZE = ObjectDecision_ObjectType_ObjectType_MAX + 1; + +const ::google::protobuf::EnumDescriptor* ObjectDecision_ObjectType_descriptor(); +inline const ::std::string& ObjectDecision_ObjectType_Name(ObjectDecision_ObjectType value) { + return ::google::protobuf::internal::NameOfEnum( + ObjectDecision_ObjectType_descriptor(), value); +} +inline bool ObjectDecision_ObjectType_Parse( + const ::std::string& name, ObjectDecision_ObjectType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + ObjectDecision_ObjectType_descriptor(), name, value); +} +enum MainEmergencyStop_ReasonCode { + MainEmergencyStop_ReasonCode_ESTOP_REASON_INTERNAL_ERR = 0, + MainEmergencyStop_ReasonCode_ESTOP_REASON_COLLISION = 1, + MainEmergencyStop_ReasonCode_ESTOP_REASON_ST_FIND_PATH = 2, + MainEmergencyStop_ReasonCode_ESTOP_REASON_ST_MAKE_DECISION = 3, + MainEmergencyStop_ReasonCode_ESTOP_REASON_SENSOR_ERROR = 4, + MainEmergencyStop_ReasonCode_MainEmergencyStop_ReasonCode_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + MainEmergencyStop_ReasonCode_MainEmergencyStop_ReasonCode_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool MainEmergencyStop_ReasonCode_IsValid(int value); +const MainEmergencyStop_ReasonCode MainEmergencyStop_ReasonCode_ReasonCode_MIN = MainEmergencyStop_ReasonCode_ESTOP_REASON_INTERNAL_ERR; +const MainEmergencyStop_ReasonCode MainEmergencyStop_ReasonCode_ReasonCode_MAX = MainEmergencyStop_ReasonCode_ESTOP_REASON_SENSOR_ERROR; +const int MainEmergencyStop_ReasonCode_ReasonCode_ARRAYSIZE = MainEmergencyStop_ReasonCode_ReasonCode_MAX + 1; + +const ::google::protobuf::EnumDescriptor* MainEmergencyStop_ReasonCode_descriptor(); +inline const ::std::string& MainEmergencyStop_ReasonCode_Name(MainEmergencyStop_ReasonCode value) { + return ::google::protobuf::internal::NameOfEnum( + MainEmergencyStop_ReasonCode_descriptor(), value); +} +inline bool MainEmergencyStop_ReasonCode_Parse( + const ::std::string& name, MainEmergencyStop_ReasonCode* value) { + return ::google::protobuf::internal::ParseNamedEnum( + MainEmergencyStop_ReasonCode_descriptor(), name, value); +} +enum MainChangeLane_Type { + MainChangeLane_Type_LEFT = 0, + MainChangeLane_Type_RIGHT = 1, + MainChangeLane_Type_MainChangeLane_Type_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + MainChangeLane_Type_MainChangeLane_Type_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool MainChangeLane_Type_IsValid(int value); +const MainChangeLane_Type MainChangeLane_Type_Type_MIN = MainChangeLane_Type_LEFT; +const MainChangeLane_Type MainChangeLane_Type_Type_MAX = MainChangeLane_Type_RIGHT; +const int MainChangeLane_Type_Type_ARRAYSIZE = MainChangeLane_Type_Type_MAX + 1; + +const ::google::protobuf::EnumDescriptor* MainChangeLane_Type_descriptor(); +inline const ::std::string& MainChangeLane_Type_Name(MainChangeLane_Type value) { + return ::google::protobuf::internal::NameOfEnum( + MainChangeLane_Type_descriptor(), value); +} +inline bool MainChangeLane_Type_Parse( + const ::std::string& name, MainChangeLane_Type* value) { + return ::google::protobuf::internal::ParseNamedEnum( + MainChangeLane_Type_descriptor(), name, value); +} +enum MainParking_Type { + MainParking_Type_FORWARD_PARKING = 0, + MainParking_Type_REVERSE_PARKING = 1, + MainParking_Type_MainParking_Type_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + MainParking_Type_MainParking_Type_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool MainParking_Type_IsValid(int value); +const MainParking_Type MainParking_Type_Type_MIN = MainParking_Type_FORWARD_PARKING; +const MainParking_Type MainParking_Type_Type_MAX = MainParking_Type_REVERSE_PARKING; +const int MainParking_Type_Type_ARRAYSIZE = MainParking_Type_Type_MAX + 1; + +const ::google::protobuf::EnumDescriptor* MainParking_Type_descriptor(); +inline const ::std::string& MainParking_Type_Name(MainParking_Type value) { + return ::google::protobuf::internal::NameOfEnum( + MainParking_Type_descriptor(), value); +} +inline bool MainParking_Type_Parse( + const ::std::string& name, MainParking_Type* value) { + return ::google::protobuf::internal::ParseNamedEnum( + MainParking_Type_descriptor(), name, value); +} +enum LightSignal_TurnSignal { + LightSignal_TurnSignal_NO_TURN = 0, + LightSignal_TurnSignal_LEFT_TURN = 1, + LightSignal_TurnSignal_RIGHT_TURN = 2, + LightSignal_TurnSignal_LightSignal_TurnSignal_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + LightSignal_TurnSignal_LightSignal_TurnSignal_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool LightSignal_TurnSignal_IsValid(int value); +const LightSignal_TurnSignal LightSignal_TurnSignal_TurnSignal_MIN = LightSignal_TurnSignal_NO_TURN; +const LightSignal_TurnSignal LightSignal_TurnSignal_TurnSignal_MAX = LightSignal_TurnSignal_RIGHT_TURN; +const int LightSignal_TurnSignal_TurnSignal_ARRAYSIZE = LightSignal_TurnSignal_TurnSignal_MAX + 1; + +const ::google::protobuf::EnumDescriptor* LightSignal_TurnSignal_descriptor(); +inline const ::std::string& LightSignal_TurnSignal_Name(LightSignal_TurnSignal value) { + return ::google::protobuf::internal::NameOfEnum( + LightSignal_TurnSignal_descriptor(), value); +} +inline bool LightSignal_TurnSignal_Parse( + const ::std::string& name, LightSignal_TurnSignal* value) { + return ::google::protobuf::internal::ParseNamedEnum( + LightSignal_TurnSignal_descriptor(), name, value); +} +enum StopReasonCode { + STOP_REASON_HEAD_VEHICLE = 0, + STOP_REASON_DESTINATION = 1, + STOP_REASON_PEDESTRIAN = 2, + STOP_REASON_OBSTACLE = 3, + STOP_REASON_PREPARKING = 4, + STOP_REASON_SIGNAL = 100, + STOP_REASON_STOP_SIGN = 101, + STOP_REASON_YIELD_SIGN = 102, + STOP_REASON_CLEAR_ZONE = 103, + STOP_REASON_CROSSWALK = 104, + StopReasonCode_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + StopReasonCode_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool StopReasonCode_IsValid(int value); +const StopReasonCode StopReasonCode_MIN = STOP_REASON_HEAD_VEHICLE; +const StopReasonCode StopReasonCode_MAX = STOP_REASON_CROSSWALK; +const int StopReasonCode_ARRAYSIZE = StopReasonCode_MAX + 1; + +const ::google::protobuf::EnumDescriptor* StopReasonCode_descriptor(); +inline const ::std::string& StopReasonCode_Name(StopReasonCode value) { + return ::google::protobuf::internal::NameOfEnum( + StopReasonCode_descriptor(), value); +} +inline bool StopReasonCode_Parse( + const ::std::string& name, StopReasonCode* value) { + return ::google::protobuf::internal::ParseNamedEnum( + StopReasonCode_descriptor(), name, value); +} +// =================================================================== + +class Range : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.Range) */ { + public: + Range(); + virtual ~Range(); + + Range(const Range& from); + + inline Range& operator=(const Range& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Range(Range&& from) noexcept + : Range() { + *this = ::std::move(from); + } + + inline Range& operator=(Range&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Range& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Range* internal_default_instance() { + return reinterpret_cast( + &_Range_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(Range* other); + friend void swap(Range& a, Range& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Range* New() const final { + return CreateMaybeMessage(NULL); + } + + Range* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Range& from); + void MergeFrom(const Range& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Range* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double start = 1; + void clear_start(); + static const int kStartFieldNumber = 1; + double start() const; + void set_start(double value); + + // double end = 2; + void clear_end(); + static const int kEndFieldNumber = 2; + double end() const; + void set_end(double value); + + // @@protoc_insertion_point(class_scope:apollo.decision.Range) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double start_; + double end_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class TargetLane : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.TargetLane) */ { + public: + TargetLane(); + virtual ~TargetLane(); + + TargetLane(const TargetLane& from); + + inline TargetLane& operator=(const TargetLane& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + TargetLane(TargetLane&& from) noexcept + : TargetLane() { + *this = ::std::move(from); + } + + inline TargetLane& operator=(TargetLane&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const TargetLane& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const TargetLane* internal_default_instance() { + return reinterpret_cast( + &_TargetLane_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(TargetLane* other); + friend void swap(TargetLane& a, TargetLane& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline TargetLane* New() const final { + return CreateMaybeMessage(NULL); + } + + TargetLane* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const TargetLane& from); + void MergeFrom(const TargetLane& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(TargetLane* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // string id = 1; + void clear_id(); + static const int kIdFieldNumber = 1; + const ::std::string& id() const; + void set_id(const ::std::string& value); + #if LANG_CXX11 + void set_id(::std::string&& value); + #endif + void set_id(const char* value); + void set_id(const char* value, size_t size); + ::std::string* mutable_id(); + ::std::string* release_id(); + void set_allocated_id(::std::string* id); + + // double start_s = 2; + void clear_start_s(); + static const int kStartSFieldNumber = 2; + double start_s() const; + void set_start_s(double value); + + // double end_s = 3; + void clear_end_s(); + static const int kEndSFieldNumber = 3; + double end_s() const; + void set_end_s(double value); + + // double speed_limit = 4; + void clear_speed_limit(); + static const int kSpeedLimitFieldNumber = 4; + double speed_limit() const; + void set_speed_limit(double value); + + // @@protoc_insertion_point(class_scope:apollo.decision.TargetLane) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr id_; + double start_s_; + double end_s_; + double speed_limit_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ObjectIgnore : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.ObjectIgnore) */ { + public: + ObjectIgnore(); + virtual ~ObjectIgnore(); + + ObjectIgnore(const ObjectIgnore& from); + + inline ObjectIgnore& operator=(const ObjectIgnore& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ObjectIgnore(ObjectIgnore&& from) noexcept + : ObjectIgnore() { + *this = ::std::move(from); + } + + inline ObjectIgnore& operator=(ObjectIgnore&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ObjectIgnore& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ObjectIgnore* internal_default_instance() { + return reinterpret_cast( + &_ObjectIgnore_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + void Swap(ObjectIgnore* other); + friend void swap(ObjectIgnore& a, ObjectIgnore& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ObjectIgnore* New() const final { + return CreateMaybeMessage(NULL); + } + + ObjectIgnore* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ObjectIgnore& from); + void MergeFrom(const ObjectIgnore& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ObjectIgnore* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:apollo.decision.ObjectIgnore) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ObjectStop : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.ObjectStop) */ { + public: + ObjectStop(); + virtual ~ObjectStop(); + + ObjectStop(const ObjectStop& from); + + inline ObjectStop& operator=(const ObjectStop& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ObjectStop(ObjectStop&& from) noexcept + : ObjectStop() { + *this = ::std::move(from); + } + + inline ObjectStop& operator=(ObjectStop&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ObjectStop& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ObjectStop* internal_default_instance() { + return reinterpret_cast( + &_ObjectStop_default_instance_); + } + static constexpr int kIndexInFileMessages = + 3; + + void Swap(ObjectStop* other); + friend void swap(ObjectStop& a, ObjectStop& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ObjectStop* New() const final { + return CreateMaybeMessage(NULL); + } + + ObjectStop* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ObjectStop& from); + void MergeFrom(const ObjectStop& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ObjectStop* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.decision.Range preferred_distance_s = 2; + bool has_preferred_distance_s() const; + void clear_preferred_distance_s(); + static const int kPreferredDistanceSFieldNumber = 2; + private: + const ::apollo::decision::Range& _internal_preferred_distance_s() const; + public: + const ::apollo::decision::Range& preferred_distance_s() const; + ::apollo::decision::Range* release_preferred_distance_s(); + ::apollo::decision::Range* mutable_preferred_distance_s(); + void set_allocated_preferred_distance_s(::apollo::decision::Range* preferred_distance_s); + + // .apollo.common.PointENU stop_point = 4; + bool has_stop_point() const; + void clear_stop_point(); + static const int kStopPointFieldNumber = 4; + private: + const ::apollo::common::PointENU& _internal_stop_point() const; + public: + const ::apollo::common::PointENU& stop_point() const; + ::apollo::common::PointENU* release_stop_point(); + ::apollo::common::PointENU* mutable_stop_point(); + void set_allocated_stop_point(::apollo::common::PointENU* stop_point); + + // double distance_s = 1; + void clear_distance_s(); + static const int kDistanceSFieldNumber = 1; + double distance_s() const; + void set_distance_s(double value); + + // .apollo.decision.StopReasonCode reason_code = 3; + void clear_reason_code(); + static const int kReasonCodeFieldNumber = 3; + ::apollo::decision::StopReasonCode reason_code() const; + void set_reason_code(::apollo::decision::StopReasonCode value); + + // @@protoc_insertion_point(class_scope:apollo.decision.ObjectStop) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::decision::Range* preferred_distance_s_; + ::apollo::common::PointENU* stop_point_; + double distance_s_; + int reason_code_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ObjectNudge : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.ObjectNudge) */ { + public: + ObjectNudge(); + virtual ~ObjectNudge(); + + ObjectNudge(const ObjectNudge& from); + + inline ObjectNudge& operator=(const ObjectNudge& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ObjectNudge(ObjectNudge&& from) noexcept + : ObjectNudge() { + *this = ::std::move(from); + } + + inline ObjectNudge& operator=(ObjectNudge&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ObjectNudge& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ObjectNudge* internal_default_instance() { + return reinterpret_cast( + &_ObjectNudge_default_instance_); + } + static constexpr int kIndexInFileMessages = + 4; + + void Swap(ObjectNudge* other); + friend void swap(ObjectNudge& a, ObjectNudge& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ObjectNudge* New() const final { + return CreateMaybeMessage(NULL); + } + + ObjectNudge* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ObjectNudge& from); + void MergeFrom(const ObjectNudge& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ObjectNudge* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef ObjectNudge_Type Type; + static const Type LEFT_NUDGE = + ObjectNudge_Type_LEFT_NUDGE; + static const Type RIGHT_NUDGE = + ObjectNudge_Type_RIGHT_NUDGE; + static inline bool Type_IsValid(int value) { + return ObjectNudge_Type_IsValid(value); + } + static const Type Type_MIN = + ObjectNudge_Type_Type_MIN; + static const Type Type_MAX = + ObjectNudge_Type_Type_MAX; + static const int Type_ARRAYSIZE = + ObjectNudge_Type_Type_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Type_descriptor() { + return ObjectNudge_Type_descriptor(); + } + static inline const ::std::string& Type_Name(Type value) { + return ObjectNudge_Type_Name(value); + } + static inline bool Type_Parse(const ::std::string& name, + Type* value) { + return ObjectNudge_Type_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // .apollo.decision.Range preferred_distance_l = 3; + bool has_preferred_distance_l() const; + void clear_preferred_distance_l(); + static const int kPreferredDistanceLFieldNumber = 3; + private: + const ::apollo::decision::Range& _internal_preferred_distance_l() const; + public: + const ::apollo::decision::Range& preferred_distance_l() const; + ::apollo::decision::Range* release_preferred_distance_l(); + ::apollo::decision::Range* mutable_preferred_distance_l(); + void set_allocated_preferred_distance_l(::apollo::decision::Range* preferred_distance_l); + + // double distance_l = 1; + void clear_distance_l(); + static const int kDistanceLFieldNumber = 1; + double distance_l() const; + void set_distance_l(double value); + + // .apollo.decision.ObjectNudge.Type type = 2; + void clear_type(); + static const int kTypeFieldNumber = 2; + ::apollo::decision::ObjectNudge_Type type() const; + void set_type(::apollo::decision::ObjectNudge_Type value); + + // @@protoc_insertion_point(class_scope:apollo.decision.ObjectNudge) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::decision::Range* preferred_distance_l_; + double distance_l_; + int type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ObjectYield : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.ObjectYield) */ { + public: + ObjectYield(); + virtual ~ObjectYield(); + + ObjectYield(const ObjectYield& from); + + inline ObjectYield& operator=(const ObjectYield& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ObjectYield(ObjectYield&& from) noexcept + : ObjectYield() { + *this = ::std::move(from); + } + + inline ObjectYield& operator=(ObjectYield&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ObjectYield& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ObjectYield* internal_default_instance() { + return reinterpret_cast( + &_ObjectYield_default_instance_); + } + static constexpr int kIndexInFileMessages = + 5; + + void Swap(ObjectYield* other); + friend void swap(ObjectYield& a, ObjectYield& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ObjectYield* New() const final { + return CreateMaybeMessage(NULL); + } + + ObjectYield* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ObjectYield& from); + void MergeFrom(const ObjectYield& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ObjectYield* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.decision.Range preferred_distance_s = 2; + bool has_preferred_distance_s() const; + void clear_preferred_distance_s(); + static const int kPreferredDistanceSFieldNumber = 2; + private: + const ::apollo::decision::Range& _internal_preferred_distance_s() const; + public: + const ::apollo::decision::Range& preferred_distance_s() const; + ::apollo::decision::Range* release_preferred_distance_s(); + ::apollo::decision::Range* mutable_preferred_distance_s(); + void set_allocated_preferred_distance_s(::apollo::decision::Range* preferred_distance_s); + + // .apollo.common.PointENU yield_point = 3; + bool has_yield_point() const; + void clear_yield_point(); + static const int kYieldPointFieldNumber = 3; + private: + const ::apollo::common::PointENU& _internal_yield_point() const; + public: + const ::apollo::common::PointENU& yield_point() const; + ::apollo::common::PointENU* release_yield_point(); + ::apollo::common::PointENU* mutable_yield_point(); + void set_allocated_yield_point(::apollo::common::PointENU* yield_point); + + // double distance_s = 1; + void clear_distance_s(); + static const int kDistanceSFieldNumber = 1; + double distance_s() const; + void set_distance_s(double value); + + // @@protoc_insertion_point(class_scope:apollo.decision.ObjectYield) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::decision::Range* preferred_distance_s_; + ::apollo::common::PointENU* yield_point_; + double distance_s_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ObjectFollow : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.ObjectFollow) */ { + public: + ObjectFollow(); + virtual ~ObjectFollow(); + + ObjectFollow(const ObjectFollow& from); + + inline ObjectFollow& operator=(const ObjectFollow& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ObjectFollow(ObjectFollow&& from) noexcept + : ObjectFollow() { + *this = ::std::move(from); + } + + inline ObjectFollow& operator=(ObjectFollow&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ObjectFollow& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ObjectFollow* internal_default_instance() { + return reinterpret_cast( + &_ObjectFollow_default_instance_); + } + static constexpr int kIndexInFileMessages = + 6; + + void Swap(ObjectFollow* other); + friend void swap(ObjectFollow& a, ObjectFollow& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ObjectFollow* New() const final { + return CreateMaybeMessage(NULL); + } + + ObjectFollow* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ObjectFollow& from); + void MergeFrom(const ObjectFollow& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ObjectFollow* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.decision.Range preferred_distance_s = 2; + bool has_preferred_distance_s() const; + void clear_preferred_distance_s(); + static const int kPreferredDistanceSFieldNumber = 2; + private: + const ::apollo::decision::Range& _internal_preferred_distance_s() const; + public: + const ::apollo::decision::Range& preferred_distance_s() const; + ::apollo::decision::Range* release_preferred_distance_s(); + ::apollo::decision::Range* mutable_preferred_distance_s(); + void set_allocated_preferred_distance_s(::apollo::decision::Range* preferred_distance_s); + + // .apollo.common.PointENU follow_point = 3; + bool has_follow_point() const; + void clear_follow_point(); + static const int kFollowPointFieldNumber = 3; + private: + const ::apollo::common::PointENU& _internal_follow_point() const; + public: + const ::apollo::common::PointENU& follow_point() const; + ::apollo::common::PointENU* release_follow_point(); + ::apollo::common::PointENU* mutable_follow_point(); + void set_allocated_follow_point(::apollo::common::PointENU* follow_point); + + // double distance_s = 1; + void clear_distance_s(); + static const int kDistanceSFieldNumber = 1; + double distance_s() const; + void set_distance_s(double value); + + // @@protoc_insertion_point(class_scope:apollo.decision.ObjectFollow) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::decision::Range* preferred_distance_s_; + ::apollo::common::PointENU* follow_point_; + double distance_s_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ObjectOvertake : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.ObjectOvertake) */ { + public: + ObjectOvertake(); + virtual ~ObjectOvertake(); + + ObjectOvertake(const ObjectOvertake& from); + + inline ObjectOvertake& operator=(const ObjectOvertake& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ObjectOvertake(ObjectOvertake&& from) noexcept + : ObjectOvertake() { + *this = ::std::move(from); + } + + inline ObjectOvertake& operator=(ObjectOvertake&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ObjectOvertake& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ObjectOvertake* internal_default_instance() { + return reinterpret_cast( + &_ObjectOvertake_default_instance_); + } + static constexpr int kIndexInFileMessages = + 7; + + void Swap(ObjectOvertake* other); + friend void swap(ObjectOvertake& a, ObjectOvertake& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ObjectOvertake* New() const final { + return CreateMaybeMessage(NULL); + } + + ObjectOvertake* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ObjectOvertake& from); + void MergeFrom(const ObjectOvertake& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ObjectOvertake* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.decision.Range preferred_distance_s = 2; + bool has_preferred_distance_s() const; + void clear_preferred_distance_s(); + static const int kPreferredDistanceSFieldNumber = 2; + private: + const ::apollo::decision::Range& _internal_preferred_distance_s() const; + public: + const ::apollo::decision::Range& preferred_distance_s() const; + ::apollo::decision::Range* release_preferred_distance_s(); + ::apollo::decision::Range* mutable_preferred_distance_s(); + void set_allocated_preferred_distance_s(::apollo::decision::Range* preferred_distance_s); + + // .apollo.common.PointENU overtake_point = 3; + bool has_overtake_point() const; + void clear_overtake_point(); + static const int kOvertakePointFieldNumber = 3; + private: + const ::apollo::common::PointENU& _internal_overtake_point() const; + public: + const ::apollo::common::PointENU& overtake_point() const; + ::apollo::common::PointENU* release_overtake_point(); + ::apollo::common::PointENU* mutable_overtake_point(); + void set_allocated_overtake_point(::apollo::common::PointENU* overtake_point); + + // double distance_s = 1; + void clear_distance_s(); + static const int kDistanceSFieldNumber = 1; + double distance_s() const; + void set_distance_s(double value); + + // @@protoc_insertion_point(class_scope:apollo.decision.ObjectOvertake) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::decision::Range* preferred_distance_s_; + ::apollo::common::PointENU* overtake_point_; + double distance_s_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ObjectSidePass : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.ObjectSidePass) */ { + public: + ObjectSidePass(); + virtual ~ObjectSidePass(); + + ObjectSidePass(const ObjectSidePass& from); + + inline ObjectSidePass& operator=(const ObjectSidePass& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ObjectSidePass(ObjectSidePass&& from) noexcept + : ObjectSidePass() { + *this = ::std::move(from); + } + + inline ObjectSidePass& operator=(ObjectSidePass&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ObjectSidePass& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ObjectSidePass* internal_default_instance() { + return reinterpret_cast( + &_ObjectSidePass_default_instance_); + } + static constexpr int kIndexInFileMessages = + 8; + + void Swap(ObjectSidePass* other); + friend void swap(ObjectSidePass& a, ObjectSidePass& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ObjectSidePass* New() const final { + return CreateMaybeMessage(NULL); + } + + ObjectSidePass* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ObjectSidePass& from); + void MergeFrom(const ObjectSidePass& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ObjectSidePass* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef ObjectSidePass_Type Type; + static const Type FOLLOW = + ObjectSidePass_Type_FOLLOW; + static const Type LEAD = + ObjectSidePass_Type_LEAD; + static inline bool Type_IsValid(int value) { + return ObjectSidePass_Type_IsValid(value); + } + static const Type Type_MIN = + ObjectSidePass_Type_Type_MIN; + static const Type Type_MAX = + ObjectSidePass_Type_Type_MAX; + static const int Type_ARRAYSIZE = + ObjectSidePass_Type_Type_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Type_descriptor() { + return ObjectSidePass_Type_descriptor(); + } + static inline const ::std::string& Type_Name(Type value) { + return ObjectSidePass_Type_Name(value); + } + static inline bool Type_Parse(const ::std::string& name, + Type* value) { + return ObjectSidePass_Type_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // .apollo.decision.Range preferred_distance_s = 2; + bool has_preferred_distance_s() const; + void clear_preferred_distance_s(); + static const int kPreferredDistanceSFieldNumber = 2; + private: + const ::apollo::decision::Range& _internal_preferred_distance_s() const; + public: + const ::apollo::decision::Range& preferred_distance_s() const; + ::apollo::decision::Range* release_preferred_distance_s(); + ::apollo::decision::Range* mutable_preferred_distance_s(); + void set_allocated_preferred_distance_s(::apollo::decision::Range* preferred_distance_s); + + // double distance_s = 1; + void clear_distance_s(); + static const int kDistanceSFieldNumber = 1; + double distance_s() const; + void set_distance_s(double value); + + // .apollo.decision.ObjectSidePass.Type type = 3; + void clear_type(); + static const int kTypeFieldNumber = 3; + ::apollo::decision::ObjectSidePass_Type type() const; + void set_type(::apollo::decision::ObjectSidePass_Type value); + + // @@protoc_insertion_point(class_scope:apollo.decision.ObjectSidePass) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::decision::Range* preferred_distance_s_; + double distance_s_; + int type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ObjectAvoid : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.ObjectAvoid) */ { + public: + ObjectAvoid(); + virtual ~ObjectAvoid(); + + ObjectAvoid(const ObjectAvoid& from); + + inline ObjectAvoid& operator=(const ObjectAvoid& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ObjectAvoid(ObjectAvoid&& from) noexcept + : ObjectAvoid() { + *this = ::std::move(from); + } + + inline ObjectAvoid& operator=(ObjectAvoid&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ObjectAvoid& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ObjectAvoid* internal_default_instance() { + return reinterpret_cast( + &_ObjectAvoid_default_instance_); + } + static constexpr int kIndexInFileMessages = + 9; + + void Swap(ObjectAvoid* other); + friend void swap(ObjectAvoid& a, ObjectAvoid& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ObjectAvoid* New() const final { + return CreateMaybeMessage(NULL); + } + + ObjectAvoid* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ObjectAvoid& from); + void MergeFrom(const ObjectAvoid& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ObjectAvoid* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:apollo.decision.ObjectAvoid) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ObjectDecisionType : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.ObjectDecisionType) */ { + public: + ObjectDecisionType(); + virtual ~ObjectDecisionType(); + + ObjectDecisionType(const ObjectDecisionType& from); + + inline ObjectDecisionType& operator=(const ObjectDecisionType& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ObjectDecisionType(ObjectDecisionType&& from) noexcept + : ObjectDecisionType() { + *this = ::std::move(from); + } + + inline ObjectDecisionType& operator=(ObjectDecisionType&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ObjectDecisionType& default_instance(); + + enum ObjectTagCase { + kIgnore = 1, + kStop = 2, + kFollow = 3, + kYield = 4, + kOvertake = 5, + kNudge = 6, + kSidepass = 7, + kAvoid = 8, + OBJECT_TAG_NOT_SET = 0, + }; + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ObjectDecisionType* internal_default_instance() { + return reinterpret_cast( + &_ObjectDecisionType_default_instance_); + } + static constexpr int kIndexInFileMessages = + 10; + + void Swap(ObjectDecisionType* other); + friend void swap(ObjectDecisionType& a, ObjectDecisionType& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ObjectDecisionType* New() const final { + return CreateMaybeMessage(NULL); + } + + ObjectDecisionType* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ObjectDecisionType& from); + void MergeFrom(const ObjectDecisionType& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ObjectDecisionType* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.decision.ObjectIgnore ignore = 1; + bool has_ignore() const; + void clear_ignore(); + static const int kIgnoreFieldNumber = 1; + private: + const ::apollo::decision::ObjectIgnore& _internal_ignore() const; + public: + const ::apollo::decision::ObjectIgnore& ignore() const; + ::apollo::decision::ObjectIgnore* release_ignore(); + ::apollo::decision::ObjectIgnore* mutable_ignore(); + void set_allocated_ignore(::apollo::decision::ObjectIgnore* ignore); + + // .apollo.decision.ObjectStop stop = 2; + bool has_stop() const; + void clear_stop(); + static const int kStopFieldNumber = 2; + private: + const ::apollo::decision::ObjectStop& _internal_stop() const; + public: + const ::apollo::decision::ObjectStop& stop() const; + ::apollo::decision::ObjectStop* release_stop(); + ::apollo::decision::ObjectStop* mutable_stop(); + void set_allocated_stop(::apollo::decision::ObjectStop* stop); + + // .apollo.decision.ObjectFollow follow = 3; + bool has_follow() const; + void clear_follow(); + static const int kFollowFieldNumber = 3; + private: + const ::apollo::decision::ObjectFollow& _internal_follow() const; + public: + const ::apollo::decision::ObjectFollow& follow() const; + ::apollo::decision::ObjectFollow* release_follow(); + ::apollo::decision::ObjectFollow* mutable_follow(); + void set_allocated_follow(::apollo::decision::ObjectFollow* follow); + + // .apollo.decision.ObjectYield yield = 4; + bool has_yield() const; + void clear_yield(); + static const int kYieldFieldNumber = 4; + private: + const ::apollo::decision::ObjectYield& _internal_yield() const; + public: + const ::apollo::decision::ObjectYield& yield() const; + ::apollo::decision::ObjectYield* release_yield(); + ::apollo::decision::ObjectYield* mutable_yield(); + void set_allocated_yield(::apollo::decision::ObjectYield* yield); + + // .apollo.decision.ObjectOvertake overtake = 5; + bool has_overtake() const; + void clear_overtake(); + static const int kOvertakeFieldNumber = 5; + private: + const ::apollo::decision::ObjectOvertake& _internal_overtake() const; + public: + const ::apollo::decision::ObjectOvertake& overtake() const; + ::apollo::decision::ObjectOvertake* release_overtake(); + ::apollo::decision::ObjectOvertake* mutable_overtake(); + void set_allocated_overtake(::apollo::decision::ObjectOvertake* overtake); + + // .apollo.decision.ObjectNudge nudge = 6; + bool has_nudge() const; + void clear_nudge(); + static const int kNudgeFieldNumber = 6; + private: + const ::apollo::decision::ObjectNudge& _internal_nudge() const; + public: + const ::apollo::decision::ObjectNudge& nudge() const; + ::apollo::decision::ObjectNudge* release_nudge(); + ::apollo::decision::ObjectNudge* mutable_nudge(); + void set_allocated_nudge(::apollo::decision::ObjectNudge* nudge); + + // .apollo.decision.ObjectSidePass sidepass = 7; + bool has_sidepass() const; + void clear_sidepass(); + static const int kSidepassFieldNumber = 7; + private: + const ::apollo::decision::ObjectSidePass& _internal_sidepass() const; + public: + const ::apollo::decision::ObjectSidePass& sidepass() const; + ::apollo::decision::ObjectSidePass* release_sidepass(); + ::apollo::decision::ObjectSidePass* mutable_sidepass(); + void set_allocated_sidepass(::apollo::decision::ObjectSidePass* sidepass); + + // .apollo.decision.ObjectAvoid avoid = 8; + bool has_avoid() const; + void clear_avoid(); + static const int kAvoidFieldNumber = 8; + private: + const ::apollo::decision::ObjectAvoid& _internal_avoid() const; + public: + const ::apollo::decision::ObjectAvoid& avoid() const; + ::apollo::decision::ObjectAvoid* release_avoid(); + ::apollo::decision::ObjectAvoid* mutable_avoid(); + void set_allocated_avoid(::apollo::decision::ObjectAvoid* avoid); + + void clear_object_tag(); + ObjectTagCase object_tag_case() const; + // @@protoc_insertion_point(class_scope:apollo.decision.ObjectDecisionType) + private: + void set_has_ignore(); + void set_has_stop(); + void set_has_follow(); + void set_has_yield(); + void set_has_overtake(); + void set_has_nudge(); + void set_has_sidepass(); + void set_has_avoid(); + + inline bool has_object_tag() const; + inline void clear_has_object_tag(); + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + union ObjectTagUnion { + ObjectTagUnion() {} + ::apollo::decision::ObjectIgnore* ignore_; + ::apollo::decision::ObjectStop* stop_; + ::apollo::decision::ObjectFollow* follow_; + ::apollo::decision::ObjectYield* yield_; + ::apollo::decision::ObjectOvertake* overtake_; + ::apollo::decision::ObjectNudge* nudge_; + ::apollo::decision::ObjectSidePass* sidepass_; + ::apollo::decision::ObjectAvoid* avoid_; + } object_tag_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::google::protobuf::uint32 _oneof_case_[1]; + + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ObjectDecision : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.ObjectDecision) */ { + public: + ObjectDecision(); + virtual ~ObjectDecision(); + + ObjectDecision(const ObjectDecision& from); + + inline ObjectDecision& operator=(const ObjectDecision& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ObjectDecision(ObjectDecision&& from) noexcept + : ObjectDecision() { + *this = ::std::move(from); + } + + inline ObjectDecision& operator=(ObjectDecision&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ObjectDecision& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ObjectDecision* internal_default_instance() { + return reinterpret_cast( + &_ObjectDecision_default_instance_); + } + static constexpr int kIndexInFileMessages = + 11; + + void Swap(ObjectDecision* other); + friend void swap(ObjectDecision& a, ObjectDecision& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ObjectDecision* New() const final { + return CreateMaybeMessage(NULL); + } + + ObjectDecision* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ObjectDecision& from); + void MergeFrom(const ObjectDecision& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ObjectDecision* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef ObjectDecision_ObjectType ObjectType; + static const ObjectType PREDICTION = + ObjectDecision_ObjectType_PREDICTION; + static const ObjectType PERCEPTION = + ObjectDecision_ObjectType_PERCEPTION; + static const ObjectType VIRTUAL = + ObjectDecision_ObjectType_VIRTUAL; + static inline bool ObjectType_IsValid(int value) { + return ObjectDecision_ObjectType_IsValid(value); + } + static const ObjectType ObjectType_MIN = + ObjectDecision_ObjectType_ObjectType_MIN; + static const ObjectType ObjectType_MAX = + ObjectDecision_ObjectType_ObjectType_MAX; + static const int ObjectType_ARRAYSIZE = + ObjectDecision_ObjectType_ObjectType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + ObjectType_descriptor() { + return ObjectDecision_ObjectType_descriptor(); + } + static inline const ::std::string& ObjectType_Name(ObjectType value) { + return ObjectDecision_ObjectType_Name(value); + } + static inline bool ObjectType_Parse(const ::std::string& name, + ObjectType* value) { + return ObjectDecision_ObjectType_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // repeated .apollo.decision.ObjectDecisionType object_decision = 5; + int object_decision_size() const; + void clear_object_decision(); + static const int kObjectDecisionFieldNumber = 5; + ::apollo::decision::ObjectDecisionType* mutable_object_decision(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecisionType >* + mutable_object_decision(); + const ::apollo::decision::ObjectDecisionType& object_decision(int index) const; + ::apollo::decision::ObjectDecisionType* add_object_decision(); + const ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecisionType >& + object_decision() const; + + // string id = 2; + void clear_id(); + static const int kIdFieldNumber = 2; + const ::std::string& id() const; + void set_id(const ::std::string& value); + #if LANG_CXX11 + void set_id(::std::string&& value); + #endif + void set_id(const char* value); + void set_id(const char* value, size_t size); + ::std::string* mutable_id(); + ::std::string* release_id(); + void set_allocated_id(::std::string* id); + + // .apollo.prediction.PredictionObstacle prediction = 1; + bool has_prediction() const; + void clear_prediction(); + static const int kPredictionFieldNumber = 1; + private: + const ::apollo::prediction::PredictionObstacle& _internal_prediction() const; + public: + const ::apollo::prediction::PredictionObstacle& prediction() const; + ::apollo::prediction::PredictionObstacle* release_prediction(); + ::apollo::prediction::PredictionObstacle* mutable_prediction(); + void set_allocated_prediction(::apollo::prediction::PredictionObstacle* prediction); + + // .apollo.decision.ObjectDecisionType decision = 4; + bool has_decision() const; + void clear_decision(); + static const int kDecisionFieldNumber = 4; + private: + const ::apollo::decision::ObjectDecisionType& _internal_decision() const; + public: + const ::apollo::decision::ObjectDecisionType& decision() const; + ::apollo::decision::ObjectDecisionType* release_decision(); + ::apollo::decision::ObjectDecisionType* mutable_decision(); + void set_allocated_decision(::apollo::decision::ObjectDecisionType* decision); + + // .apollo.decision.ObjectDecision.ObjectType type = 3; + void clear_type(); + static const int kTypeFieldNumber = 3; + ::apollo::decision::ObjectDecision_ObjectType type() const; + void set_type(::apollo::decision::ObjectDecision_ObjectType value); + + // @@protoc_insertion_point(class_scope:apollo.decision.ObjectDecision) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecisionType > object_decision_; + ::google::protobuf::internal::ArenaStringPtr id_; + ::apollo::prediction::PredictionObstacle* prediction_; + ::apollo::decision::ObjectDecisionType* decision_; + int type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ObjectDecisions : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.ObjectDecisions) */ { + public: + ObjectDecisions(); + virtual ~ObjectDecisions(); + + ObjectDecisions(const ObjectDecisions& from); + + inline ObjectDecisions& operator=(const ObjectDecisions& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ObjectDecisions(ObjectDecisions&& from) noexcept + : ObjectDecisions() { + *this = ::std::move(from); + } + + inline ObjectDecisions& operator=(ObjectDecisions&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ObjectDecisions& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ObjectDecisions* internal_default_instance() { + return reinterpret_cast( + &_ObjectDecisions_default_instance_); + } + static constexpr int kIndexInFileMessages = + 12; + + void Swap(ObjectDecisions* other); + friend void swap(ObjectDecisions& a, ObjectDecisions& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ObjectDecisions* New() const final { + return CreateMaybeMessage(NULL); + } + + ObjectDecisions* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ObjectDecisions& from); + void MergeFrom(const ObjectDecisions& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ObjectDecisions* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.decision.ObjectDecision decision = 1; + int decision_size() const; + void clear_decision(); + static const int kDecisionFieldNumber = 1; + ::apollo::decision::ObjectDecision* mutable_decision(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecision >* + mutable_decision(); + const ::apollo::decision::ObjectDecision& decision(int index) const; + ::apollo::decision::ObjectDecision* add_decision(); + const ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecision >& + decision() const; + + // @@protoc_insertion_point(class_scope:apollo.decision.ObjectDecisions) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecision > decision_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class StopLine : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.StopLine) */ { + public: + StopLine(); + virtual ~StopLine(); + + StopLine(const StopLine& from); + + inline StopLine& operator=(const StopLine& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + StopLine(StopLine&& from) noexcept + : StopLine() { + *this = ::std::move(from); + } + + inline StopLine& operator=(StopLine&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const StopLine& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const StopLine* internal_default_instance() { + return reinterpret_cast( + &_StopLine_default_instance_); + } + static constexpr int kIndexInFileMessages = + 13; + + void Swap(StopLine* other); + friend void swap(StopLine& a, StopLine& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline StopLine* New() const final { + return CreateMaybeMessage(NULL); + } + + StopLine* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const StopLine& from); + void MergeFrom(const StopLine& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(StopLine* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // string lane_id = 1; + void clear_lane_id(); + static const int kLaneIdFieldNumber = 1; + const ::std::string& lane_id() const; + void set_lane_id(const ::std::string& value); + #if LANG_CXX11 + void set_lane_id(::std::string&& value); + #endif + void set_lane_id(const char* value); + void set_lane_id(const char* value, size_t size); + ::std::string* mutable_lane_id(); + ::std::string* release_lane_id(); + void set_allocated_lane_id(::std::string* lane_id); + + // double distance_s = 2; + void clear_distance_s(); + static const int kDistanceSFieldNumber = 2; + double distance_s() const; + void set_distance_s(double value); + + // @@protoc_insertion_point(class_scope:apollo.decision.StopLine) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr lane_id_; + double distance_s_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class MainStop : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.MainStop) */ { + public: + MainStop(); + virtual ~MainStop(); + + MainStop(const MainStop& from); + + inline MainStop& operator=(const MainStop& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + MainStop(MainStop&& from) noexcept + : MainStop() { + *this = ::std::move(from); + } + + inline MainStop& operator=(MainStop&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const MainStop& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const MainStop* internal_default_instance() { + return reinterpret_cast( + &_MainStop_default_instance_); + } + static constexpr int kIndexInFileMessages = + 14; + + void Swap(MainStop* other); + friend void swap(MainStop& a, MainStop& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline MainStop* New() const final { + return CreateMaybeMessage(NULL); + } + + MainStop* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const MainStop& from); + void MergeFrom(const MainStop& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(MainStop* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // string reason = 4; + void clear_reason(); + static const int kReasonFieldNumber = 4; + const ::std::string& reason() const; + void set_reason(const ::std::string& value); + #if LANG_CXX11 + void set_reason(::std::string&& value); + #endif + void set_reason(const char* value); + void set_reason(const char* value, size_t size); + ::std::string* mutable_reason(); + ::std::string* release_reason(); + void set_allocated_reason(::std::string* reason); + + // .apollo.decision.StopLine enforced_line = 1; + bool has_enforced_line() const; + void clear_enforced_line(); + static const int kEnforcedLineFieldNumber = 1; + private: + const ::apollo::decision::StopLine& _internal_enforced_line() const; + public: + const ::apollo::decision::StopLine& enforced_line() const; + ::apollo::decision::StopLine* release_enforced_line(); + ::apollo::decision::StopLine* mutable_enforced_line(); + void set_allocated_enforced_line(::apollo::decision::StopLine* enforced_line); + + // .apollo.decision.StopLine preferred_start = 2; + bool has_preferred_start() const; + void clear_preferred_start(); + static const int kPreferredStartFieldNumber = 2; + private: + const ::apollo::decision::StopLine& _internal_preferred_start() const; + public: + const ::apollo::decision::StopLine& preferred_start() const; + ::apollo::decision::StopLine* release_preferred_start(); + ::apollo::decision::StopLine* mutable_preferred_start(); + void set_allocated_preferred_start(::apollo::decision::StopLine* preferred_start); + + // .apollo.decision.StopLine preferred_end = 3; + bool has_preferred_end() const; + void clear_preferred_end(); + static const int kPreferredEndFieldNumber = 3; + private: + const ::apollo::decision::StopLine& _internal_preferred_end() const; + public: + const ::apollo::decision::StopLine& preferred_end() const; + ::apollo::decision::StopLine* release_preferred_end(); + ::apollo::decision::StopLine* mutable_preferred_end(); + void set_allocated_preferred_end(::apollo::decision::StopLine* preferred_end); + + // .apollo.common.PointENU stop_point = 6; + bool has_stop_point() const; + void clear_stop_point(); + static const int kStopPointFieldNumber = 6; + private: + const ::apollo::common::PointENU& _internal_stop_point() const; + public: + const ::apollo::common::PointENU& stop_point() const; + ::apollo::common::PointENU* release_stop_point(); + ::apollo::common::PointENU* mutable_stop_point(); + void set_allocated_stop_point(::apollo::common::PointENU* stop_point); + + // double stop_heading = 7; + void clear_stop_heading(); + static const int kStopHeadingFieldNumber = 7; + double stop_heading() const; + void set_stop_heading(double value); + + // .apollo.decision.StopReasonCode reason_code = 5; + void clear_reason_code(); + static const int kReasonCodeFieldNumber = 5; + ::apollo::decision::StopReasonCode reason_code() const; + void set_reason_code(::apollo::decision::StopReasonCode value); + + // @@protoc_insertion_point(class_scope:apollo.decision.MainStop) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr reason_; + ::apollo::decision::StopLine* enforced_line_; + ::apollo::decision::StopLine* preferred_start_; + ::apollo::decision::StopLine* preferred_end_; + ::apollo::common::PointENU* stop_point_; + double stop_heading_; + int reason_code_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class EmergencyStopHardBrake : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.EmergencyStopHardBrake) */ { + public: + EmergencyStopHardBrake(); + virtual ~EmergencyStopHardBrake(); + + EmergencyStopHardBrake(const EmergencyStopHardBrake& from); + + inline EmergencyStopHardBrake& operator=(const EmergencyStopHardBrake& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + EmergencyStopHardBrake(EmergencyStopHardBrake&& from) noexcept + : EmergencyStopHardBrake() { + *this = ::std::move(from); + } + + inline EmergencyStopHardBrake& operator=(EmergencyStopHardBrake&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const EmergencyStopHardBrake& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const EmergencyStopHardBrake* internal_default_instance() { + return reinterpret_cast( + &_EmergencyStopHardBrake_default_instance_); + } + static constexpr int kIndexInFileMessages = + 15; + + void Swap(EmergencyStopHardBrake* other); + friend void swap(EmergencyStopHardBrake& a, EmergencyStopHardBrake& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline EmergencyStopHardBrake* New() const final { + return CreateMaybeMessage(NULL); + } + + EmergencyStopHardBrake* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const EmergencyStopHardBrake& from); + void MergeFrom(const EmergencyStopHardBrake& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(EmergencyStopHardBrake* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:apollo.decision.EmergencyStopHardBrake) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class EmergencyStopCruiseToStop : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.EmergencyStopCruiseToStop) */ { + public: + EmergencyStopCruiseToStop(); + virtual ~EmergencyStopCruiseToStop(); + + EmergencyStopCruiseToStop(const EmergencyStopCruiseToStop& from); + + inline EmergencyStopCruiseToStop& operator=(const EmergencyStopCruiseToStop& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + EmergencyStopCruiseToStop(EmergencyStopCruiseToStop&& from) noexcept + : EmergencyStopCruiseToStop() { + *this = ::std::move(from); + } + + inline EmergencyStopCruiseToStop& operator=(EmergencyStopCruiseToStop&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const EmergencyStopCruiseToStop& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const EmergencyStopCruiseToStop* internal_default_instance() { + return reinterpret_cast( + &_EmergencyStopCruiseToStop_default_instance_); + } + static constexpr int kIndexInFileMessages = + 16; + + void Swap(EmergencyStopCruiseToStop* other); + friend void swap(EmergencyStopCruiseToStop& a, EmergencyStopCruiseToStop& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline EmergencyStopCruiseToStop* New() const final { + return CreateMaybeMessage(NULL); + } + + EmergencyStopCruiseToStop* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const EmergencyStopCruiseToStop& from); + void MergeFrom(const EmergencyStopCruiseToStop& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(EmergencyStopCruiseToStop* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:apollo.decision.EmergencyStopCruiseToStop) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class MainEmergencyStop : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.MainEmergencyStop) */ { + public: + MainEmergencyStop(); + virtual ~MainEmergencyStop(); + + MainEmergencyStop(const MainEmergencyStop& from); + + inline MainEmergencyStop& operator=(const MainEmergencyStop& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + MainEmergencyStop(MainEmergencyStop&& from) noexcept + : MainEmergencyStop() { + *this = ::std::move(from); + } + + inline MainEmergencyStop& operator=(MainEmergencyStop&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const MainEmergencyStop& default_instance(); + + enum TaskCase { + kHardBrake = 3, + kCruiseToStop = 4, + TASK_NOT_SET = 0, + }; + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const MainEmergencyStop* internal_default_instance() { + return reinterpret_cast( + &_MainEmergencyStop_default_instance_); + } + static constexpr int kIndexInFileMessages = + 17; + + void Swap(MainEmergencyStop* other); + friend void swap(MainEmergencyStop& a, MainEmergencyStop& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline MainEmergencyStop* New() const final { + return CreateMaybeMessage(NULL); + } + + MainEmergencyStop* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const MainEmergencyStop& from); + void MergeFrom(const MainEmergencyStop& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(MainEmergencyStop* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef MainEmergencyStop_ReasonCode ReasonCode; + static const ReasonCode ESTOP_REASON_INTERNAL_ERR = + MainEmergencyStop_ReasonCode_ESTOP_REASON_INTERNAL_ERR; + static const ReasonCode ESTOP_REASON_COLLISION = + MainEmergencyStop_ReasonCode_ESTOP_REASON_COLLISION; + static const ReasonCode ESTOP_REASON_ST_FIND_PATH = + MainEmergencyStop_ReasonCode_ESTOP_REASON_ST_FIND_PATH; + static const ReasonCode ESTOP_REASON_ST_MAKE_DECISION = + MainEmergencyStop_ReasonCode_ESTOP_REASON_ST_MAKE_DECISION; + static const ReasonCode ESTOP_REASON_SENSOR_ERROR = + MainEmergencyStop_ReasonCode_ESTOP_REASON_SENSOR_ERROR; + static inline bool ReasonCode_IsValid(int value) { + return MainEmergencyStop_ReasonCode_IsValid(value); + } + static const ReasonCode ReasonCode_MIN = + MainEmergencyStop_ReasonCode_ReasonCode_MIN; + static const ReasonCode ReasonCode_MAX = + MainEmergencyStop_ReasonCode_ReasonCode_MAX; + static const int ReasonCode_ARRAYSIZE = + MainEmergencyStop_ReasonCode_ReasonCode_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + ReasonCode_descriptor() { + return MainEmergencyStop_ReasonCode_descriptor(); + } + static inline const ::std::string& ReasonCode_Name(ReasonCode value) { + return MainEmergencyStop_ReasonCode_Name(value); + } + static inline bool ReasonCode_Parse(const ::std::string& name, + ReasonCode* value) { + return MainEmergencyStop_ReasonCode_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // string reason = 1; + void clear_reason(); + static const int kReasonFieldNumber = 1; + const ::std::string& reason() const; + void set_reason(const ::std::string& value); + #if LANG_CXX11 + void set_reason(::std::string&& value); + #endif + void set_reason(const char* value); + void set_reason(const char* value, size_t size); + ::std::string* mutable_reason(); + ::std::string* release_reason(); + void set_allocated_reason(::std::string* reason); + + // .apollo.decision.MainEmergencyStop.ReasonCode reason_code = 2; + void clear_reason_code(); + static const int kReasonCodeFieldNumber = 2; + ::apollo::decision::MainEmergencyStop_ReasonCode reason_code() const; + void set_reason_code(::apollo::decision::MainEmergencyStop_ReasonCode value); + + // .apollo.decision.EmergencyStopHardBrake hard_brake = 3; + bool has_hard_brake() const; + void clear_hard_brake(); + static const int kHardBrakeFieldNumber = 3; + private: + const ::apollo::decision::EmergencyStopHardBrake& _internal_hard_brake() const; + public: + const ::apollo::decision::EmergencyStopHardBrake& hard_brake() const; + ::apollo::decision::EmergencyStopHardBrake* release_hard_brake(); + ::apollo::decision::EmergencyStopHardBrake* mutable_hard_brake(); + void set_allocated_hard_brake(::apollo::decision::EmergencyStopHardBrake* hard_brake); + + // .apollo.decision.EmergencyStopCruiseToStop cruise_to_stop = 4; + bool has_cruise_to_stop() const; + void clear_cruise_to_stop(); + static const int kCruiseToStopFieldNumber = 4; + private: + const ::apollo::decision::EmergencyStopCruiseToStop& _internal_cruise_to_stop() const; + public: + const ::apollo::decision::EmergencyStopCruiseToStop& cruise_to_stop() const; + ::apollo::decision::EmergencyStopCruiseToStop* release_cruise_to_stop(); + ::apollo::decision::EmergencyStopCruiseToStop* mutable_cruise_to_stop(); + void set_allocated_cruise_to_stop(::apollo::decision::EmergencyStopCruiseToStop* cruise_to_stop); + + void clear_task(); + TaskCase task_case() const; + // @@protoc_insertion_point(class_scope:apollo.decision.MainEmergencyStop) + private: + void set_has_hard_brake(); + void set_has_cruise_to_stop(); + + inline bool has_task() const; + inline void clear_has_task(); + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr reason_; + int reason_code_; + union TaskUnion { + TaskUnion() {} + ::apollo::decision::EmergencyStopHardBrake* hard_brake_; + ::apollo::decision::EmergencyStopCruiseToStop* cruise_to_stop_; + } task_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::google::protobuf::uint32 _oneof_case_[1]; + + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class MainCruise : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.MainCruise) */ { + public: + MainCruise(); + virtual ~MainCruise(); + + MainCruise(const MainCruise& from); + + inline MainCruise& operator=(const MainCruise& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + MainCruise(MainCruise&& from) noexcept + : MainCruise() { + *this = ::std::move(from); + } + + inline MainCruise& operator=(MainCruise&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const MainCruise& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const MainCruise* internal_default_instance() { + return reinterpret_cast( + &_MainCruise_default_instance_); + } + static constexpr int kIndexInFileMessages = + 18; + + void Swap(MainCruise* other); + friend void swap(MainCruise& a, MainCruise& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline MainCruise* New() const final { + return CreateMaybeMessage(NULL); + } + + MainCruise* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const MainCruise& from); + void MergeFrom(const MainCruise& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(MainCruise* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:apollo.decision.MainCruise) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class MainChangeLane : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.MainChangeLane) */ { + public: + MainChangeLane(); + virtual ~MainChangeLane(); + + MainChangeLane(const MainChangeLane& from); + + inline MainChangeLane& operator=(const MainChangeLane& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + MainChangeLane(MainChangeLane&& from) noexcept + : MainChangeLane() { + *this = ::std::move(from); + } + + inline MainChangeLane& operator=(MainChangeLane&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const MainChangeLane& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const MainChangeLane* internal_default_instance() { + return reinterpret_cast( + &_MainChangeLane_default_instance_); + } + static constexpr int kIndexInFileMessages = + 19; + + void Swap(MainChangeLane* other); + friend void swap(MainChangeLane& a, MainChangeLane& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline MainChangeLane* New() const final { + return CreateMaybeMessage(NULL); + } + + MainChangeLane* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const MainChangeLane& from); + void MergeFrom(const MainChangeLane& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(MainChangeLane* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef MainChangeLane_Type Type; + static const Type LEFT = + MainChangeLane_Type_LEFT; + static const Type RIGHT = + MainChangeLane_Type_RIGHT; + static inline bool Type_IsValid(int value) { + return MainChangeLane_Type_IsValid(value); + } + static const Type Type_MIN = + MainChangeLane_Type_Type_MIN; + static const Type Type_MAX = + MainChangeLane_Type_Type_MAX; + static const int Type_ARRAYSIZE = + MainChangeLane_Type_Type_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Type_descriptor() { + return MainChangeLane_Type_descriptor(); + } + static inline const ::std::string& Type_Name(Type value) { + return MainChangeLane_Type_Name(value); + } + static inline bool Type_Parse(const ::std::string& name, + Type* value) { + return MainChangeLane_Type_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // repeated .apollo.decision.TargetLane default_lane = 2; + int default_lane_size() const; + void clear_default_lane(); + static const int kDefaultLaneFieldNumber = 2; + ::apollo::decision::TargetLane* mutable_default_lane(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::decision::TargetLane >* + mutable_default_lane(); + const ::apollo::decision::TargetLane& default_lane(int index) const; + ::apollo::decision::TargetLane* add_default_lane(); + const ::google::protobuf::RepeatedPtrField< ::apollo::decision::TargetLane >& + default_lane() const; + + // .apollo.decision.MainStop default_lane_stop = 3; + bool has_default_lane_stop() const; + void clear_default_lane_stop(); + static const int kDefaultLaneStopFieldNumber = 3; + private: + const ::apollo::decision::MainStop& _internal_default_lane_stop() const; + public: + const ::apollo::decision::MainStop& default_lane_stop() const; + ::apollo::decision::MainStop* release_default_lane_stop(); + ::apollo::decision::MainStop* mutable_default_lane_stop(); + void set_allocated_default_lane_stop(::apollo::decision::MainStop* default_lane_stop); + + // .apollo.decision.MainStop target_lane_stop = 4; + bool has_target_lane_stop() const; + void clear_target_lane_stop(); + static const int kTargetLaneStopFieldNumber = 4; + private: + const ::apollo::decision::MainStop& _internal_target_lane_stop() const; + public: + const ::apollo::decision::MainStop& target_lane_stop() const; + ::apollo::decision::MainStop* release_target_lane_stop(); + ::apollo::decision::MainStop* mutable_target_lane_stop(); + void set_allocated_target_lane_stop(::apollo::decision::MainStop* target_lane_stop); + + // .apollo.decision.MainChangeLane.Type type = 1; + void clear_type(); + static const int kTypeFieldNumber = 1; + ::apollo::decision::MainChangeLane_Type type() const; + void set_type(::apollo::decision::MainChangeLane_Type value); + + // @@protoc_insertion_point(class_scope:apollo.decision.MainChangeLane) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::decision::TargetLane > default_lane_; + ::apollo::decision::MainStop* default_lane_stop_; + ::apollo::decision::MainStop* target_lane_stop_; + int type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class MainMissionComplete : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.MainMissionComplete) */ { + public: + MainMissionComplete(); + virtual ~MainMissionComplete(); + + MainMissionComplete(const MainMissionComplete& from); + + inline MainMissionComplete& operator=(const MainMissionComplete& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + MainMissionComplete(MainMissionComplete&& from) noexcept + : MainMissionComplete() { + *this = ::std::move(from); + } + + inline MainMissionComplete& operator=(MainMissionComplete&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const MainMissionComplete& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const MainMissionComplete* internal_default_instance() { + return reinterpret_cast( + &_MainMissionComplete_default_instance_); + } + static constexpr int kIndexInFileMessages = + 20; + + void Swap(MainMissionComplete* other); + friend void swap(MainMissionComplete& a, MainMissionComplete& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline MainMissionComplete* New() const final { + return CreateMaybeMessage(NULL); + } + + MainMissionComplete* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const MainMissionComplete& from); + void MergeFrom(const MainMissionComplete& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(MainMissionComplete* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:apollo.decision.MainMissionComplete) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class MainNotReady : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.MainNotReady) */ { + public: + MainNotReady(); + virtual ~MainNotReady(); + + MainNotReady(const MainNotReady& from); + + inline MainNotReady& operator=(const MainNotReady& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + MainNotReady(MainNotReady&& from) noexcept + : MainNotReady() { + *this = ::std::move(from); + } + + inline MainNotReady& operator=(MainNotReady&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const MainNotReady& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const MainNotReady* internal_default_instance() { + return reinterpret_cast( + &_MainNotReady_default_instance_); + } + static constexpr int kIndexInFileMessages = + 21; + + void Swap(MainNotReady* other); + friend void swap(MainNotReady& a, MainNotReady& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline MainNotReady* New() const final { + return CreateMaybeMessage(NULL); + } + + MainNotReady* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const MainNotReady& from); + void MergeFrom(const MainNotReady& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(MainNotReady* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // string reason = 1; + void clear_reason(); + static const int kReasonFieldNumber = 1; + const ::std::string& reason() const; + void set_reason(const ::std::string& value); + #if LANG_CXX11 + void set_reason(::std::string&& value); + #endif + void set_reason(const char* value); + void set_reason(const char* value, size_t size); + ::std::string* mutable_reason(); + ::std::string* release_reason(); + void set_allocated_reason(::std::string* reason); + + // @@protoc_insertion_point(class_scope:apollo.decision.MainNotReady) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr reason_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class MainParking : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.MainParking) */ { + public: + MainParking(); + virtual ~MainParking(); + + MainParking(const MainParking& from); + + inline MainParking& operator=(const MainParking& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + MainParking(MainParking&& from) noexcept + : MainParking() { + *this = ::std::move(from); + } + + inline MainParking& operator=(MainParking&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const MainParking& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const MainParking* internal_default_instance() { + return reinterpret_cast( + &_MainParking_default_instance_); + } + static constexpr int kIndexInFileMessages = + 22; + + void Swap(MainParking* other); + friend void swap(MainParking& a, MainParking& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline MainParking* New() const final { + return CreateMaybeMessage(NULL); + } + + MainParking* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const MainParking& from); + void MergeFrom(const MainParking& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(MainParking* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef MainParking_Type Type; + static const Type FORWARD_PARKING = + MainParking_Type_FORWARD_PARKING; + static const Type REVERSE_PARKING = + MainParking_Type_REVERSE_PARKING; + static inline bool Type_IsValid(int value) { + return MainParking_Type_IsValid(value); + } + static const Type Type_MIN = + MainParking_Type_Type_MIN; + static const Type Type_MAX = + MainParking_Type_Type_MAX; + static const int Type_ARRAYSIZE = + MainParking_Type_Type_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Type_descriptor() { + return MainParking_Type_descriptor(); + } + static inline const ::std::string& Type_Name(Type value) { + return MainParking_Type_Name(value); + } + static inline bool Type_Parse(const ::std::string& name, + Type* value) { + return MainParking_Type_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // repeated .apollo.common.PointENU parking_polygon = 4; + int parking_polygon_size() const; + void clear_parking_polygon(); + static const int kParkingPolygonFieldNumber = 4; + ::apollo::common::PointENU* mutable_parking_polygon(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::common::PointENU >* + mutable_parking_polygon(); + const ::apollo::common::PointENU& parking_polygon(int index) const; + ::apollo::common::PointENU* add_parking_polygon(); + const ::google::protobuf::RepeatedPtrField< ::apollo::common::PointENU >& + parking_polygon() const; + + // .apollo.common.PointENU stop_point = 3; + bool has_stop_point() const; + void clear_stop_point(); + static const int kStopPointFieldNumber = 3; + private: + const ::apollo::common::PointENU& _internal_stop_point() const; + public: + const ::apollo::common::PointENU& stop_point() const; + ::apollo::common::PointENU* release_stop_point(); + ::apollo::common::PointENU* mutable_stop_point(); + void set_allocated_stop_point(::apollo::common::PointENU* stop_point); + + // double heading = 2; + void clear_heading(); + static const int kHeadingFieldNumber = 2; + double heading() const; + void set_heading(double value); + + // .apollo.decision.MainParking.Type type = 1; + void clear_type(); + static const int kTypeFieldNumber = 1; + ::apollo::decision::MainParking_Type type() const; + void set_type(::apollo::decision::MainParking_Type value); + + // @@protoc_insertion_point(class_scope:apollo.decision.MainParking) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::common::PointENU > parking_polygon_; + ::apollo::common::PointENU* stop_point_; + double heading_; + int type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class MainDecision : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.MainDecision) */ { + public: + MainDecision(); + virtual ~MainDecision(); + + MainDecision(const MainDecision& from); + + inline MainDecision& operator=(const MainDecision& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + MainDecision(MainDecision&& from) noexcept + : MainDecision() { + *this = ::std::move(from); + } + + inline MainDecision& operator=(MainDecision&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const MainDecision& default_instance(); + + enum TaskCase { + kCruise = 1, + kStop = 2, + kEstop = 3, + kChangeLane = 4, + kMissionComplete = 6, + kNotReady = 7, + kParking = 8, + TASK_NOT_SET = 0, + }; + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const MainDecision* internal_default_instance() { + return reinterpret_cast( + &_MainDecision_default_instance_); + } + static constexpr int kIndexInFileMessages = + 23; + + void Swap(MainDecision* other); + friend void swap(MainDecision& a, MainDecision& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline MainDecision* New() const final { + return CreateMaybeMessage(NULL); + } + + MainDecision* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const MainDecision& from); + void MergeFrom(const MainDecision& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(MainDecision* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.decision.TargetLane target_lane = 5; + int target_lane_size() const; + void clear_target_lane(); + static const int kTargetLaneFieldNumber = 5; + ::apollo::decision::TargetLane* mutable_target_lane(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::decision::TargetLane >* + mutable_target_lane(); + const ::apollo::decision::TargetLane& target_lane(int index) const; + ::apollo::decision::TargetLane* add_target_lane(); + const ::google::protobuf::RepeatedPtrField< ::apollo::decision::TargetLane >& + target_lane() const; + + // .apollo.decision.MainCruise cruise = 1; + bool has_cruise() const; + void clear_cruise(); + static const int kCruiseFieldNumber = 1; + private: + const ::apollo::decision::MainCruise& _internal_cruise() const; + public: + const ::apollo::decision::MainCruise& cruise() const; + ::apollo::decision::MainCruise* release_cruise(); + ::apollo::decision::MainCruise* mutable_cruise(); + void set_allocated_cruise(::apollo::decision::MainCruise* cruise); + + // .apollo.decision.MainStop stop = 2; + bool has_stop() const; + void clear_stop(); + static const int kStopFieldNumber = 2; + private: + const ::apollo::decision::MainStop& _internal_stop() const; + public: + const ::apollo::decision::MainStop& stop() const; + ::apollo::decision::MainStop* release_stop(); + ::apollo::decision::MainStop* mutable_stop(); + void set_allocated_stop(::apollo::decision::MainStop* stop); + + // .apollo.decision.MainEmergencyStop estop = 3; + bool has_estop() const; + void clear_estop(); + static const int kEstopFieldNumber = 3; + private: + const ::apollo::decision::MainEmergencyStop& _internal_estop() const; + public: + const ::apollo::decision::MainEmergencyStop& estop() const; + ::apollo::decision::MainEmergencyStop* release_estop(); + ::apollo::decision::MainEmergencyStop* mutable_estop(); + void set_allocated_estop(::apollo::decision::MainEmergencyStop* estop); + + // .apollo.decision.MainChangeLane change_lane = 4; + bool has_change_lane() const; + void clear_change_lane(); + static const int kChangeLaneFieldNumber = 4; + private: + const ::apollo::decision::MainChangeLane& _internal_change_lane() const; + public: + const ::apollo::decision::MainChangeLane& change_lane() const; + ::apollo::decision::MainChangeLane* release_change_lane(); + ::apollo::decision::MainChangeLane* mutable_change_lane(); + void set_allocated_change_lane(::apollo::decision::MainChangeLane* change_lane); + + // .apollo.decision.MainMissionComplete mission_complete = 6; + bool has_mission_complete() const; + void clear_mission_complete(); + static const int kMissionCompleteFieldNumber = 6; + private: + const ::apollo::decision::MainMissionComplete& _internal_mission_complete() const; + public: + const ::apollo::decision::MainMissionComplete& mission_complete() const; + ::apollo::decision::MainMissionComplete* release_mission_complete(); + ::apollo::decision::MainMissionComplete* mutable_mission_complete(); + void set_allocated_mission_complete(::apollo::decision::MainMissionComplete* mission_complete); + + // .apollo.decision.MainNotReady not_ready = 7; + bool has_not_ready() const; + void clear_not_ready(); + static const int kNotReadyFieldNumber = 7; + private: + const ::apollo::decision::MainNotReady& _internal_not_ready() const; + public: + const ::apollo::decision::MainNotReady& not_ready() const; + ::apollo::decision::MainNotReady* release_not_ready(); + ::apollo::decision::MainNotReady* mutable_not_ready(); + void set_allocated_not_ready(::apollo::decision::MainNotReady* not_ready); + + // .apollo.decision.MainParking parking = 8; + bool has_parking() const; + void clear_parking(); + static const int kParkingFieldNumber = 8; + private: + const ::apollo::decision::MainParking& _internal_parking() const; + public: + const ::apollo::decision::MainParking& parking() const; + ::apollo::decision::MainParking* release_parking(); + ::apollo::decision::MainParking* mutable_parking(); + void set_allocated_parking(::apollo::decision::MainParking* parking); + + void clear_task(); + TaskCase task_case() const; + // @@protoc_insertion_point(class_scope:apollo.decision.MainDecision) + private: + void set_has_cruise(); + void set_has_stop(); + void set_has_estop(); + void set_has_change_lane(); + void set_has_mission_complete(); + void set_has_not_ready(); + void set_has_parking(); + + inline bool has_task() const; + inline void clear_has_task(); + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::decision::TargetLane > target_lane_; + union TaskUnion { + TaskUnion() {} + ::apollo::decision::MainCruise* cruise_; + ::apollo::decision::MainStop* stop_; + ::apollo::decision::MainEmergencyStop* estop_; + ::apollo::decision::MainChangeLane* change_lane_; + ::apollo::decision::MainMissionComplete* mission_complete_; + ::apollo::decision::MainNotReady* not_ready_; + ::apollo::decision::MainParking* parking_; + } task_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::google::protobuf::uint32 _oneof_case_[1]; + + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class MasterVehicleDebug : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.MasterVehicleDebug) */ { + public: + MasterVehicleDebug(); + virtual ~MasterVehicleDebug(); + + MasterVehicleDebug(const MasterVehicleDebug& from); + + inline MasterVehicleDebug& operator=(const MasterVehicleDebug& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + MasterVehicleDebug(MasterVehicleDebug&& from) noexcept + : MasterVehicleDebug() { + *this = ::std::move(from); + } + + inline MasterVehicleDebug& operator=(MasterVehicleDebug&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const MasterVehicleDebug& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const MasterVehicleDebug* internal_default_instance() { + return reinterpret_cast( + &_MasterVehicleDebug_default_instance_); + } + static constexpr int kIndexInFileMessages = + 24; + + void Swap(MasterVehicleDebug* other); + friend void swap(MasterVehicleDebug& a, MasterVehicleDebug& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline MasterVehicleDebug* New() const final { + return CreateMaybeMessage(NULL); + } + + MasterVehicleDebug* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const MasterVehicleDebug& from); + void MergeFrom(const MasterVehicleDebug& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(MasterVehicleDebug* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // string current_lane_id = 2; + void clear_current_lane_id(); + static const int kCurrentLaneIdFieldNumber = 2; + const ::std::string& current_lane_id() const; + void set_current_lane_id(const ::std::string& value); + #if LANG_CXX11 + void set_current_lane_id(::std::string&& value); + #endif + void set_current_lane_id(const char* value); + void set_current_lane_id(const char* value, size_t size); + ::std::string* mutable_current_lane_id(); + ::std::string* release_current_lane_id(); + void set_allocated_current_lane_id(::std::string* current_lane_id); + + // .apollo.common.PointENU position = 1; + bool has_position() const; + void clear_position(); + static const int kPositionFieldNumber = 1; + private: + const ::apollo::common::PointENU& _internal_position() const; + public: + const ::apollo::common::PointENU& position() const; + ::apollo::common::PointENU* release_position(); + ::apollo::common::PointENU* mutable_position(); + void set_allocated_position(::apollo::common::PointENU* position); + + // .apollo.decision.Range route_s_range = 10; + bool has_route_s_range() const; + void clear_route_s_range(); + static const int kRouteSRangeFieldNumber = 10; + private: + const ::apollo::decision::Range& _internal_route_s_range() const; + public: + const ::apollo::decision::Range& route_s_range() const; + ::apollo::decision::Range* release_route_s_range(); + ::apollo::decision::Range* mutable_route_s_range(); + void set_allocated_route_s_range(::apollo::decision::Range* route_s_range); + + // .apollo.decision.Range route_l_range = 11; + bool has_route_l_range() const; + void clear_route_l_range(); + static const int kRouteLRangeFieldNumber = 11; + private: + const ::apollo::decision::Range& _internal_route_l_range() const; + public: + const ::apollo::decision::Range& route_l_range() const; + ::apollo::decision::Range* release_route_l_range(); + ::apollo::decision::Range* mutable_route_l_range(); + void set_allocated_route_l_range(::apollo::decision::Range* route_l_range); + + // double lane_s = 3; + void clear_lane_s(); + static const int kLaneSFieldNumber = 3; + double lane_s() const; + void set_lane_s(double value); + + // double lane_l = 4; + void clear_lane_l(); + static const int kLaneLFieldNumber = 4; + double lane_l() const; + void set_lane_l(double value); + + // double route_s = 5; + void clear_route_s(); + static const int kRouteSFieldNumber = 5; + double route_s() const; + void set_route_s(double value); + + // double route_l = 6; + void clear_route_l(); + static const int kRouteLFieldNumber = 6; + double route_l() const; + void set_route_l(double value); + + // double heading = 7; + void clear_heading(); + static const int kHeadingFieldNumber = 7; + double heading() const; + void set_heading(double value); + + // double heading_speed = 8; + void clear_heading_speed(); + static const int kHeadingSpeedFieldNumber = 8; + double heading_speed() const; + void set_heading_speed(double value); + + // double heading_acceleration = 9; + void clear_heading_acceleration(); + static const int kHeadingAccelerationFieldNumber = 9; + double heading_acceleration() const; + void set_heading_acceleration(double value); + + // @@protoc_insertion_point(class_scope:apollo.decision.MasterVehicleDebug) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr current_lane_id_; + ::apollo::common::PointENU* position_; + ::apollo::decision::Range* route_s_range_; + ::apollo::decision::Range* route_l_range_; + double lane_s_; + double lane_l_; + double route_s_; + double route_l_; + double heading_; + double heading_speed_; + double heading_acceleration_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ObjectDebug : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.ObjectDebug) */ { + public: + ObjectDebug(); + virtual ~ObjectDebug(); + + ObjectDebug(const ObjectDebug& from); + + inline ObjectDebug& operator=(const ObjectDebug& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ObjectDebug(ObjectDebug&& from) noexcept + : ObjectDebug() { + *this = ::std::move(from); + } + + inline ObjectDebug& operator=(ObjectDebug&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ObjectDebug& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ObjectDebug* internal_default_instance() { + return reinterpret_cast( + &_ObjectDebug_default_instance_); + } + static constexpr int kIndexInFileMessages = + 25; + + void Swap(ObjectDebug* other); + friend void swap(ObjectDebug& a, ObjectDebug& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ObjectDebug* New() const final { + return CreateMaybeMessage(NULL); + } + + ObjectDebug* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ObjectDebug& from); + void MergeFrom(const ObjectDebug& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ObjectDebug* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.common.Point3D st_region = 10; + int st_region_size() const; + void clear_st_region(); + static const int kStRegionFieldNumber = 10; + ::apollo::common::Point3D* mutable_st_region(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::common::Point3D >* + mutable_st_region(); + const ::apollo::common::Point3D& st_region(int index) const; + ::apollo::common::Point3D* add_st_region(); + const ::google::protobuf::RepeatedPtrField< ::apollo::common::Point3D >& + st_region() const; + + // string id = 1; + void clear_id(); + static const int kIdFieldNumber = 1; + const ::std::string& id() const; + void set_id(const ::std::string& value); + #if LANG_CXX11 + void set_id(::std::string&& value); + #endif + void set_id(const char* value); + void set_id(const char* value, size_t size); + ::std::string* mutable_id(); + ::std::string* release_id(); + void set_allocated_id(::std::string* id); + + // string path_id = 2; + void clear_path_id(); + static const int kPathIdFieldNumber = 2; + const ::std::string& path_id() const; + void set_path_id(const ::std::string& value); + #if LANG_CXX11 + void set_path_id(::std::string&& value); + #endif + void set_path_id(const char* value); + void set_path_id(const char* value, size_t size); + ::std::string* mutable_path_id(); + ::std::string* release_path_id(); + void set_allocated_path_id(::std::string* path_id); + + // string lane_id = 6; + void clear_lane_id(); + static const int kLaneIdFieldNumber = 6; + const ::std::string& lane_id() const; + void set_lane_id(const ::std::string& value); + #if LANG_CXX11 + void set_lane_id(::std::string&& value); + #endif + void set_lane_id(const char* value); + void set_lane_id(const char* value, size_t size); + ::std::string* mutable_lane_id(); + ::std::string* release_lane_id(); + void set_allocated_lane_id(::std::string* lane_id); + + // .apollo.decision.Range route_s = 3; + bool has_route_s() const; + void clear_route_s(); + static const int kRouteSFieldNumber = 3; + private: + const ::apollo::decision::Range& _internal_route_s() const; + public: + const ::apollo::decision::Range& route_s() const; + ::apollo::decision::Range* release_route_s(); + ::apollo::decision::Range* mutable_route_s(); + void set_allocated_route_s(::apollo::decision::Range* route_s); + + // .apollo.decision.Range route_l = 4; + bool has_route_l() const; + void clear_route_l(); + static const int kRouteLFieldNumber = 4; + private: + const ::apollo::decision::Range& _internal_route_l() const; + public: + const ::apollo::decision::Range& route_l() const; + ::apollo::decision::Range* release_route_l(); + ::apollo::decision::Range* mutable_route_l(); + void set_allocated_route_l(::apollo::decision::Range* route_l); + + // double lane_s = 7; + void clear_lane_s(); + static const int kLaneSFieldNumber = 7; + double lane_s() const; + void set_lane_s(double value); + + // double path_speed = 9; + void clear_path_speed(); + static const int kPathSpeedFieldNumber = 9; + double path_speed() const; + void set_path_speed(double value); + + // bool on_route = 5; + void clear_on_route(); + static const int kOnRouteFieldNumber = 5; + bool on_route() const; + void set_on_route(bool value); + + // bool on_lane = 8; + void clear_on_lane(); + static const int kOnLaneFieldNumber = 8; + bool on_lane() const; + void set_on_lane(bool value); + + // @@protoc_insertion_point(class_scope:apollo.decision.ObjectDebug) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::common::Point3D > st_region_; + ::google::protobuf::internal::ArenaStringPtr id_; + ::google::protobuf::internal::ArenaStringPtr path_id_; + ::google::protobuf::internal::ArenaStringPtr lane_id_; + ::apollo::decision::Range* route_s_; + ::apollo::decision::Range* route_l_; + double lane_s_; + double path_speed_; + bool on_route_; + bool on_lane_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class LatencyStats : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.LatencyStats) */ { + public: + LatencyStats(); + virtual ~LatencyStats(); + + LatencyStats(const LatencyStats& from); + + inline LatencyStats& operator=(const LatencyStats& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + LatencyStats(LatencyStats&& from) noexcept + : LatencyStats() { + *this = ::std::move(from); + } + + inline LatencyStats& operator=(LatencyStats&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const LatencyStats& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const LatencyStats* internal_default_instance() { + return reinterpret_cast( + &_LatencyStats_default_instance_); + } + static constexpr int kIndexInFileMessages = + 26; + + void Swap(LatencyStats* other); + friend void swap(LatencyStats& a, LatencyStats& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline LatencyStats* New() const final { + return CreateMaybeMessage(NULL); + } + + LatencyStats* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const LatencyStats& from); + void MergeFrom(const LatencyStats& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(LatencyStats* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double total_time_ms = 1; + void clear_total_time_ms(); + static const int kTotalTimeMsFieldNumber = 1; + double total_time_ms() const; + void set_total_time_ms(double value); + + // double sensor_read_time_ms = 2; + void clear_sensor_read_time_ms(); + static const int kSensorReadTimeMsFieldNumber = 2; + double sensor_read_time_ms() const; + void set_sensor_read_time_ms(double value); + + // double adc_prepare_time_ms = 3; + void clear_adc_prepare_time_ms(); + static const int kAdcPrepareTimeMsFieldNumber = 3; + double adc_prepare_time_ms() const; + void set_adc_prepare_time_ms(double value); + + // double obj_prepare_time_ms = 4; + void clear_obj_prepare_time_ms(); + static const int kObjPrepareTimeMsFieldNumber = 4; + double obj_prepare_time_ms() const; + void set_obj_prepare_time_ms(double value); + + // double world_rule_time_ms = 5; + void clear_world_rule_time_ms(); + static const int kWorldRuleTimeMsFieldNumber = 5; + double world_rule_time_ms() const; + void set_world_rule_time_ms(double value); + + // double st_graph_time_ms = 6; + void clear_st_graph_time_ms(); + static const int kStGraphTimeMsFieldNumber = 6; + double st_graph_time_ms() const; + void set_st_graph_time_ms(double value); + + // double gateway_receive_delay_ms = 8; + void clear_gateway_receive_delay_ms(); + static const int kGatewayReceiveDelayMsFieldNumber = 8; + double gateway_receive_delay_ms() const; + void set_gateway_receive_delay_ms(double value); + + // double perception_receive_delay_ms = 9; + void clear_perception_receive_delay_ms(); + static const int kPerceptionReceiveDelayMsFieldNumber = 9; + double perception_receive_delay_ms() const; + void set_perception_receive_delay_ms(double value); + + // double prediction_receive_delay_ms = 10; + void clear_prediction_receive_delay_ms(); + static const int kPredictionReceiveDelayMsFieldNumber = 10; + double prediction_receive_delay_ms() const; + void set_prediction_receive_delay_ms(double value); + + // double signal_receive_delay_ms = 11; + void clear_signal_receive_delay_ms(); + static const int kSignalReceiveDelayMsFieldNumber = 11; + double signal_receive_delay_ms() const; + void set_signal_receive_delay_ms(double value); + + // double perception_interval_ms = 12; + void clear_perception_interval_ms(); + static const int kPerceptionIntervalMsFieldNumber = 12; + double perception_interval_ms() const; + void set_perception_interval_ms(double value); + + // double prediction_interval_ms = 13; + void clear_prediction_interval_ms(); + static const int kPredictionIntervalMsFieldNumber = 13; + double prediction_interval_ms() const; + void set_prediction_interval_ms(double value); + + // @@protoc_insertion_point(class_scope:apollo.decision.LatencyStats) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double total_time_ms_; + double sensor_read_time_ms_; + double adc_prepare_time_ms_; + double obj_prepare_time_ms_; + double world_rule_time_ms_; + double st_graph_time_ms_; + double gateway_receive_delay_ms_; + double perception_receive_delay_ms_; + double prediction_receive_delay_ms_; + double signal_receive_delay_ms_; + double perception_interval_ms_; + double prediction_interval_ms_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Stats : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.Stats) */ { + public: + Stats(); + virtual ~Stats(); + + Stats(const Stats& from); + + inline Stats& operator=(const Stats& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Stats(Stats&& from) noexcept + : Stats() { + *this = ::std::move(from); + } + + inline Stats& operator=(Stats&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Stats& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Stats* internal_default_instance() { + return reinterpret_cast( + &_Stats_default_instance_); + } + static constexpr int kIndexInFileMessages = + 27; + + void Swap(Stats* other); + friend void swap(Stats& a, Stats& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Stats* New() const final { + return CreateMaybeMessage(NULL); + } + + Stats* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Stats& from); + void MergeFrom(const Stats& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Stats* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.decision.LatencyStats latency_stats = 1; + bool has_latency_stats() const; + void clear_latency_stats(); + static const int kLatencyStatsFieldNumber = 1; + private: + const ::apollo::decision::LatencyStats& _internal_latency_stats() const; + public: + const ::apollo::decision::LatencyStats& latency_stats() const; + ::apollo::decision::LatencyStats* release_latency_stats(); + ::apollo::decision::LatencyStats* mutable_latency_stats(); + void set_allocated_latency_stats(::apollo::decision::LatencyStats* latency_stats); + + // @@protoc_insertion_point(class_scope:apollo.decision.Stats) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::decision::LatencyStats* latency_stats_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ModuleDebug : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.ModuleDebug) */ { + public: + ModuleDebug(); + virtual ~ModuleDebug(); + + ModuleDebug(const ModuleDebug& from); + + inline ModuleDebug& operator=(const ModuleDebug& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ModuleDebug(ModuleDebug&& from) noexcept + : ModuleDebug() { + *this = ::std::move(from); + } + + inline ModuleDebug& operator=(ModuleDebug&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ModuleDebug& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ModuleDebug* internal_default_instance() { + return reinterpret_cast( + &_ModuleDebug_default_instance_); + } + static constexpr int kIndexInFileMessages = + 28; + + void Swap(ModuleDebug* other); + friend void swap(ModuleDebug& a, ModuleDebug& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ModuleDebug* New() const final { + return CreateMaybeMessage(NULL); + } + + ModuleDebug* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ModuleDebug& from); + void MergeFrom(const ModuleDebug& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ModuleDebug* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // uint32 gateway_sequence_num = 1; + void clear_gateway_sequence_num(); + static const int kGatewaySequenceNumFieldNumber = 1; + ::google::protobuf::uint32 gateway_sequence_num() const; + void set_gateway_sequence_num(::google::protobuf::uint32 value); + + // uint32 perception_sequence_num = 2; + void clear_perception_sequence_num(); + static const int kPerceptionSequenceNumFieldNumber = 2; + ::google::protobuf::uint32 perception_sequence_num() const; + void set_perception_sequence_num(::google::protobuf::uint32 value); + + // uint32 prediction_sequence_num = 3; + void clear_prediction_sequence_num(); + static const int kPredictionSequenceNumFieldNumber = 3; + ::google::protobuf::uint32 prediction_sequence_num() const; + void set_prediction_sequence_num(::google::protobuf::uint32 value); + + // uint32 signal_sequence_num = 4; + void clear_signal_sequence_num(); + static const int kSignalSequenceNumFieldNumber = 4; + ::google::protobuf::uint32 signal_sequence_num() const; + void set_signal_sequence_num(::google::protobuf::uint32 value); + + // @@protoc_insertion_point(class_scope:apollo.decision.ModuleDebug) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::uint32 gateway_sequence_num_; + ::google::protobuf::uint32 perception_sequence_num_; + ::google::protobuf::uint32 prediction_sequence_num_; + ::google::protobuf::uint32 signal_sequence_num_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Debug : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.Debug) */ { + public: + Debug(); + virtual ~Debug(); + + Debug(const Debug& from); + + inline Debug& operator=(const Debug& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Debug(Debug&& from) noexcept + : Debug() { + *this = ::std::move(from); + } + + inline Debug& operator=(Debug&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Debug& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Debug* internal_default_instance() { + return reinterpret_cast( + &_Debug_default_instance_); + } + static constexpr int kIndexInFileMessages = + 29; + + void Swap(Debug* other); + friend void swap(Debug& a, Debug& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Debug* New() const final { + return CreateMaybeMessage(NULL); + } + + Debug* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Debug& from); + void MergeFrom(const Debug& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Debug* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.decision.ObjectDebug object = 3; + int object_size() const; + void clear_object(); + static const int kObjectFieldNumber = 3; + ::apollo::decision::ObjectDebug* mutable_object(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDebug >* + mutable_object(); + const ::apollo::decision::ObjectDebug& object(int index) const; + ::apollo::decision::ObjectDebug* add_object(); + const ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDebug >& + object() const; + + // bytes map_version = 5; + void clear_map_version(); + static const int kMapVersionFieldNumber = 5; + const ::std::string& map_version() const; + void set_map_version(const ::std::string& value); + #if LANG_CXX11 + void set_map_version(::std::string&& value); + #endif + void set_map_version(const char* value); + void set_map_version(const void* value, size_t size); + ::std::string* mutable_map_version(); + ::std::string* release_map_version(); + void set_allocated_map_version(::std::string* map_version); + + // bytes decision_version = 7; + void clear_decision_version(); + static const int kDecisionVersionFieldNumber = 7; + const ::std::string& decision_version() const; + void set_decision_version(const ::std::string& value); + #if LANG_CXX11 + void set_decision_version(::std::string&& value); + #endif + void set_decision_version(const char* value); + void set_decision_version(const void* value, size_t size); + ::std::string* mutable_decision_version(); + ::std::string* release_decision_version(); + void set_allocated_decision_version(::std::string* decision_version); + + // .apollo.decision.MasterVehicleDebug master_vehicle = 1; + bool has_master_vehicle() const; + void clear_master_vehicle(); + static const int kMasterVehicleFieldNumber = 1; + private: + const ::apollo::decision::MasterVehicleDebug& _internal_master_vehicle() const; + public: + const ::apollo::decision::MasterVehicleDebug& master_vehicle() const; + ::apollo::decision::MasterVehicleDebug* release_master_vehicle(); + ::apollo::decision::MasterVehicleDebug* mutable_master_vehicle(); + void set_allocated_master_vehicle(::apollo::decision::MasterVehicleDebug* master_vehicle); + + // .apollo.decision.MainDecision original_decision = 2; + bool has_original_decision() const; + void clear_original_decision(); + static const int kOriginalDecisionFieldNumber = 2; + private: + const ::apollo::decision::MainDecision& _internal_original_decision() const; + public: + const ::apollo::decision::MainDecision& original_decision() const; + ::apollo::decision::MainDecision* release_original_decision(); + ::apollo::decision::MainDecision* mutable_original_decision(); + void set_allocated_original_decision(::apollo::decision::MainDecision* original_decision); + + // .apollo.decision.ModuleDebug module_debug = 6; + bool has_module_debug() const; + void clear_module_debug(); + static const int kModuleDebugFieldNumber = 6; + private: + const ::apollo::decision::ModuleDebug& _internal_module_debug() const; + public: + const ::apollo::decision::ModuleDebug& module_debug() const; + ::apollo::decision::ModuleDebug* release_module_debug(); + ::apollo::decision::ModuleDebug* mutable_module_debug(); + void set_allocated_module_debug(::apollo::decision::ModuleDebug* module_debug); + + // @@protoc_insertion_point(class_scope:apollo.decision.Debug) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDebug > object_; + ::google::protobuf::internal::ArenaStringPtr map_version_; + ::google::protobuf::internal::ArenaStringPtr decision_version_; + ::apollo::decision::MasterVehicleDebug* master_vehicle_; + ::apollo::decision::MainDecision* original_decision_; + ::apollo::decision::ModuleDebug* module_debug_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class LightSignal : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.LightSignal) */ { + public: + LightSignal(); + virtual ~LightSignal(); + + LightSignal(const LightSignal& from); + + inline LightSignal& operator=(const LightSignal& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + LightSignal(LightSignal&& from) noexcept + : LightSignal() { + *this = ::std::move(from); + } + + inline LightSignal& operator=(LightSignal&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const LightSignal& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const LightSignal* internal_default_instance() { + return reinterpret_cast( + &_LightSignal_default_instance_); + } + static constexpr int kIndexInFileMessages = + 30; + + void Swap(LightSignal* other); + friend void swap(LightSignal& a, LightSignal& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline LightSignal* New() const final { + return CreateMaybeMessage(NULL); + } + + LightSignal* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const LightSignal& from); + void MergeFrom(const LightSignal& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(LightSignal* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef LightSignal_TurnSignal TurnSignal; + static const TurnSignal NO_TURN = + LightSignal_TurnSignal_NO_TURN; + static const TurnSignal LEFT_TURN = + LightSignal_TurnSignal_LEFT_TURN; + static const TurnSignal RIGHT_TURN = + LightSignal_TurnSignal_RIGHT_TURN; + static inline bool TurnSignal_IsValid(int value) { + return LightSignal_TurnSignal_IsValid(value); + } + static const TurnSignal TurnSignal_MIN = + LightSignal_TurnSignal_TurnSignal_MIN; + static const TurnSignal TurnSignal_MAX = + LightSignal_TurnSignal_TurnSignal_MAX; + static const int TurnSignal_ARRAYSIZE = + LightSignal_TurnSignal_TurnSignal_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + TurnSignal_descriptor() { + return LightSignal_TurnSignal_descriptor(); + } + static inline const ::std::string& TurnSignal_Name(TurnSignal value) { + return LightSignal_TurnSignal_Name(value); + } + static inline bool TurnSignal_Parse(const ::std::string& name, + TurnSignal* value) { + return LightSignal_TurnSignal_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // bool emergency = 1; + void clear_emergency(); + static const int kEmergencyFieldNumber = 1; + bool emergency() const; + void set_emergency(bool value); + + // .apollo.decision.LightSignal.TurnSignal turn_signal = 2; + void clear_turn_signal(); + static const int kTurnSignalFieldNumber = 2; + ::apollo::decision::LightSignal_TurnSignal turn_signal() const; + void set_turn_signal(::apollo::decision::LightSignal_TurnSignal value); + + // @@protoc_insertion_point(class_scope:apollo.decision.LightSignal) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + bool emergency_; + int turn_signal_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class DecisionResult : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.decision.DecisionResult) */ { + public: + DecisionResult(); + virtual ~DecisionResult(); + + DecisionResult(const DecisionResult& from); + + inline DecisionResult& operator=(const DecisionResult& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + DecisionResult(DecisionResult&& from) noexcept + : DecisionResult() { + *this = ::std::move(from); + } + + inline DecisionResult& operator=(DecisionResult&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const DecisionResult& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const DecisionResult* internal_default_instance() { + return reinterpret_cast( + &_DecisionResult_default_instance_); + } + static constexpr int kIndexInFileMessages = + 31; + + void Swap(DecisionResult* other); + friend void swap(DecisionResult& a, DecisionResult& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline DecisionResult* New() const final { + return CreateMaybeMessage(NULL); + } + + DecisionResult* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const DecisionResult& from); + void MergeFrom(const DecisionResult& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(DecisionResult* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.decision.ObjectDecisions object_decision = 2; + bool has_object_decision() const; + void clear_object_decision(); + static const int kObjectDecisionFieldNumber = 2; + private: + const ::apollo::decision::ObjectDecisions& _internal_object_decision() const; + public: + const ::apollo::decision::ObjectDecisions& object_decision() const; + ::apollo::decision::ObjectDecisions* release_object_decision(); + ::apollo::decision::ObjectDecisions* mutable_object_decision(); + void set_allocated_object_decision(::apollo::decision::ObjectDecisions* object_decision); + + // .apollo.decision.MainDecision main_decision = 3; + bool has_main_decision() const; + void clear_main_decision(); + static const int kMainDecisionFieldNumber = 3; + private: + const ::apollo::decision::MainDecision& _internal_main_decision() const; + public: + const ::apollo::decision::MainDecision& main_decision() const; + ::apollo::decision::MainDecision* release_main_decision(); + ::apollo::decision::MainDecision* mutable_main_decision(); + void set_allocated_main_decision(::apollo::decision::MainDecision* main_decision); + + // .apollo.decision.Debug debug = 4; + bool has_debug() const; + void clear_debug(); + static const int kDebugFieldNumber = 4; + private: + const ::apollo::decision::Debug& _internal_debug() const; + public: + const ::apollo::decision::Debug& debug() const; + ::apollo::decision::Debug* release_debug(); + ::apollo::decision::Debug* mutable_debug(); + void set_allocated_debug(::apollo::decision::Debug* debug); + + // .apollo.decision.LightSignal light_signal = 5; + bool has_light_signal() const; + void clear_light_signal(); + static const int kLightSignalFieldNumber = 5; + private: + const ::apollo::decision::LightSignal& _internal_light_signal() const; + public: + const ::apollo::decision::LightSignal& light_signal() const; + ::apollo::decision::LightSignal* release_light_signal(); + ::apollo::decision::LightSignal* mutable_light_signal(); + void set_allocated_light_signal(::apollo::decision::LightSignal* light_signal); + + // .apollo.decision.Stats stats = 6; + bool has_stats() const; + void clear_stats(); + static const int kStatsFieldNumber = 6; + private: + const ::apollo::decision::Stats& _internal_stats() const; + public: + const ::apollo::decision::Stats& stats() const; + ::apollo::decision::Stats* release_stats(); + ::apollo::decision::Stats* mutable_stats(); + void set_allocated_stats(::apollo::decision::Stats* stats); + + // .apollo.canbus.Signal signal = 7; + bool has_signal() const; + void clear_signal(); + static const int kSignalFieldNumber = 7; + private: + const ::apollo::canbus::Signal& _internal_signal() const; + public: + const ::apollo::canbus::Signal& signal() const; + ::apollo::canbus::Signal* release_signal(); + ::apollo::canbus::Signal* mutable_signal(); + void set_allocated_signal(::apollo::canbus::Signal* signal); + + // @@protoc_insertion_point(class_scope:apollo.decision.DecisionResult) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::Header* header_; + ::apollo::decision::ObjectDecisions* object_decision_; + ::apollo::decision::MainDecision* main_decision_; + ::apollo::decision::Debug* debug_; + ::apollo::decision::LightSignal* light_signal_; + ::apollo::decision::Stats* stats_; + ::apollo::canbus::Signal* signal_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// Range + +// double start = 1; +inline void Range::clear_start() { + start_ = 0; +} +inline double Range::start() const { + // @@protoc_insertion_point(field_get:apollo.decision.Range.start) + return start_; +} +inline void Range::set_start(double value) { + + start_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.Range.start) +} + +// double end = 2; +inline void Range::clear_end() { + end_ = 0; +} +inline double Range::end() const { + // @@protoc_insertion_point(field_get:apollo.decision.Range.end) + return end_; +} +inline void Range::set_end(double value) { + + end_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.Range.end) +} + +// ------------------------------------------------------------------- + +// TargetLane + +// string id = 1; +inline void TargetLane::clear_id() { + id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& TargetLane::id() const { + // @@protoc_insertion_point(field_get:apollo.decision.TargetLane.id) + return id_.GetNoArena(); +} +inline void TargetLane::set_id(const ::std::string& value) { + + id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.decision.TargetLane.id) +} +#if LANG_CXX11 +inline void TargetLane::set_id(::std::string&& value) { + + id_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.decision.TargetLane.id) +} +#endif +inline void TargetLane::set_id(const char* value) { + GOOGLE_DCHECK(value != NULL); + + id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.decision.TargetLane.id) +} +inline void TargetLane::set_id(const char* value, size_t size) { + + id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.decision.TargetLane.id) +} +inline ::std::string* TargetLane::mutable_id() { + + // @@protoc_insertion_point(field_mutable:apollo.decision.TargetLane.id) + return id_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* TargetLane::release_id() { + // @@protoc_insertion_point(field_release:apollo.decision.TargetLane.id) + + return id_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void TargetLane::set_allocated_id(::std::string* id) { + if (id != NULL) { + + } else { + + } + id_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), id); + // @@protoc_insertion_point(field_set_allocated:apollo.decision.TargetLane.id) +} + +// double start_s = 2; +inline void TargetLane::clear_start_s() { + start_s_ = 0; +} +inline double TargetLane::start_s() const { + // @@protoc_insertion_point(field_get:apollo.decision.TargetLane.start_s) + return start_s_; +} +inline void TargetLane::set_start_s(double value) { + + start_s_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.TargetLane.start_s) +} + +// double end_s = 3; +inline void TargetLane::clear_end_s() { + end_s_ = 0; +} +inline double TargetLane::end_s() const { + // @@protoc_insertion_point(field_get:apollo.decision.TargetLane.end_s) + return end_s_; +} +inline void TargetLane::set_end_s(double value) { + + end_s_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.TargetLane.end_s) +} + +// double speed_limit = 4; +inline void TargetLane::clear_speed_limit() { + speed_limit_ = 0; +} +inline double TargetLane::speed_limit() const { + // @@protoc_insertion_point(field_get:apollo.decision.TargetLane.speed_limit) + return speed_limit_; +} +inline void TargetLane::set_speed_limit(double value) { + + speed_limit_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.TargetLane.speed_limit) +} + +// ------------------------------------------------------------------- + +// ObjectIgnore + +// ------------------------------------------------------------------- + +// ObjectStop + +// double distance_s = 1; +inline void ObjectStop::clear_distance_s() { + distance_s_ = 0; +} +inline double ObjectStop::distance_s() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectStop.distance_s) + return distance_s_; +} +inline void ObjectStop::set_distance_s(double value) { + + distance_s_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectStop.distance_s) +} + +// .apollo.decision.Range preferred_distance_s = 2; +inline bool ObjectStop::has_preferred_distance_s() const { + return this != internal_default_instance() && preferred_distance_s_ != NULL; +} +inline void ObjectStop::clear_preferred_distance_s() { + if (GetArenaNoVirtual() == NULL && preferred_distance_s_ != NULL) { + delete preferred_distance_s_; + } + preferred_distance_s_ = NULL; +} +inline const ::apollo::decision::Range& ObjectStop::_internal_preferred_distance_s() const { + return *preferred_distance_s_; +} +inline const ::apollo::decision::Range& ObjectStop::preferred_distance_s() const { + const ::apollo::decision::Range* p = preferred_distance_s_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectStop.preferred_distance_s) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_Range_default_instance_); +} +inline ::apollo::decision::Range* ObjectStop::release_preferred_distance_s() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectStop.preferred_distance_s) + + ::apollo::decision::Range* temp = preferred_distance_s_; + preferred_distance_s_ = NULL; + return temp; +} +inline ::apollo::decision::Range* ObjectStop::mutable_preferred_distance_s() { + + if (preferred_distance_s_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::Range>(GetArenaNoVirtual()); + preferred_distance_s_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectStop.preferred_distance_s) + return preferred_distance_s_; +} +inline void ObjectStop::set_allocated_preferred_distance_s(::apollo::decision::Range* preferred_distance_s) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete preferred_distance_s_; + } + if (preferred_distance_s) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + preferred_distance_s = ::google::protobuf::internal::GetOwnedMessage( + message_arena, preferred_distance_s, submessage_arena); + } + + } else { + + } + preferred_distance_s_ = preferred_distance_s; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectStop.preferred_distance_s) +} + +// .apollo.decision.StopReasonCode reason_code = 3; +inline void ObjectStop::clear_reason_code() { + reason_code_ = 0; +} +inline ::apollo::decision::StopReasonCode ObjectStop::reason_code() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectStop.reason_code) + return static_cast< ::apollo::decision::StopReasonCode >(reason_code_); +} +inline void ObjectStop::set_reason_code(::apollo::decision::StopReasonCode value) { + + reason_code_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectStop.reason_code) +} + +// .apollo.common.PointENU stop_point = 4; +inline bool ObjectStop::has_stop_point() const { + return this != internal_default_instance() && stop_point_ != NULL; +} +inline const ::apollo::common::PointENU& ObjectStop::_internal_stop_point() const { + return *stop_point_; +} +inline const ::apollo::common::PointENU& ObjectStop::stop_point() const { + const ::apollo::common::PointENU* p = stop_point_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectStop.stop_point) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_PointENU_default_instance_); +} +inline ::apollo::common::PointENU* ObjectStop::release_stop_point() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectStop.stop_point) + + ::apollo::common::PointENU* temp = stop_point_; + stop_point_ = NULL; + return temp; +} +inline ::apollo::common::PointENU* ObjectStop::mutable_stop_point() { + + if (stop_point_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::PointENU>(GetArenaNoVirtual()); + stop_point_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectStop.stop_point) + return stop_point_; +} +inline void ObjectStop::set_allocated_stop_point(::apollo::common::PointENU* stop_point) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(stop_point_); + } + if (stop_point) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + stop_point = ::google::protobuf::internal::GetOwnedMessage( + message_arena, stop_point, submessage_arena); + } + + } else { + + } + stop_point_ = stop_point; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectStop.stop_point) +} + +// ------------------------------------------------------------------- + +// ObjectNudge + +// double distance_l = 1; +inline void ObjectNudge::clear_distance_l() { + distance_l_ = 0; +} +inline double ObjectNudge::distance_l() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectNudge.distance_l) + return distance_l_; +} +inline void ObjectNudge::set_distance_l(double value) { + + distance_l_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectNudge.distance_l) +} + +// .apollo.decision.ObjectNudge.Type type = 2; +inline void ObjectNudge::clear_type() { + type_ = 0; +} +inline ::apollo::decision::ObjectNudge_Type ObjectNudge::type() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectNudge.type) + return static_cast< ::apollo::decision::ObjectNudge_Type >(type_); +} +inline void ObjectNudge::set_type(::apollo::decision::ObjectNudge_Type value) { + + type_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectNudge.type) +} + +// .apollo.decision.Range preferred_distance_l = 3; +inline bool ObjectNudge::has_preferred_distance_l() const { + return this != internal_default_instance() && preferred_distance_l_ != NULL; +} +inline void ObjectNudge::clear_preferred_distance_l() { + if (GetArenaNoVirtual() == NULL && preferred_distance_l_ != NULL) { + delete preferred_distance_l_; + } + preferred_distance_l_ = NULL; +} +inline const ::apollo::decision::Range& ObjectNudge::_internal_preferred_distance_l() const { + return *preferred_distance_l_; +} +inline const ::apollo::decision::Range& ObjectNudge::preferred_distance_l() const { + const ::apollo::decision::Range* p = preferred_distance_l_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectNudge.preferred_distance_l) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_Range_default_instance_); +} +inline ::apollo::decision::Range* ObjectNudge::release_preferred_distance_l() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectNudge.preferred_distance_l) + + ::apollo::decision::Range* temp = preferred_distance_l_; + preferred_distance_l_ = NULL; + return temp; +} +inline ::apollo::decision::Range* ObjectNudge::mutable_preferred_distance_l() { + + if (preferred_distance_l_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::Range>(GetArenaNoVirtual()); + preferred_distance_l_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectNudge.preferred_distance_l) + return preferred_distance_l_; +} +inline void ObjectNudge::set_allocated_preferred_distance_l(::apollo::decision::Range* preferred_distance_l) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete preferred_distance_l_; + } + if (preferred_distance_l) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + preferred_distance_l = ::google::protobuf::internal::GetOwnedMessage( + message_arena, preferred_distance_l, submessage_arena); + } + + } else { + + } + preferred_distance_l_ = preferred_distance_l; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectNudge.preferred_distance_l) +} + +// ------------------------------------------------------------------- + +// ObjectYield + +// double distance_s = 1; +inline void ObjectYield::clear_distance_s() { + distance_s_ = 0; +} +inline double ObjectYield::distance_s() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectYield.distance_s) + return distance_s_; +} +inline void ObjectYield::set_distance_s(double value) { + + distance_s_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectYield.distance_s) +} + +// .apollo.decision.Range preferred_distance_s = 2; +inline bool ObjectYield::has_preferred_distance_s() const { + return this != internal_default_instance() && preferred_distance_s_ != NULL; +} +inline void ObjectYield::clear_preferred_distance_s() { + if (GetArenaNoVirtual() == NULL && preferred_distance_s_ != NULL) { + delete preferred_distance_s_; + } + preferred_distance_s_ = NULL; +} +inline const ::apollo::decision::Range& ObjectYield::_internal_preferred_distance_s() const { + return *preferred_distance_s_; +} +inline const ::apollo::decision::Range& ObjectYield::preferred_distance_s() const { + const ::apollo::decision::Range* p = preferred_distance_s_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectYield.preferred_distance_s) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_Range_default_instance_); +} +inline ::apollo::decision::Range* ObjectYield::release_preferred_distance_s() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectYield.preferred_distance_s) + + ::apollo::decision::Range* temp = preferred_distance_s_; + preferred_distance_s_ = NULL; + return temp; +} +inline ::apollo::decision::Range* ObjectYield::mutable_preferred_distance_s() { + + if (preferred_distance_s_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::Range>(GetArenaNoVirtual()); + preferred_distance_s_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectYield.preferred_distance_s) + return preferred_distance_s_; +} +inline void ObjectYield::set_allocated_preferred_distance_s(::apollo::decision::Range* preferred_distance_s) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete preferred_distance_s_; + } + if (preferred_distance_s) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + preferred_distance_s = ::google::protobuf::internal::GetOwnedMessage( + message_arena, preferred_distance_s, submessage_arena); + } + + } else { + + } + preferred_distance_s_ = preferred_distance_s; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectYield.preferred_distance_s) +} + +// .apollo.common.PointENU yield_point = 3; +inline bool ObjectYield::has_yield_point() const { + return this != internal_default_instance() && yield_point_ != NULL; +} +inline const ::apollo::common::PointENU& ObjectYield::_internal_yield_point() const { + return *yield_point_; +} +inline const ::apollo::common::PointENU& ObjectYield::yield_point() const { + const ::apollo::common::PointENU* p = yield_point_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectYield.yield_point) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_PointENU_default_instance_); +} +inline ::apollo::common::PointENU* ObjectYield::release_yield_point() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectYield.yield_point) + + ::apollo::common::PointENU* temp = yield_point_; + yield_point_ = NULL; + return temp; +} +inline ::apollo::common::PointENU* ObjectYield::mutable_yield_point() { + + if (yield_point_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::PointENU>(GetArenaNoVirtual()); + yield_point_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectYield.yield_point) + return yield_point_; +} +inline void ObjectYield::set_allocated_yield_point(::apollo::common::PointENU* yield_point) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(yield_point_); + } + if (yield_point) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + yield_point = ::google::protobuf::internal::GetOwnedMessage( + message_arena, yield_point, submessage_arena); + } + + } else { + + } + yield_point_ = yield_point; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectYield.yield_point) +} + +// ------------------------------------------------------------------- + +// ObjectFollow + +// double distance_s = 1; +inline void ObjectFollow::clear_distance_s() { + distance_s_ = 0; +} +inline double ObjectFollow::distance_s() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectFollow.distance_s) + return distance_s_; +} +inline void ObjectFollow::set_distance_s(double value) { + + distance_s_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectFollow.distance_s) +} + +// .apollo.decision.Range preferred_distance_s = 2; +inline bool ObjectFollow::has_preferred_distance_s() const { + return this != internal_default_instance() && preferred_distance_s_ != NULL; +} +inline void ObjectFollow::clear_preferred_distance_s() { + if (GetArenaNoVirtual() == NULL && preferred_distance_s_ != NULL) { + delete preferred_distance_s_; + } + preferred_distance_s_ = NULL; +} +inline const ::apollo::decision::Range& ObjectFollow::_internal_preferred_distance_s() const { + return *preferred_distance_s_; +} +inline const ::apollo::decision::Range& ObjectFollow::preferred_distance_s() const { + const ::apollo::decision::Range* p = preferred_distance_s_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectFollow.preferred_distance_s) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_Range_default_instance_); +} +inline ::apollo::decision::Range* ObjectFollow::release_preferred_distance_s() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectFollow.preferred_distance_s) + + ::apollo::decision::Range* temp = preferred_distance_s_; + preferred_distance_s_ = NULL; + return temp; +} +inline ::apollo::decision::Range* ObjectFollow::mutable_preferred_distance_s() { + + if (preferred_distance_s_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::Range>(GetArenaNoVirtual()); + preferred_distance_s_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectFollow.preferred_distance_s) + return preferred_distance_s_; +} +inline void ObjectFollow::set_allocated_preferred_distance_s(::apollo::decision::Range* preferred_distance_s) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete preferred_distance_s_; + } + if (preferred_distance_s) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + preferred_distance_s = ::google::protobuf::internal::GetOwnedMessage( + message_arena, preferred_distance_s, submessage_arena); + } + + } else { + + } + preferred_distance_s_ = preferred_distance_s; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectFollow.preferred_distance_s) +} + +// .apollo.common.PointENU follow_point = 3; +inline bool ObjectFollow::has_follow_point() const { + return this != internal_default_instance() && follow_point_ != NULL; +} +inline const ::apollo::common::PointENU& ObjectFollow::_internal_follow_point() const { + return *follow_point_; +} +inline const ::apollo::common::PointENU& ObjectFollow::follow_point() const { + const ::apollo::common::PointENU* p = follow_point_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectFollow.follow_point) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_PointENU_default_instance_); +} +inline ::apollo::common::PointENU* ObjectFollow::release_follow_point() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectFollow.follow_point) + + ::apollo::common::PointENU* temp = follow_point_; + follow_point_ = NULL; + return temp; +} +inline ::apollo::common::PointENU* ObjectFollow::mutable_follow_point() { + + if (follow_point_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::PointENU>(GetArenaNoVirtual()); + follow_point_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectFollow.follow_point) + return follow_point_; +} +inline void ObjectFollow::set_allocated_follow_point(::apollo::common::PointENU* follow_point) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(follow_point_); + } + if (follow_point) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + follow_point = ::google::protobuf::internal::GetOwnedMessage( + message_arena, follow_point, submessage_arena); + } + + } else { + + } + follow_point_ = follow_point; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectFollow.follow_point) +} + +// ------------------------------------------------------------------- + +// ObjectOvertake + +// double distance_s = 1; +inline void ObjectOvertake::clear_distance_s() { + distance_s_ = 0; +} +inline double ObjectOvertake::distance_s() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectOvertake.distance_s) + return distance_s_; +} +inline void ObjectOvertake::set_distance_s(double value) { + + distance_s_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectOvertake.distance_s) +} + +// .apollo.decision.Range preferred_distance_s = 2; +inline bool ObjectOvertake::has_preferred_distance_s() const { + return this != internal_default_instance() && preferred_distance_s_ != NULL; +} +inline void ObjectOvertake::clear_preferred_distance_s() { + if (GetArenaNoVirtual() == NULL && preferred_distance_s_ != NULL) { + delete preferred_distance_s_; + } + preferred_distance_s_ = NULL; +} +inline const ::apollo::decision::Range& ObjectOvertake::_internal_preferred_distance_s() const { + return *preferred_distance_s_; +} +inline const ::apollo::decision::Range& ObjectOvertake::preferred_distance_s() const { + const ::apollo::decision::Range* p = preferred_distance_s_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectOvertake.preferred_distance_s) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_Range_default_instance_); +} +inline ::apollo::decision::Range* ObjectOvertake::release_preferred_distance_s() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectOvertake.preferred_distance_s) + + ::apollo::decision::Range* temp = preferred_distance_s_; + preferred_distance_s_ = NULL; + return temp; +} +inline ::apollo::decision::Range* ObjectOvertake::mutable_preferred_distance_s() { + + if (preferred_distance_s_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::Range>(GetArenaNoVirtual()); + preferred_distance_s_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectOvertake.preferred_distance_s) + return preferred_distance_s_; +} +inline void ObjectOvertake::set_allocated_preferred_distance_s(::apollo::decision::Range* preferred_distance_s) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete preferred_distance_s_; + } + if (preferred_distance_s) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + preferred_distance_s = ::google::protobuf::internal::GetOwnedMessage( + message_arena, preferred_distance_s, submessage_arena); + } + + } else { + + } + preferred_distance_s_ = preferred_distance_s; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectOvertake.preferred_distance_s) +} + +// .apollo.common.PointENU overtake_point = 3; +inline bool ObjectOvertake::has_overtake_point() const { + return this != internal_default_instance() && overtake_point_ != NULL; +} +inline const ::apollo::common::PointENU& ObjectOvertake::_internal_overtake_point() const { + return *overtake_point_; +} +inline const ::apollo::common::PointENU& ObjectOvertake::overtake_point() const { + const ::apollo::common::PointENU* p = overtake_point_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectOvertake.overtake_point) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_PointENU_default_instance_); +} +inline ::apollo::common::PointENU* ObjectOvertake::release_overtake_point() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectOvertake.overtake_point) + + ::apollo::common::PointENU* temp = overtake_point_; + overtake_point_ = NULL; + return temp; +} +inline ::apollo::common::PointENU* ObjectOvertake::mutable_overtake_point() { + + if (overtake_point_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::PointENU>(GetArenaNoVirtual()); + overtake_point_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectOvertake.overtake_point) + return overtake_point_; +} +inline void ObjectOvertake::set_allocated_overtake_point(::apollo::common::PointENU* overtake_point) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(overtake_point_); + } + if (overtake_point) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + overtake_point = ::google::protobuf::internal::GetOwnedMessage( + message_arena, overtake_point, submessage_arena); + } + + } else { + + } + overtake_point_ = overtake_point; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectOvertake.overtake_point) +} + +// ------------------------------------------------------------------- + +// ObjectSidePass + +// double distance_s = 1; +inline void ObjectSidePass::clear_distance_s() { + distance_s_ = 0; +} +inline double ObjectSidePass::distance_s() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectSidePass.distance_s) + return distance_s_; +} +inline void ObjectSidePass::set_distance_s(double value) { + + distance_s_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectSidePass.distance_s) +} + +// .apollo.decision.Range preferred_distance_s = 2; +inline bool ObjectSidePass::has_preferred_distance_s() const { + return this != internal_default_instance() && preferred_distance_s_ != NULL; +} +inline void ObjectSidePass::clear_preferred_distance_s() { + if (GetArenaNoVirtual() == NULL && preferred_distance_s_ != NULL) { + delete preferred_distance_s_; + } + preferred_distance_s_ = NULL; +} +inline const ::apollo::decision::Range& ObjectSidePass::_internal_preferred_distance_s() const { + return *preferred_distance_s_; +} +inline const ::apollo::decision::Range& ObjectSidePass::preferred_distance_s() const { + const ::apollo::decision::Range* p = preferred_distance_s_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectSidePass.preferred_distance_s) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_Range_default_instance_); +} +inline ::apollo::decision::Range* ObjectSidePass::release_preferred_distance_s() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectSidePass.preferred_distance_s) + + ::apollo::decision::Range* temp = preferred_distance_s_; + preferred_distance_s_ = NULL; + return temp; +} +inline ::apollo::decision::Range* ObjectSidePass::mutable_preferred_distance_s() { + + if (preferred_distance_s_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::Range>(GetArenaNoVirtual()); + preferred_distance_s_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectSidePass.preferred_distance_s) + return preferred_distance_s_; +} +inline void ObjectSidePass::set_allocated_preferred_distance_s(::apollo::decision::Range* preferred_distance_s) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete preferred_distance_s_; + } + if (preferred_distance_s) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + preferred_distance_s = ::google::protobuf::internal::GetOwnedMessage( + message_arena, preferred_distance_s, submessage_arena); + } + + } else { + + } + preferred_distance_s_ = preferred_distance_s; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectSidePass.preferred_distance_s) +} + +// .apollo.decision.ObjectSidePass.Type type = 3; +inline void ObjectSidePass::clear_type() { + type_ = 0; +} +inline ::apollo::decision::ObjectSidePass_Type ObjectSidePass::type() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectSidePass.type) + return static_cast< ::apollo::decision::ObjectSidePass_Type >(type_); +} +inline void ObjectSidePass::set_type(::apollo::decision::ObjectSidePass_Type value) { + + type_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectSidePass.type) +} + +// ------------------------------------------------------------------- + +// ObjectAvoid + +// ------------------------------------------------------------------- + +// ObjectDecisionType + +// .apollo.decision.ObjectIgnore ignore = 1; +inline bool ObjectDecisionType::has_ignore() const { + return object_tag_case() == kIgnore; +} +inline void ObjectDecisionType::set_has_ignore() { + _oneof_case_[0] = kIgnore; +} +inline void ObjectDecisionType::clear_ignore() { + if (has_ignore()) { + delete object_tag_.ignore_; + clear_has_object_tag(); + } +} +inline const ::apollo::decision::ObjectIgnore& ObjectDecisionType::_internal_ignore() const { + return *object_tag_.ignore_; +} +inline ::apollo::decision::ObjectIgnore* ObjectDecisionType::release_ignore() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDecisionType.ignore) + if (has_ignore()) { + clear_has_object_tag(); + ::apollo::decision::ObjectIgnore* temp = object_tag_.ignore_; + object_tag_.ignore_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::ObjectIgnore& ObjectDecisionType::ignore() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecisionType.ignore) + return has_ignore() + ? *object_tag_.ignore_ + : *reinterpret_cast< ::apollo::decision::ObjectIgnore*>(&::apollo::decision::_ObjectIgnore_default_instance_); +} +inline ::apollo::decision::ObjectIgnore* ObjectDecisionType::mutable_ignore() { + if (!has_ignore()) { + clear_object_tag(); + set_has_ignore(); + object_tag_.ignore_ = CreateMaybeMessage< ::apollo::decision::ObjectIgnore >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDecisionType.ignore) + return object_tag_.ignore_; +} + +// .apollo.decision.ObjectStop stop = 2; +inline bool ObjectDecisionType::has_stop() const { + return object_tag_case() == kStop; +} +inline void ObjectDecisionType::set_has_stop() { + _oneof_case_[0] = kStop; +} +inline void ObjectDecisionType::clear_stop() { + if (has_stop()) { + delete object_tag_.stop_; + clear_has_object_tag(); + } +} +inline const ::apollo::decision::ObjectStop& ObjectDecisionType::_internal_stop() const { + return *object_tag_.stop_; +} +inline ::apollo::decision::ObjectStop* ObjectDecisionType::release_stop() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDecisionType.stop) + if (has_stop()) { + clear_has_object_tag(); + ::apollo::decision::ObjectStop* temp = object_tag_.stop_; + object_tag_.stop_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::ObjectStop& ObjectDecisionType::stop() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecisionType.stop) + return has_stop() + ? *object_tag_.stop_ + : *reinterpret_cast< ::apollo::decision::ObjectStop*>(&::apollo::decision::_ObjectStop_default_instance_); +} +inline ::apollo::decision::ObjectStop* ObjectDecisionType::mutable_stop() { + if (!has_stop()) { + clear_object_tag(); + set_has_stop(); + object_tag_.stop_ = CreateMaybeMessage< ::apollo::decision::ObjectStop >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDecisionType.stop) + return object_tag_.stop_; +} + +// .apollo.decision.ObjectFollow follow = 3; +inline bool ObjectDecisionType::has_follow() const { + return object_tag_case() == kFollow; +} +inline void ObjectDecisionType::set_has_follow() { + _oneof_case_[0] = kFollow; +} +inline void ObjectDecisionType::clear_follow() { + if (has_follow()) { + delete object_tag_.follow_; + clear_has_object_tag(); + } +} +inline const ::apollo::decision::ObjectFollow& ObjectDecisionType::_internal_follow() const { + return *object_tag_.follow_; +} +inline ::apollo::decision::ObjectFollow* ObjectDecisionType::release_follow() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDecisionType.follow) + if (has_follow()) { + clear_has_object_tag(); + ::apollo::decision::ObjectFollow* temp = object_tag_.follow_; + object_tag_.follow_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::ObjectFollow& ObjectDecisionType::follow() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecisionType.follow) + return has_follow() + ? *object_tag_.follow_ + : *reinterpret_cast< ::apollo::decision::ObjectFollow*>(&::apollo::decision::_ObjectFollow_default_instance_); +} +inline ::apollo::decision::ObjectFollow* ObjectDecisionType::mutable_follow() { + if (!has_follow()) { + clear_object_tag(); + set_has_follow(); + object_tag_.follow_ = CreateMaybeMessage< ::apollo::decision::ObjectFollow >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDecisionType.follow) + return object_tag_.follow_; +} + +// .apollo.decision.ObjectYield yield = 4; +inline bool ObjectDecisionType::has_yield() const { + return object_tag_case() == kYield; +} +inline void ObjectDecisionType::set_has_yield() { + _oneof_case_[0] = kYield; +} +inline void ObjectDecisionType::clear_yield() { + if (has_yield()) { + delete object_tag_.yield_; + clear_has_object_tag(); + } +} +inline const ::apollo::decision::ObjectYield& ObjectDecisionType::_internal_yield() const { + return *object_tag_.yield_; +} +inline ::apollo::decision::ObjectYield* ObjectDecisionType::release_yield() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDecisionType.yield) + if (has_yield()) { + clear_has_object_tag(); + ::apollo::decision::ObjectYield* temp = object_tag_.yield_; + object_tag_.yield_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::ObjectYield& ObjectDecisionType::yield() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecisionType.yield) + return has_yield() + ? *object_tag_.yield_ + : *reinterpret_cast< ::apollo::decision::ObjectYield*>(&::apollo::decision::_ObjectYield_default_instance_); +} +inline ::apollo::decision::ObjectYield* ObjectDecisionType::mutable_yield() { + if (!has_yield()) { + clear_object_tag(); + set_has_yield(); + object_tag_.yield_ = CreateMaybeMessage< ::apollo::decision::ObjectYield >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDecisionType.yield) + return object_tag_.yield_; +} + +// .apollo.decision.ObjectOvertake overtake = 5; +inline bool ObjectDecisionType::has_overtake() const { + return object_tag_case() == kOvertake; +} +inline void ObjectDecisionType::set_has_overtake() { + _oneof_case_[0] = kOvertake; +} +inline void ObjectDecisionType::clear_overtake() { + if (has_overtake()) { + delete object_tag_.overtake_; + clear_has_object_tag(); + } +} +inline const ::apollo::decision::ObjectOvertake& ObjectDecisionType::_internal_overtake() const { + return *object_tag_.overtake_; +} +inline ::apollo::decision::ObjectOvertake* ObjectDecisionType::release_overtake() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDecisionType.overtake) + if (has_overtake()) { + clear_has_object_tag(); + ::apollo::decision::ObjectOvertake* temp = object_tag_.overtake_; + object_tag_.overtake_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::ObjectOvertake& ObjectDecisionType::overtake() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecisionType.overtake) + return has_overtake() + ? *object_tag_.overtake_ + : *reinterpret_cast< ::apollo::decision::ObjectOvertake*>(&::apollo::decision::_ObjectOvertake_default_instance_); +} +inline ::apollo::decision::ObjectOvertake* ObjectDecisionType::mutable_overtake() { + if (!has_overtake()) { + clear_object_tag(); + set_has_overtake(); + object_tag_.overtake_ = CreateMaybeMessage< ::apollo::decision::ObjectOvertake >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDecisionType.overtake) + return object_tag_.overtake_; +} + +// .apollo.decision.ObjectNudge nudge = 6; +inline bool ObjectDecisionType::has_nudge() const { + return object_tag_case() == kNudge; +} +inline void ObjectDecisionType::set_has_nudge() { + _oneof_case_[0] = kNudge; +} +inline void ObjectDecisionType::clear_nudge() { + if (has_nudge()) { + delete object_tag_.nudge_; + clear_has_object_tag(); + } +} +inline const ::apollo::decision::ObjectNudge& ObjectDecisionType::_internal_nudge() const { + return *object_tag_.nudge_; +} +inline ::apollo::decision::ObjectNudge* ObjectDecisionType::release_nudge() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDecisionType.nudge) + if (has_nudge()) { + clear_has_object_tag(); + ::apollo::decision::ObjectNudge* temp = object_tag_.nudge_; + object_tag_.nudge_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::ObjectNudge& ObjectDecisionType::nudge() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecisionType.nudge) + return has_nudge() + ? *object_tag_.nudge_ + : *reinterpret_cast< ::apollo::decision::ObjectNudge*>(&::apollo::decision::_ObjectNudge_default_instance_); +} +inline ::apollo::decision::ObjectNudge* ObjectDecisionType::mutable_nudge() { + if (!has_nudge()) { + clear_object_tag(); + set_has_nudge(); + object_tag_.nudge_ = CreateMaybeMessage< ::apollo::decision::ObjectNudge >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDecisionType.nudge) + return object_tag_.nudge_; +} + +// .apollo.decision.ObjectSidePass sidepass = 7; +inline bool ObjectDecisionType::has_sidepass() const { + return object_tag_case() == kSidepass; +} +inline void ObjectDecisionType::set_has_sidepass() { + _oneof_case_[0] = kSidepass; +} +inline void ObjectDecisionType::clear_sidepass() { + if (has_sidepass()) { + delete object_tag_.sidepass_; + clear_has_object_tag(); + } +} +inline const ::apollo::decision::ObjectSidePass& ObjectDecisionType::_internal_sidepass() const { + return *object_tag_.sidepass_; +} +inline ::apollo::decision::ObjectSidePass* ObjectDecisionType::release_sidepass() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDecisionType.sidepass) + if (has_sidepass()) { + clear_has_object_tag(); + ::apollo::decision::ObjectSidePass* temp = object_tag_.sidepass_; + object_tag_.sidepass_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::ObjectSidePass& ObjectDecisionType::sidepass() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecisionType.sidepass) + return has_sidepass() + ? *object_tag_.sidepass_ + : *reinterpret_cast< ::apollo::decision::ObjectSidePass*>(&::apollo::decision::_ObjectSidePass_default_instance_); +} +inline ::apollo::decision::ObjectSidePass* ObjectDecisionType::mutable_sidepass() { + if (!has_sidepass()) { + clear_object_tag(); + set_has_sidepass(); + object_tag_.sidepass_ = CreateMaybeMessage< ::apollo::decision::ObjectSidePass >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDecisionType.sidepass) + return object_tag_.sidepass_; +} + +// .apollo.decision.ObjectAvoid avoid = 8; +inline bool ObjectDecisionType::has_avoid() const { + return object_tag_case() == kAvoid; +} +inline void ObjectDecisionType::set_has_avoid() { + _oneof_case_[0] = kAvoid; +} +inline void ObjectDecisionType::clear_avoid() { + if (has_avoid()) { + delete object_tag_.avoid_; + clear_has_object_tag(); + } +} +inline const ::apollo::decision::ObjectAvoid& ObjectDecisionType::_internal_avoid() const { + return *object_tag_.avoid_; +} +inline ::apollo::decision::ObjectAvoid* ObjectDecisionType::release_avoid() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDecisionType.avoid) + if (has_avoid()) { + clear_has_object_tag(); + ::apollo::decision::ObjectAvoid* temp = object_tag_.avoid_; + object_tag_.avoid_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::ObjectAvoid& ObjectDecisionType::avoid() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecisionType.avoid) + return has_avoid() + ? *object_tag_.avoid_ + : *reinterpret_cast< ::apollo::decision::ObjectAvoid*>(&::apollo::decision::_ObjectAvoid_default_instance_); +} +inline ::apollo::decision::ObjectAvoid* ObjectDecisionType::mutable_avoid() { + if (!has_avoid()) { + clear_object_tag(); + set_has_avoid(); + object_tag_.avoid_ = CreateMaybeMessage< ::apollo::decision::ObjectAvoid >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDecisionType.avoid) + return object_tag_.avoid_; +} + +inline bool ObjectDecisionType::has_object_tag() const { + return object_tag_case() != OBJECT_TAG_NOT_SET; +} +inline void ObjectDecisionType::clear_has_object_tag() { + _oneof_case_[0] = OBJECT_TAG_NOT_SET; +} +inline ObjectDecisionType::ObjectTagCase ObjectDecisionType::object_tag_case() const { + return ObjectDecisionType::ObjectTagCase(_oneof_case_[0]); +} +// ------------------------------------------------------------------- + +// ObjectDecision + +// .apollo.prediction.PredictionObstacle prediction = 1; +inline bool ObjectDecision::has_prediction() const { + return this != internal_default_instance() && prediction_ != NULL; +} +inline const ::apollo::prediction::PredictionObstacle& ObjectDecision::_internal_prediction() const { + return *prediction_; +} +inline const ::apollo::prediction::PredictionObstacle& ObjectDecision::prediction() const { + const ::apollo::prediction::PredictionObstacle* p = prediction_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecision.prediction) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::prediction::_PredictionObstacle_default_instance_); +} +inline ::apollo::prediction::PredictionObstacle* ObjectDecision::release_prediction() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDecision.prediction) + + ::apollo::prediction::PredictionObstacle* temp = prediction_; + prediction_ = NULL; + return temp; +} +inline ::apollo::prediction::PredictionObstacle* ObjectDecision::mutable_prediction() { + + if (prediction_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::prediction::PredictionObstacle>(GetArenaNoVirtual()); + prediction_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDecision.prediction) + return prediction_; +} +inline void ObjectDecision::set_allocated_prediction(::apollo::prediction::PredictionObstacle* prediction) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(prediction_); + } + if (prediction) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + prediction = ::google::protobuf::internal::GetOwnedMessage( + message_arena, prediction, submessage_arena); + } + + } else { + + } + prediction_ = prediction; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDecision.prediction) +} + +// string id = 2; +inline void ObjectDecision::clear_id() { + id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& ObjectDecision::id() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecision.id) + return id_.GetNoArena(); +} +inline void ObjectDecision::set_id(const ::std::string& value) { + + id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.decision.ObjectDecision.id) +} +#if LANG_CXX11 +inline void ObjectDecision::set_id(::std::string&& value) { + + id_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.decision.ObjectDecision.id) +} +#endif +inline void ObjectDecision::set_id(const char* value) { + GOOGLE_DCHECK(value != NULL); + + id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.decision.ObjectDecision.id) +} +inline void ObjectDecision::set_id(const char* value, size_t size) { + + id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.decision.ObjectDecision.id) +} +inline ::std::string* ObjectDecision::mutable_id() { + + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDecision.id) + return id_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* ObjectDecision::release_id() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDecision.id) + + return id_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void ObjectDecision::set_allocated_id(::std::string* id) { + if (id != NULL) { + + } else { + + } + id_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), id); + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDecision.id) +} + +// .apollo.decision.ObjectDecision.ObjectType type = 3; +inline void ObjectDecision::clear_type() { + type_ = 0; +} +inline ::apollo::decision::ObjectDecision_ObjectType ObjectDecision::type() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecision.type) + return static_cast< ::apollo::decision::ObjectDecision_ObjectType >(type_); +} +inline void ObjectDecision::set_type(::apollo::decision::ObjectDecision_ObjectType value) { + + type_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectDecision.type) +} + +// .apollo.decision.ObjectDecisionType decision = 4; +inline bool ObjectDecision::has_decision() const { + return this != internal_default_instance() && decision_ != NULL; +} +inline void ObjectDecision::clear_decision() { + if (GetArenaNoVirtual() == NULL && decision_ != NULL) { + delete decision_; + } + decision_ = NULL; +} +inline const ::apollo::decision::ObjectDecisionType& ObjectDecision::_internal_decision() const { + return *decision_; +} +inline const ::apollo::decision::ObjectDecisionType& ObjectDecision::decision() const { + const ::apollo::decision::ObjectDecisionType* p = decision_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecision.decision) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_ObjectDecisionType_default_instance_); +} +inline ::apollo::decision::ObjectDecisionType* ObjectDecision::release_decision() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDecision.decision) + + ::apollo::decision::ObjectDecisionType* temp = decision_; + decision_ = NULL; + return temp; +} +inline ::apollo::decision::ObjectDecisionType* ObjectDecision::mutable_decision() { + + if (decision_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::ObjectDecisionType>(GetArenaNoVirtual()); + decision_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDecision.decision) + return decision_; +} +inline void ObjectDecision::set_allocated_decision(::apollo::decision::ObjectDecisionType* decision) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete decision_; + } + if (decision) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + decision = ::google::protobuf::internal::GetOwnedMessage( + message_arena, decision, submessage_arena); + } + + } else { + + } + decision_ = decision; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDecision.decision) +} + +// repeated .apollo.decision.ObjectDecisionType object_decision = 5; +inline int ObjectDecision::object_decision_size() const { + return object_decision_.size(); +} +inline void ObjectDecision::clear_object_decision() { + object_decision_.Clear(); +} +inline ::apollo::decision::ObjectDecisionType* ObjectDecision::mutable_object_decision(int index) { + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDecision.object_decision) + return object_decision_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecisionType >* +ObjectDecision::mutable_object_decision() { + // @@protoc_insertion_point(field_mutable_list:apollo.decision.ObjectDecision.object_decision) + return &object_decision_; +} +inline const ::apollo::decision::ObjectDecisionType& ObjectDecision::object_decision(int index) const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecision.object_decision) + return object_decision_.Get(index); +} +inline ::apollo::decision::ObjectDecisionType* ObjectDecision::add_object_decision() { + // @@protoc_insertion_point(field_add:apollo.decision.ObjectDecision.object_decision) + return object_decision_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecisionType >& +ObjectDecision::object_decision() const { + // @@protoc_insertion_point(field_list:apollo.decision.ObjectDecision.object_decision) + return object_decision_; +} + +// ------------------------------------------------------------------- + +// ObjectDecisions + +// repeated .apollo.decision.ObjectDecision decision = 1; +inline int ObjectDecisions::decision_size() const { + return decision_.size(); +} +inline void ObjectDecisions::clear_decision() { + decision_.Clear(); +} +inline ::apollo::decision::ObjectDecision* ObjectDecisions::mutable_decision(int index) { + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDecisions.decision) + return decision_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecision >* +ObjectDecisions::mutable_decision() { + // @@protoc_insertion_point(field_mutable_list:apollo.decision.ObjectDecisions.decision) + return &decision_; +} +inline const ::apollo::decision::ObjectDecision& ObjectDecisions::decision(int index) const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDecisions.decision) + return decision_.Get(index); +} +inline ::apollo::decision::ObjectDecision* ObjectDecisions::add_decision() { + // @@protoc_insertion_point(field_add:apollo.decision.ObjectDecisions.decision) + return decision_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecision >& +ObjectDecisions::decision() const { + // @@protoc_insertion_point(field_list:apollo.decision.ObjectDecisions.decision) + return decision_; +} + +// ------------------------------------------------------------------- + +// StopLine + +// string lane_id = 1; +inline void StopLine::clear_lane_id() { + lane_id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& StopLine::lane_id() const { + // @@protoc_insertion_point(field_get:apollo.decision.StopLine.lane_id) + return lane_id_.GetNoArena(); +} +inline void StopLine::set_lane_id(const ::std::string& value) { + + lane_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.decision.StopLine.lane_id) +} +#if LANG_CXX11 +inline void StopLine::set_lane_id(::std::string&& value) { + + lane_id_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.decision.StopLine.lane_id) +} +#endif +inline void StopLine::set_lane_id(const char* value) { + GOOGLE_DCHECK(value != NULL); + + lane_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.decision.StopLine.lane_id) +} +inline void StopLine::set_lane_id(const char* value, size_t size) { + + lane_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.decision.StopLine.lane_id) +} +inline ::std::string* StopLine::mutable_lane_id() { + + // @@protoc_insertion_point(field_mutable:apollo.decision.StopLine.lane_id) + return lane_id_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* StopLine::release_lane_id() { + // @@protoc_insertion_point(field_release:apollo.decision.StopLine.lane_id) + + return lane_id_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void StopLine::set_allocated_lane_id(::std::string* lane_id) { + if (lane_id != NULL) { + + } else { + + } + lane_id_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), lane_id); + // @@protoc_insertion_point(field_set_allocated:apollo.decision.StopLine.lane_id) +} + +// double distance_s = 2; +inline void StopLine::clear_distance_s() { + distance_s_ = 0; +} +inline double StopLine::distance_s() const { + // @@protoc_insertion_point(field_get:apollo.decision.StopLine.distance_s) + return distance_s_; +} +inline void StopLine::set_distance_s(double value) { + + distance_s_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.StopLine.distance_s) +} + +// ------------------------------------------------------------------- + +// MainStop + +// .apollo.decision.StopLine enforced_line = 1; +inline bool MainStop::has_enforced_line() const { + return this != internal_default_instance() && enforced_line_ != NULL; +} +inline void MainStop::clear_enforced_line() { + if (GetArenaNoVirtual() == NULL && enforced_line_ != NULL) { + delete enforced_line_; + } + enforced_line_ = NULL; +} +inline const ::apollo::decision::StopLine& MainStop::_internal_enforced_line() const { + return *enforced_line_; +} +inline const ::apollo::decision::StopLine& MainStop::enforced_line() const { + const ::apollo::decision::StopLine* p = enforced_line_; + // @@protoc_insertion_point(field_get:apollo.decision.MainStop.enforced_line) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_StopLine_default_instance_); +} +inline ::apollo::decision::StopLine* MainStop::release_enforced_line() { + // @@protoc_insertion_point(field_release:apollo.decision.MainStop.enforced_line) + + ::apollo::decision::StopLine* temp = enforced_line_; + enforced_line_ = NULL; + return temp; +} +inline ::apollo::decision::StopLine* MainStop::mutable_enforced_line() { + + if (enforced_line_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::StopLine>(GetArenaNoVirtual()); + enforced_line_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainStop.enforced_line) + return enforced_line_; +} +inline void MainStop::set_allocated_enforced_line(::apollo::decision::StopLine* enforced_line) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete enforced_line_; + } + if (enforced_line) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + enforced_line = ::google::protobuf::internal::GetOwnedMessage( + message_arena, enforced_line, submessage_arena); + } + + } else { + + } + enforced_line_ = enforced_line; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainStop.enforced_line) +} + +// .apollo.decision.StopLine preferred_start = 2; +inline bool MainStop::has_preferred_start() const { + return this != internal_default_instance() && preferred_start_ != NULL; +} +inline void MainStop::clear_preferred_start() { + if (GetArenaNoVirtual() == NULL && preferred_start_ != NULL) { + delete preferred_start_; + } + preferred_start_ = NULL; +} +inline const ::apollo::decision::StopLine& MainStop::_internal_preferred_start() const { + return *preferred_start_; +} +inline const ::apollo::decision::StopLine& MainStop::preferred_start() const { + const ::apollo::decision::StopLine* p = preferred_start_; + // @@protoc_insertion_point(field_get:apollo.decision.MainStop.preferred_start) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_StopLine_default_instance_); +} +inline ::apollo::decision::StopLine* MainStop::release_preferred_start() { + // @@protoc_insertion_point(field_release:apollo.decision.MainStop.preferred_start) + + ::apollo::decision::StopLine* temp = preferred_start_; + preferred_start_ = NULL; + return temp; +} +inline ::apollo::decision::StopLine* MainStop::mutable_preferred_start() { + + if (preferred_start_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::StopLine>(GetArenaNoVirtual()); + preferred_start_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainStop.preferred_start) + return preferred_start_; +} +inline void MainStop::set_allocated_preferred_start(::apollo::decision::StopLine* preferred_start) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete preferred_start_; + } + if (preferred_start) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + preferred_start = ::google::protobuf::internal::GetOwnedMessage( + message_arena, preferred_start, submessage_arena); + } + + } else { + + } + preferred_start_ = preferred_start; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainStop.preferred_start) +} + +// .apollo.decision.StopLine preferred_end = 3; +inline bool MainStop::has_preferred_end() const { + return this != internal_default_instance() && preferred_end_ != NULL; +} +inline void MainStop::clear_preferred_end() { + if (GetArenaNoVirtual() == NULL && preferred_end_ != NULL) { + delete preferred_end_; + } + preferred_end_ = NULL; +} +inline const ::apollo::decision::StopLine& MainStop::_internal_preferred_end() const { + return *preferred_end_; +} +inline const ::apollo::decision::StopLine& MainStop::preferred_end() const { + const ::apollo::decision::StopLine* p = preferred_end_; + // @@protoc_insertion_point(field_get:apollo.decision.MainStop.preferred_end) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_StopLine_default_instance_); +} +inline ::apollo::decision::StopLine* MainStop::release_preferred_end() { + // @@protoc_insertion_point(field_release:apollo.decision.MainStop.preferred_end) + + ::apollo::decision::StopLine* temp = preferred_end_; + preferred_end_ = NULL; + return temp; +} +inline ::apollo::decision::StopLine* MainStop::mutable_preferred_end() { + + if (preferred_end_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::StopLine>(GetArenaNoVirtual()); + preferred_end_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainStop.preferred_end) + return preferred_end_; +} +inline void MainStop::set_allocated_preferred_end(::apollo::decision::StopLine* preferred_end) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete preferred_end_; + } + if (preferred_end) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + preferred_end = ::google::protobuf::internal::GetOwnedMessage( + message_arena, preferred_end, submessage_arena); + } + + } else { + + } + preferred_end_ = preferred_end; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainStop.preferred_end) +} + +// string reason = 4; +inline void MainStop::clear_reason() { + reason_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& MainStop::reason() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainStop.reason) + return reason_.GetNoArena(); +} +inline void MainStop::set_reason(const ::std::string& value) { + + reason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.decision.MainStop.reason) +} +#if LANG_CXX11 +inline void MainStop::set_reason(::std::string&& value) { + + reason_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.decision.MainStop.reason) +} +#endif +inline void MainStop::set_reason(const char* value) { + GOOGLE_DCHECK(value != NULL); + + reason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.decision.MainStop.reason) +} +inline void MainStop::set_reason(const char* value, size_t size) { + + reason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.decision.MainStop.reason) +} +inline ::std::string* MainStop::mutable_reason() { + + // @@protoc_insertion_point(field_mutable:apollo.decision.MainStop.reason) + return reason_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* MainStop::release_reason() { + // @@protoc_insertion_point(field_release:apollo.decision.MainStop.reason) + + return reason_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void MainStop::set_allocated_reason(::std::string* reason) { + if (reason != NULL) { + + } else { + + } + reason_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), reason); + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainStop.reason) +} + +// .apollo.decision.StopReasonCode reason_code = 5; +inline void MainStop::clear_reason_code() { + reason_code_ = 0; +} +inline ::apollo::decision::StopReasonCode MainStop::reason_code() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainStop.reason_code) + return static_cast< ::apollo::decision::StopReasonCode >(reason_code_); +} +inline void MainStop::set_reason_code(::apollo::decision::StopReasonCode value) { + + reason_code_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.MainStop.reason_code) +} + +// .apollo.common.PointENU stop_point = 6; +inline bool MainStop::has_stop_point() const { + return this != internal_default_instance() && stop_point_ != NULL; +} +inline const ::apollo::common::PointENU& MainStop::_internal_stop_point() const { + return *stop_point_; +} +inline const ::apollo::common::PointENU& MainStop::stop_point() const { + const ::apollo::common::PointENU* p = stop_point_; + // @@protoc_insertion_point(field_get:apollo.decision.MainStop.stop_point) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_PointENU_default_instance_); +} +inline ::apollo::common::PointENU* MainStop::release_stop_point() { + // @@protoc_insertion_point(field_release:apollo.decision.MainStop.stop_point) + + ::apollo::common::PointENU* temp = stop_point_; + stop_point_ = NULL; + return temp; +} +inline ::apollo::common::PointENU* MainStop::mutable_stop_point() { + + if (stop_point_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::PointENU>(GetArenaNoVirtual()); + stop_point_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainStop.stop_point) + return stop_point_; +} +inline void MainStop::set_allocated_stop_point(::apollo::common::PointENU* stop_point) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(stop_point_); + } + if (stop_point) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + stop_point = ::google::protobuf::internal::GetOwnedMessage( + message_arena, stop_point, submessage_arena); + } + + } else { + + } + stop_point_ = stop_point; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainStop.stop_point) +} + +// double stop_heading = 7; +inline void MainStop::clear_stop_heading() { + stop_heading_ = 0; +} +inline double MainStop::stop_heading() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainStop.stop_heading) + return stop_heading_; +} +inline void MainStop::set_stop_heading(double value) { + + stop_heading_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.MainStop.stop_heading) +} + +// ------------------------------------------------------------------- + +// EmergencyStopHardBrake + +// ------------------------------------------------------------------- + +// EmergencyStopCruiseToStop + +// ------------------------------------------------------------------- + +// MainEmergencyStop + +// string reason = 1; +inline void MainEmergencyStop::clear_reason() { + reason_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& MainEmergencyStop::reason() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainEmergencyStop.reason) + return reason_.GetNoArena(); +} +inline void MainEmergencyStop::set_reason(const ::std::string& value) { + + reason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.decision.MainEmergencyStop.reason) +} +#if LANG_CXX11 +inline void MainEmergencyStop::set_reason(::std::string&& value) { + + reason_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.decision.MainEmergencyStop.reason) +} +#endif +inline void MainEmergencyStop::set_reason(const char* value) { + GOOGLE_DCHECK(value != NULL); + + reason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.decision.MainEmergencyStop.reason) +} +inline void MainEmergencyStop::set_reason(const char* value, size_t size) { + + reason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.decision.MainEmergencyStop.reason) +} +inline ::std::string* MainEmergencyStop::mutable_reason() { + + // @@protoc_insertion_point(field_mutable:apollo.decision.MainEmergencyStop.reason) + return reason_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* MainEmergencyStop::release_reason() { + // @@protoc_insertion_point(field_release:apollo.decision.MainEmergencyStop.reason) + + return reason_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void MainEmergencyStop::set_allocated_reason(::std::string* reason) { + if (reason != NULL) { + + } else { + + } + reason_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), reason); + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainEmergencyStop.reason) +} + +// .apollo.decision.MainEmergencyStop.ReasonCode reason_code = 2; +inline void MainEmergencyStop::clear_reason_code() { + reason_code_ = 0; +} +inline ::apollo::decision::MainEmergencyStop_ReasonCode MainEmergencyStop::reason_code() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainEmergencyStop.reason_code) + return static_cast< ::apollo::decision::MainEmergencyStop_ReasonCode >(reason_code_); +} +inline void MainEmergencyStop::set_reason_code(::apollo::decision::MainEmergencyStop_ReasonCode value) { + + reason_code_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.MainEmergencyStop.reason_code) +} + +// .apollo.decision.EmergencyStopHardBrake hard_brake = 3; +inline bool MainEmergencyStop::has_hard_brake() const { + return task_case() == kHardBrake; +} +inline void MainEmergencyStop::set_has_hard_brake() { + _oneof_case_[0] = kHardBrake; +} +inline void MainEmergencyStop::clear_hard_brake() { + if (has_hard_brake()) { + delete task_.hard_brake_; + clear_has_task(); + } +} +inline const ::apollo::decision::EmergencyStopHardBrake& MainEmergencyStop::_internal_hard_brake() const { + return *task_.hard_brake_; +} +inline ::apollo::decision::EmergencyStopHardBrake* MainEmergencyStop::release_hard_brake() { + // @@protoc_insertion_point(field_release:apollo.decision.MainEmergencyStop.hard_brake) + if (has_hard_brake()) { + clear_has_task(); + ::apollo::decision::EmergencyStopHardBrake* temp = task_.hard_brake_; + task_.hard_brake_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::EmergencyStopHardBrake& MainEmergencyStop::hard_brake() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainEmergencyStop.hard_brake) + return has_hard_brake() + ? *task_.hard_brake_ + : *reinterpret_cast< ::apollo::decision::EmergencyStopHardBrake*>(&::apollo::decision::_EmergencyStopHardBrake_default_instance_); +} +inline ::apollo::decision::EmergencyStopHardBrake* MainEmergencyStop::mutable_hard_brake() { + if (!has_hard_brake()) { + clear_task(); + set_has_hard_brake(); + task_.hard_brake_ = CreateMaybeMessage< ::apollo::decision::EmergencyStopHardBrake >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainEmergencyStop.hard_brake) + return task_.hard_brake_; +} + +// .apollo.decision.EmergencyStopCruiseToStop cruise_to_stop = 4; +inline bool MainEmergencyStop::has_cruise_to_stop() const { + return task_case() == kCruiseToStop; +} +inline void MainEmergencyStop::set_has_cruise_to_stop() { + _oneof_case_[0] = kCruiseToStop; +} +inline void MainEmergencyStop::clear_cruise_to_stop() { + if (has_cruise_to_stop()) { + delete task_.cruise_to_stop_; + clear_has_task(); + } +} +inline const ::apollo::decision::EmergencyStopCruiseToStop& MainEmergencyStop::_internal_cruise_to_stop() const { + return *task_.cruise_to_stop_; +} +inline ::apollo::decision::EmergencyStopCruiseToStop* MainEmergencyStop::release_cruise_to_stop() { + // @@protoc_insertion_point(field_release:apollo.decision.MainEmergencyStop.cruise_to_stop) + if (has_cruise_to_stop()) { + clear_has_task(); + ::apollo::decision::EmergencyStopCruiseToStop* temp = task_.cruise_to_stop_; + task_.cruise_to_stop_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::EmergencyStopCruiseToStop& MainEmergencyStop::cruise_to_stop() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainEmergencyStop.cruise_to_stop) + return has_cruise_to_stop() + ? *task_.cruise_to_stop_ + : *reinterpret_cast< ::apollo::decision::EmergencyStopCruiseToStop*>(&::apollo::decision::_EmergencyStopCruiseToStop_default_instance_); +} +inline ::apollo::decision::EmergencyStopCruiseToStop* MainEmergencyStop::mutable_cruise_to_stop() { + if (!has_cruise_to_stop()) { + clear_task(); + set_has_cruise_to_stop(); + task_.cruise_to_stop_ = CreateMaybeMessage< ::apollo::decision::EmergencyStopCruiseToStop >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainEmergencyStop.cruise_to_stop) + return task_.cruise_to_stop_; +} + +inline bool MainEmergencyStop::has_task() const { + return task_case() != TASK_NOT_SET; +} +inline void MainEmergencyStop::clear_has_task() { + _oneof_case_[0] = TASK_NOT_SET; +} +inline MainEmergencyStop::TaskCase MainEmergencyStop::task_case() const { + return MainEmergencyStop::TaskCase(_oneof_case_[0]); +} +// ------------------------------------------------------------------- + +// MainCruise + +// ------------------------------------------------------------------- + +// MainChangeLane + +// .apollo.decision.MainChangeLane.Type type = 1; +inline void MainChangeLane::clear_type() { + type_ = 0; +} +inline ::apollo::decision::MainChangeLane_Type MainChangeLane::type() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainChangeLane.type) + return static_cast< ::apollo::decision::MainChangeLane_Type >(type_); +} +inline void MainChangeLane::set_type(::apollo::decision::MainChangeLane_Type value) { + + type_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.MainChangeLane.type) +} + +// repeated .apollo.decision.TargetLane default_lane = 2; +inline int MainChangeLane::default_lane_size() const { + return default_lane_.size(); +} +inline void MainChangeLane::clear_default_lane() { + default_lane_.Clear(); +} +inline ::apollo::decision::TargetLane* MainChangeLane::mutable_default_lane(int index) { + // @@protoc_insertion_point(field_mutable:apollo.decision.MainChangeLane.default_lane) + return default_lane_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::decision::TargetLane >* +MainChangeLane::mutable_default_lane() { + // @@protoc_insertion_point(field_mutable_list:apollo.decision.MainChangeLane.default_lane) + return &default_lane_; +} +inline const ::apollo::decision::TargetLane& MainChangeLane::default_lane(int index) const { + // @@protoc_insertion_point(field_get:apollo.decision.MainChangeLane.default_lane) + return default_lane_.Get(index); +} +inline ::apollo::decision::TargetLane* MainChangeLane::add_default_lane() { + // @@protoc_insertion_point(field_add:apollo.decision.MainChangeLane.default_lane) + return default_lane_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::decision::TargetLane >& +MainChangeLane::default_lane() const { + // @@protoc_insertion_point(field_list:apollo.decision.MainChangeLane.default_lane) + return default_lane_; +} + +// .apollo.decision.MainStop default_lane_stop = 3; +inline bool MainChangeLane::has_default_lane_stop() const { + return this != internal_default_instance() && default_lane_stop_ != NULL; +} +inline void MainChangeLane::clear_default_lane_stop() { + if (GetArenaNoVirtual() == NULL && default_lane_stop_ != NULL) { + delete default_lane_stop_; + } + default_lane_stop_ = NULL; +} +inline const ::apollo::decision::MainStop& MainChangeLane::_internal_default_lane_stop() const { + return *default_lane_stop_; +} +inline const ::apollo::decision::MainStop& MainChangeLane::default_lane_stop() const { + const ::apollo::decision::MainStop* p = default_lane_stop_; + // @@protoc_insertion_point(field_get:apollo.decision.MainChangeLane.default_lane_stop) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_MainStop_default_instance_); +} +inline ::apollo::decision::MainStop* MainChangeLane::release_default_lane_stop() { + // @@protoc_insertion_point(field_release:apollo.decision.MainChangeLane.default_lane_stop) + + ::apollo::decision::MainStop* temp = default_lane_stop_; + default_lane_stop_ = NULL; + return temp; +} +inline ::apollo::decision::MainStop* MainChangeLane::mutable_default_lane_stop() { + + if (default_lane_stop_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::MainStop>(GetArenaNoVirtual()); + default_lane_stop_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainChangeLane.default_lane_stop) + return default_lane_stop_; +} +inline void MainChangeLane::set_allocated_default_lane_stop(::apollo::decision::MainStop* default_lane_stop) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete default_lane_stop_; + } + if (default_lane_stop) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + default_lane_stop = ::google::protobuf::internal::GetOwnedMessage( + message_arena, default_lane_stop, submessage_arena); + } + + } else { + + } + default_lane_stop_ = default_lane_stop; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainChangeLane.default_lane_stop) +} + +// .apollo.decision.MainStop target_lane_stop = 4; +inline bool MainChangeLane::has_target_lane_stop() const { + return this != internal_default_instance() && target_lane_stop_ != NULL; +} +inline void MainChangeLane::clear_target_lane_stop() { + if (GetArenaNoVirtual() == NULL && target_lane_stop_ != NULL) { + delete target_lane_stop_; + } + target_lane_stop_ = NULL; +} +inline const ::apollo::decision::MainStop& MainChangeLane::_internal_target_lane_stop() const { + return *target_lane_stop_; +} +inline const ::apollo::decision::MainStop& MainChangeLane::target_lane_stop() const { + const ::apollo::decision::MainStop* p = target_lane_stop_; + // @@protoc_insertion_point(field_get:apollo.decision.MainChangeLane.target_lane_stop) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_MainStop_default_instance_); +} +inline ::apollo::decision::MainStop* MainChangeLane::release_target_lane_stop() { + // @@protoc_insertion_point(field_release:apollo.decision.MainChangeLane.target_lane_stop) + + ::apollo::decision::MainStop* temp = target_lane_stop_; + target_lane_stop_ = NULL; + return temp; +} +inline ::apollo::decision::MainStop* MainChangeLane::mutable_target_lane_stop() { + + if (target_lane_stop_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::MainStop>(GetArenaNoVirtual()); + target_lane_stop_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainChangeLane.target_lane_stop) + return target_lane_stop_; +} +inline void MainChangeLane::set_allocated_target_lane_stop(::apollo::decision::MainStop* target_lane_stop) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete target_lane_stop_; + } + if (target_lane_stop) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + target_lane_stop = ::google::protobuf::internal::GetOwnedMessage( + message_arena, target_lane_stop, submessage_arena); + } + + } else { + + } + target_lane_stop_ = target_lane_stop; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainChangeLane.target_lane_stop) +} + +// ------------------------------------------------------------------- + +// MainMissionComplete + +// ------------------------------------------------------------------- + +// MainNotReady + +// string reason = 1; +inline void MainNotReady::clear_reason() { + reason_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& MainNotReady::reason() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainNotReady.reason) + return reason_.GetNoArena(); +} +inline void MainNotReady::set_reason(const ::std::string& value) { + + reason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.decision.MainNotReady.reason) +} +#if LANG_CXX11 +inline void MainNotReady::set_reason(::std::string&& value) { + + reason_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.decision.MainNotReady.reason) +} +#endif +inline void MainNotReady::set_reason(const char* value) { + GOOGLE_DCHECK(value != NULL); + + reason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.decision.MainNotReady.reason) +} +inline void MainNotReady::set_reason(const char* value, size_t size) { + + reason_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.decision.MainNotReady.reason) +} +inline ::std::string* MainNotReady::mutable_reason() { + + // @@protoc_insertion_point(field_mutable:apollo.decision.MainNotReady.reason) + return reason_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* MainNotReady::release_reason() { + // @@protoc_insertion_point(field_release:apollo.decision.MainNotReady.reason) + + return reason_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void MainNotReady::set_allocated_reason(::std::string* reason) { + if (reason != NULL) { + + } else { + + } + reason_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), reason); + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainNotReady.reason) +} + +// ------------------------------------------------------------------- + +// MainParking + +// .apollo.decision.MainParking.Type type = 1; +inline void MainParking::clear_type() { + type_ = 0; +} +inline ::apollo::decision::MainParking_Type MainParking::type() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainParking.type) + return static_cast< ::apollo::decision::MainParking_Type >(type_); +} +inline void MainParking::set_type(::apollo::decision::MainParking_Type value) { + + type_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.MainParking.type) +} + +// double heading = 2; +inline void MainParking::clear_heading() { + heading_ = 0; +} +inline double MainParking::heading() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainParking.heading) + return heading_; +} +inline void MainParking::set_heading(double value) { + + heading_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.MainParking.heading) +} + +// .apollo.common.PointENU stop_point = 3; +inline bool MainParking::has_stop_point() const { + return this != internal_default_instance() && stop_point_ != NULL; +} +inline const ::apollo::common::PointENU& MainParking::_internal_stop_point() const { + return *stop_point_; +} +inline const ::apollo::common::PointENU& MainParking::stop_point() const { + const ::apollo::common::PointENU* p = stop_point_; + // @@protoc_insertion_point(field_get:apollo.decision.MainParking.stop_point) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_PointENU_default_instance_); +} +inline ::apollo::common::PointENU* MainParking::release_stop_point() { + // @@protoc_insertion_point(field_release:apollo.decision.MainParking.stop_point) + + ::apollo::common::PointENU* temp = stop_point_; + stop_point_ = NULL; + return temp; +} +inline ::apollo::common::PointENU* MainParking::mutable_stop_point() { + + if (stop_point_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::PointENU>(GetArenaNoVirtual()); + stop_point_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainParking.stop_point) + return stop_point_; +} +inline void MainParking::set_allocated_stop_point(::apollo::common::PointENU* stop_point) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(stop_point_); + } + if (stop_point) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + stop_point = ::google::protobuf::internal::GetOwnedMessage( + message_arena, stop_point, submessage_arena); + } + + } else { + + } + stop_point_ = stop_point; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MainParking.stop_point) +} + +// repeated .apollo.common.PointENU parking_polygon = 4; +inline int MainParking::parking_polygon_size() const { + return parking_polygon_.size(); +} +inline ::apollo::common::PointENU* MainParking::mutable_parking_polygon(int index) { + // @@protoc_insertion_point(field_mutable:apollo.decision.MainParking.parking_polygon) + return parking_polygon_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::common::PointENU >* +MainParking::mutable_parking_polygon() { + // @@protoc_insertion_point(field_mutable_list:apollo.decision.MainParking.parking_polygon) + return &parking_polygon_; +} +inline const ::apollo::common::PointENU& MainParking::parking_polygon(int index) const { + // @@protoc_insertion_point(field_get:apollo.decision.MainParking.parking_polygon) + return parking_polygon_.Get(index); +} +inline ::apollo::common::PointENU* MainParking::add_parking_polygon() { + // @@protoc_insertion_point(field_add:apollo.decision.MainParking.parking_polygon) + return parking_polygon_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::common::PointENU >& +MainParking::parking_polygon() const { + // @@protoc_insertion_point(field_list:apollo.decision.MainParking.parking_polygon) + return parking_polygon_; +} + +// ------------------------------------------------------------------- + +// MainDecision + +// .apollo.decision.MainCruise cruise = 1; +inline bool MainDecision::has_cruise() const { + return task_case() == kCruise; +} +inline void MainDecision::set_has_cruise() { + _oneof_case_[0] = kCruise; +} +inline void MainDecision::clear_cruise() { + if (has_cruise()) { + delete task_.cruise_; + clear_has_task(); + } +} +inline const ::apollo::decision::MainCruise& MainDecision::_internal_cruise() const { + return *task_.cruise_; +} +inline ::apollo::decision::MainCruise* MainDecision::release_cruise() { + // @@protoc_insertion_point(field_release:apollo.decision.MainDecision.cruise) + if (has_cruise()) { + clear_has_task(); + ::apollo::decision::MainCruise* temp = task_.cruise_; + task_.cruise_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::MainCruise& MainDecision::cruise() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainDecision.cruise) + return has_cruise() + ? *task_.cruise_ + : *reinterpret_cast< ::apollo::decision::MainCruise*>(&::apollo::decision::_MainCruise_default_instance_); +} +inline ::apollo::decision::MainCruise* MainDecision::mutable_cruise() { + if (!has_cruise()) { + clear_task(); + set_has_cruise(); + task_.cruise_ = CreateMaybeMessage< ::apollo::decision::MainCruise >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainDecision.cruise) + return task_.cruise_; +} + +// .apollo.decision.MainStop stop = 2; +inline bool MainDecision::has_stop() const { + return task_case() == kStop; +} +inline void MainDecision::set_has_stop() { + _oneof_case_[0] = kStop; +} +inline void MainDecision::clear_stop() { + if (has_stop()) { + delete task_.stop_; + clear_has_task(); + } +} +inline const ::apollo::decision::MainStop& MainDecision::_internal_stop() const { + return *task_.stop_; +} +inline ::apollo::decision::MainStop* MainDecision::release_stop() { + // @@protoc_insertion_point(field_release:apollo.decision.MainDecision.stop) + if (has_stop()) { + clear_has_task(); + ::apollo::decision::MainStop* temp = task_.stop_; + task_.stop_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::MainStop& MainDecision::stop() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainDecision.stop) + return has_stop() + ? *task_.stop_ + : *reinterpret_cast< ::apollo::decision::MainStop*>(&::apollo::decision::_MainStop_default_instance_); +} +inline ::apollo::decision::MainStop* MainDecision::mutable_stop() { + if (!has_stop()) { + clear_task(); + set_has_stop(); + task_.stop_ = CreateMaybeMessage< ::apollo::decision::MainStop >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainDecision.stop) + return task_.stop_; +} + +// .apollo.decision.MainEmergencyStop estop = 3; +inline bool MainDecision::has_estop() const { + return task_case() == kEstop; +} +inline void MainDecision::set_has_estop() { + _oneof_case_[0] = kEstop; +} +inline void MainDecision::clear_estop() { + if (has_estop()) { + delete task_.estop_; + clear_has_task(); + } +} +inline const ::apollo::decision::MainEmergencyStop& MainDecision::_internal_estop() const { + return *task_.estop_; +} +inline ::apollo::decision::MainEmergencyStop* MainDecision::release_estop() { + // @@protoc_insertion_point(field_release:apollo.decision.MainDecision.estop) + if (has_estop()) { + clear_has_task(); + ::apollo::decision::MainEmergencyStop* temp = task_.estop_; + task_.estop_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::MainEmergencyStop& MainDecision::estop() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainDecision.estop) + return has_estop() + ? *task_.estop_ + : *reinterpret_cast< ::apollo::decision::MainEmergencyStop*>(&::apollo::decision::_MainEmergencyStop_default_instance_); +} +inline ::apollo::decision::MainEmergencyStop* MainDecision::mutable_estop() { + if (!has_estop()) { + clear_task(); + set_has_estop(); + task_.estop_ = CreateMaybeMessage< ::apollo::decision::MainEmergencyStop >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainDecision.estop) + return task_.estop_; +} + +// .apollo.decision.MainChangeLane change_lane = 4; +inline bool MainDecision::has_change_lane() const { + return task_case() == kChangeLane; +} +inline void MainDecision::set_has_change_lane() { + _oneof_case_[0] = kChangeLane; +} +inline void MainDecision::clear_change_lane() { + if (has_change_lane()) { + delete task_.change_lane_; + clear_has_task(); + } +} +inline const ::apollo::decision::MainChangeLane& MainDecision::_internal_change_lane() const { + return *task_.change_lane_; +} +inline ::apollo::decision::MainChangeLane* MainDecision::release_change_lane() { + // @@protoc_insertion_point(field_release:apollo.decision.MainDecision.change_lane) + if (has_change_lane()) { + clear_has_task(); + ::apollo::decision::MainChangeLane* temp = task_.change_lane_; + task_.change_lane_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::MainChangeLane& MainDecision::change_lane() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainDecision.change_lane) + return has_change_lane() + ? *task_.change_lane_ + : *reinterpret_cast< ::apollo::decision::MainChangeLane*>(&::apollo::decision::_MainChangeLane_default_instance_); +} +inline ::apollo::decision::MainChangeLane* MainDecision::mutable_change_lane() { + if (!has_change_lane()) { + clear_task(); + set_has_change_lane(); + task_.change_lane_ = CreateMaybeMessage< ::apollo::decision::MainChangeLane >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainDecision.change_lane) + return task_.change_lane_; +} + +// .apollo.decision.MainMissionComplete mission_complete = 6; +inline bool MainDecision::has_mission_complete() const { + return task_case() == kMissionComplete; +} +inline void MainDecision::set_has_mission_complete() { + _oneof_case_[0] = kMissionComplete; +} +inline void MainDecision::clear_mission_complete() { + if (has_mission_complete()) { + delete task_.mission_complete_; + clear_has_task(); + } +} +inline const ::apollo::decision::MainMissionComplete& MainDecision::_internal_mission_complete() const { + return *task_.mission_complete_; +} +inline ::apollo::decision::MainMissionComplete* MainDecision::release_mission_complete() { + // @@protoc_insertion_point(field_release:apollo.decision.MainDecision.mission_complete) + if (has_mission_complete()) { + clear_has_task(); + ::apollo::decision::MainMissionComplete* temp = task_.mission_complete_; + task_.mission_complete_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::MainMissionComplete& MainDecision::mission_complete() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainDecision.mission_complete) + return has_mission_complete() + ? *task_.mission_complete_ + : *reinterpret_cast< ::apollo::decision::MainMissionComplete*>(&::apollo::decision::_MainMissionComplete_default_instance_); +} +inline ::apollo::decision::MainMissionComplete* MainDecision::mutable_mission_complete() { + if (!has_mission_complete()) { + clear_task(); + set_has_mission_complete(); + task_.mission_complete_ = CreateMaybeMessage< ::apollo::decision::MainMissionComplete >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainDecision.mission_complete) + return task_.mission_complete_; +} + +// .apollo.decision.MainNotReady not_ready = 7; +inline bool MainDecision::has_not_ready() const { + return task_case() == kNotReady; +} +inline void MainDecision::set_has_not_ready() { + _oneof_case_[0] = kNotReady; +} +inline void MainDecision::clear_not_ready() { + if (has_not_ready()) { + delete task_.not_ready_; + clear_has_task(); + } +} +inline const ::apollo::decision::MainNotReady& MainDecision::_internal_not_ready() const { + return *task_.not_ready_; +} +inline ::apollo::decision::MainNotReady* MainDecision::release_not_ready() { + // @@protoc_insertion_point(field_release:apollo.decision.MainDecision.not_ready) + if (has_not_ready()) { + clear_has_task(); + ::apollo::decision::MainNotReady* temp = task_.not_ready_; + task_.not_ready_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::MainNotReady& MainDecision::not_ready() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainDecision.not_ready) + return has_not_ready() + ? *task_.not_ready_ + : *reinterpret_cast< ::apollo::decision::MainNotReady*>(&::apollo::decision::_MainNotReady_default_instance_); +} +inline ::apollo::decision::MainNotReady* MainDecision::mutable_not_ready() { + if (!has_not_ready()) { + clear_task(); + set_has_not_ready(); + task_.not_ready_ = CreateMaybeMessage< ::apollo::decision::MainNotReady >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainDecision.not_ready) + return task_.not_ready_; +} + +// .apollo.decision.MainParking parking = 8; +inline bool MainDecision::has_parking() const { + return task_case() == kParking; +} +inline void MainDecision::set_has_parking() { + _oneof_case_[0] = kParking; +} +inline void MainDecision::clear_parking() { + if (has_parking()) { + delete task_.parking_; + clear_has_task(); + } +} +inline const ::apollo::decision::MainParking& MainDecision::_internal_parking() const { + return *task_.parking_; +} +inline ::apollo::decision::MainParking* MainDecision::release_parking() { + // @@protoc_insertion_point(field_release:apollo.decision.MainDecision.parking) + if (has_parking()) { + clear_has_task(); + ::apollo::decision::MainParking* temp = task_.parking_; + task_.parking_ = NULL; + return temp; + } else { + return NULL; + } +} +inline const ::apollo::decision::MainParking& MainDecision::parking() const { + // @@protoc_insertion_point(field_get:apollo.decision.MainDecision.parking) + return has_parking() + ? *task_.parking_ + : *reinterpret_cast< ::apollo::decision::MainParking*>(&::apollo::decision::_MainParking_default_instance_); +} +inline ::apollo::decision::MainParking* MainDecision::mutable_parking() { + if (!has_parking()) { + clear_task(); + set_has_parking(); + task_.parking_ = CreateMaybeMessage< ::apollo::decision::MainParking >( + GetArenaNoVirtual()); + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MainDecision.parking) + return task_.parking_; +} + +// repeated .apollo.decision.TargetLane target_lane = 5; +inline int MainDecision::target_lane_size() const { + return target_lane_.size(); +} +inline void MainDecision::clear_target_lane() { + target_lane_.Clear(); +} +inline ::apollo::decision::TargetLane* MainDecision::mutable_target_lane(int index) { + // @@protoc_insertion_point(field_mutable:apollo.decision.MainDecision.target_lane) + return target_lane_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::decision::TargetLane >* +MainDecision::mutable_target_lane() { + // @@protoc_insertion_point(field_mutable_list:apollo.decision.MainDecision.target_lane) + return &target_lane_; +} +inline const ::apollo::decision::TargetLane& MainDecision::target_lane(int index) const { + // @@protoc_insertion_point(field_get:apollo.decision.MainDecision.target_lane) + return target_lane_.Get(index); +} +inline ::apollo::decision::TargetLane* MainDecision::add_target_lane() { + // @@protoc_insertion_point(field_add:apollo.decision.MainDecision.target_lane) + return target_lane_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::decision::TargetLane >& +MainDecision::target_lane() const { + // @@protoc_insertion_point(field_list:apollo.decision.MainDecision.target_lane) + return target_lane_; +} + +inline bool MainDecision::has_task() const { + return task_case() != TASK_NOT_SET; +} +inline void MainDecision::clear_has_task() { + _oneof_case_[0] = TASK_NOT_SET; +} +inline MainDecision::TaskCase MainDecision::task_case() const { + return MainDecision::TaskCase(_oneof_case_[0]); +} +// ------------------------------------------------------------------- + +// MasterVehicleDebug + +// .apollo.common.PointENU position = 1; +inline bool MasterVehicleDebug::has_position() const { + return this != internal_default_instance() && position_ != NULL; +} +inline const ::apollo::common::PointENU& MasterVehicleDebug::_internal_position() const { + return *position_; +} +inline const ::apollo::common::PointENU& MasterVehicleDebug::position() const { + const ::apollo::common::PointENU* p = position_; + // @@protoc_insertion_point(field_get:apollo.decision.MasterVehicleDebug.position) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_PointENU_default_instance_); +} +inline ::apollo::common::PointENU* MasterVehicleDebug::release_position() { + // @@protoc_insertion_point(field_release:apollo.decision.MasterVehicleDebug.position) + + ::apollo::common::PointENU* temp = position_; + position_ = NULL; + return temp; +} +inline ::apollo::common::PointENU* MasterVehicleDebug::mutable_position() { + + if (position_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::PointENU>(GetArenaNoVirtual()); + position_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MasterVehicleDebug.position) + return position_; +} +inline void MasterVehicleDebug::set_allocated_position(::apollo::common::PointENU* position) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(position_); + } + if (position) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + position = ::google::protobuf::internal::GetOwnedMessage( + message_arena, position, submessage_arena); + } + + } else { + + } + position_ = position; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MasterVehicleDebug.position) +} + +// string current_lane_id = 2; +inline void MasterVehicleDebug::clear_current_lane_id() { + current_lane_id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& MasterVehicleDebug::current_lane_id() const { + // @@protoc_insertion_point(field_get:apollo.decision.MasterVehicleDebug.current_lane_id) + return current_lane_id_.GetNoArena(); +} +inline void MasterVehicleDebug::set_current_lane_id(const ::std::string& value) { + + current_lane_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.decision.MasterVehicleDebug.current_lane_id) +} +#if LANG_CXX11 +inline void MasterVehicleDebug::set_current_lane_id(::std::string&& value) { + + current_lane_id_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.decision.MasterVehicleDebug.current_lane_id) +} +#endif +inline void MasterVehicleDebug::set_current_lane_id(const char* value) { + GOOGLE_DCHECK(value != NULL); + + current_lane_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.decision.MasterVehicleDebug.current_lane_id) +} +inline void MasterVehicleDebug::set_current_lane_id(const char* value, size_t size) { + + current_lane_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.decision.MasterVehicleDebug.current_lane_id) +} +inline ::std::string* MasterVehicleDebug::mutable_current_lane_id() { + + // @@protoc_insertion_point(field_mutable:apollo.decision.MasterVehicleDebug.current_lane_id) + return current_lane_id_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* MasterVehicleDebug::release_current_lane_id() { + // @@protoc_insertion_point(field_release:apollo.decision.MasterVehicleDebug.current_lane_id) + + return current_lane_id_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void MasterVehicleDebug::set_allocated_current_lane_id(::std::string* current_lane_id) { + if (current_lane_id != NULL) { + + } else { + + } + current_lane_id_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), current_lane_id); + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MasterVehicleDebug.current_lane_id) +} + +// double lane_s = 3; +inline void MasterVehicleDebug::clear_lane_s() { + lane_s_ = 0; +} +inline double MasterVehicleDebug::lane_s() const { + // @@protoc_insertion_point(field_get:apollo.decision.MasterVehicleDebug.lane_s) + return lane_s_; +} +inline void MasterVehicleDebug::set_lane_s(double value) { + + lane_s_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.MasterVehicleDebug.lane_s) +} + +// double lane_l = 4; +inline void MasterVehicleDebug::clear_lane_l() { + lane_l_ = 0; +} +inline double MasterVehicleDebug::lane_l() const { + // @@protoc_insertion_point(field_get:apollo.decision.MasterVehicleDebug.lane_l) + return lane_l_; +} +inline void MasterVehicleDebug::set_lane_l(double value) { + + lane_l_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.MasterVehicleDebug.lane_l) +} + +// double route_s = 5; +inline void MasterVehicleDebug::clear_route_s() { + route_s_ = 0; +} +inline double MasterVehicleDebug::route_s() const { + // @@protoc_insertion_point(field_get:apollo.decision.MasterVehicleDebug.route_s) + return route_s_; +} +inline void MasterVehicleDebug::set_route_s(double value) { + + route_s_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.MasterVehicleDebug.route_s) +} + +// double route_l = 6; +inline void MasterVehicleDebug::clear_route_l() { + route_l_ = 0; +} +inline double MasterVehicleDebug::route_l() const { + // @@protoc_insertion_point(field_get:apollo.decision.MasterVehicleDebug.route_l) + return route_l_; +} +inline void MasterVehicleDebug::set_route_l(double value) { + + route_l_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.MasterVehicleDebug.route_l) +} + +// double heading = 7; +inline void MasterVehicleDebug::clear_heading() { + heading_ = 0; +} +inline double MasterVehicleDebug::heading() const { + // @@protoc_insertion_point(field_get:apollo.decision.MasterVehicleDebug.heading) + return heading_; +} +inline void MasterVehicleDebug::set_heading(double value) { + + heading_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.MasterVehicleDebug.heading) +} + +// double heading_speed = 8; +inline void MasterVehicleDebug::clear_heading_speed() { + heading_speed_ = 0; +} +inline double MasterVehicleDebug::heading_speed() const { + // @@protoc_insertion_point(field_get:apollo.decision.MasterVehicleDebug.heading_speed) + return heading_speed_; +} +inline void MasterVehicleDebug::set_heading_speed(double value) { + + heading_speed_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.MasterVehicleDebug.heading_speed) +} + +// double heading_acceleration = 9; +inline void MasterVehicleDebug::clear_heading_acceleration() { + heading_acceleration_ = 0; +} +inline double MasterVehicleDebug::heading_acceleration() const { + // @@protoc_insertion_point(field_get:apollo.decision.MasterVehicleDebug.heading_acceleration) + return heading_acceleration_; +} +inline void MasterVehicleDebug::set_heading_acceleration(double value) { + + heading_acceleration_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.MasterVehicleDebug.heading_acceleration) +} + +// .apollo.decision.Range route_s_range = 10; +inline bool MasterVehicleDebug::has_route_s_range() const { + return this != internal_default_instance() && route_s_range_ != NULL; +} +inline void MasterVehicleDebug::clear_route_s_range() { + if (GetArenaNoVirtual() == NULL && route_s_range_ != NULL) { + delete route_s_range_; + } + route_s_range_ = NULL; +} +inline const ::apollo::decision::Range& MasterVehicleDebug::_internal_route_s_range() const { + return *route_s_range_; +} +inline const ::apollo::decision::Range& MasterVehicleDebug::route_s_range() const { + const ::apollo::decision::Range* p = route_s_range_; + // @@protoc_insertion_point(field_get:apollo.decision.MasterVehicleDebug.route_s_range) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_Range_default_instance_); +} +inline ::apollo::decision::Range* MasterVehicleDebug::release_route_s_range() { + // @@protoc_insertion_point(field_release:apollo.decision.MasterVehicleDebug.route_s_range) + + ::apollo::decision::Range* temp = route_s_range_; + route_s_range_ = NULL; + return temp; +} +inline ::apollo::decision::Range* MasterVehicleDebug::mutable_route_s_range() { + + if (route_s_range_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::Range>(GetArenaNoVirtual()); + route_s_range_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MasterVehicleDebug.route_s_range) + return route_s_range_; +} +inline void MasterVehicleDebug::set_allocated_route_s_range(::apollo::decision::Range* route_s_range) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete route_s_range_; + } + if (route_s_range) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + route_s_range = ::google::protobuf::internal::GetOwnedMessage( + message_arena, route_s_range, submessage_arena); + } + + } else { + + } + route_s_range_ = route_s_range; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MasterVehicleDebug.route_s_range) +} + +// .apollo.decision.Range route_l_range = 11; +inline bool MasterVehicleDebug::has_route_l_range() const { + return this != internal_default_instance() && route_l_range_ != NULL; +} +inline void MasterVehicleDebug::clear_route_l_range() { + if (GetArenaNoVirtual() == NULL && route_l_range_ != NULL) { + delete route_l_range_; + } + route_l_range_ = NULL; +} +inline const ::apollo::decision::Range& MasterVehicleDebug::_internal_route_l_range() const { + return *route_l_range_; +} +inline const ::apollo::decision::Range& MasterVehicleDebug::route_l_range() const { + const ::apollo::decision::Range* p = route_l_range_; + // @@protoc_insertion_point(field_get:apollo.decision.MasterVehicleDebug.route_l_range) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_Range_default_instance_); +} +inline ::apollo::decision::Range* MasterVehicleDebug::release_route_l_range() { + // @@protoc_insertion_point(field_release:apollo.decision.MasterVehicleDebug.route_l_range) + + ::apollo::decision::Range* temp = route_l_range_; + route_l_range_ = NULL; + return temp; +} +inline ::apollo::decision::Range* MasterVehicleDebug::mutable_route_l_range() { + + if (route_l_range_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::Range>(GetArenaNoVirtual()); + route_l_range_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.MasterVehicleDebug.route_l_range) + return route_l_range_; +} +inline void MasterVehicleDebug::set_allocated_route_l_range(::apollo::decision::Range* route_l_range) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete route_l_range_; + } + if (route_l_range) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + route_l_range = ::google::protobuf::internal::GetOwnedMessage( + message_arena, route_l_range, submessage_arena); + } + + } else { + + } + route_l_range_ = route_l_range; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.MasterVehicleDebug.route_l_range) +} + +// ------------------------------------------------------------------- + +// ObjectDebug + +// string id = 1; +inline void ObjectDebug::clear_id() { + id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& ObjectDebug::id() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDebug.id) + return id_.GetNoArena(); +} +inline void ObjectDebug::set_id(const ::std::string& value) { + + id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.decision.ObjectDebug.id) +} +#if LANG_CXX11 +inline void ObjectDebug::set_id(::std::string&& value) { + + id_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.decision.ObjectDebug.id) +} +#endif +inline void ObjectDebug::set_id(const char* value) { + GOOGLE_DCHECK(value != NULL); + + id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.decision.ObjectDebug.id) +} +inline void ObjectDebug::set_id(const char* value, size_t size) { + + id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.decision.ObjectDebug.id) +} +inline ::std::string* ObjectDebug::mutable_id() { + + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDebug.id) + return id_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* ObjectDebug::release_id() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDebug.id) + + return id_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void ObjectDebug::set_allocated_id(::std::string* id) { + if (id != NULL) { + + } else { + + } + id_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), id); + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDebug.id) +} + +// string path_id = 2; +inline void ObjectDebug::clear_path_id() { + path_id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& ObjectDebug::path_id() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDebug.path_id) + return path_id_.GetNoArena(); +} +inline void ObjectDebug::set_path_id(const ::std::string& value) { + + path_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.decision.ObjectDebug.path_id) +} +#if LANG_CXX11 +inline void ObjectDebug::set_path_id(::std::string&& value) { + + path_id_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.decision.ObjectDebug.path_id) +} +#endif +inline void ObjectDebug::set_path_id(const char* value) { + GOOGLE_DCHECK(value != NULL); + + path_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.decision.ObjectDebug.path_id) +} +inline void ObjectDebug::set_path_id(const char* value, size_t size) { + + path_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.decision.ObjectDebug.path_id) +} +inline ::std::string* ObjectDebug::mutable_path_id() { + + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDebug.path_id) + return path_id_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* ObjectDebug::release_path_id() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDebug.path_id) + + return path_id_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void ObjectDebug::set_allocated_path_id(::std::string* path_id) { + if (path_id != NULL) { + + } else { + + } + path_id_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), path_id); + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDebug.path_id) +} + +// .apollo.decision.Range route_s = 3; +inline bool ObjectDebug::has_route_s() const { + return this != internal_default_instance() && route_s_ != NULL; +} +inline void ObjectDebug::clear_route_s() { + if (GetArenaNoVirtual() == NULL && route_s_ != NULL) { + delete route_s_; + } + route_s_ = NULL; +} +inline const ::apollo::decision::Range& ObjectDebug::_internal_route_s() const { + return *route_s_; +} +inline const ::apollo::decision::Range& ObjectDebug::route_s() const { + const ::apollo::decision::Range* p = route_s_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDebug.route_s) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_Range_default_instance_); +} +inline ::apollo::decision::Range* ObjectDebug::release_route_s() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDebug.route_s) + + ::apollo::decision::Range* temp = route_s_; + route_s_ = NULL; + return temp; +} +inline ::apollo::decision::Range* ObjectDebug::mutable_route_s() { + + if (route_s_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::Range>(GetArenaNoVirtual()); + route_s_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDebug.route_s) + return route_s_; +} +inline void ObjectDebug::set_allocated_route_s(::apollo::decision::Range* route_s) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete route_s_; + } + if (route_s) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + route_s = ::google::protobuf::internal::GetOwnedMessage( + message_arena, route_s, submessage_arena); + } + + } else { + + } + route_s_ = route_s; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDebug.route_s) +} + +// .apollo.decision.Range route_l = 4; +inline bool ObjectDebug::has_route_l() const { + return this != internal_default_instance() && route_l_ != NULL; +} +inline void ObjectDebug::clear_route_l() { + if (GetArenaNoVirtual() == NULL && route_l_ != NULL) { + delete route_l_; + } + route_l_ = NULL; +} +inline const ::apollo::decision::Range& ObjectDebug::_internal_route_l() const { + return *route_l_; +} +inline const ::apollo::decision::Range& ObjectDebug::route_l() const { + const ::apollo::decision::Range* p = route_l_; + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDebug.route_l) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_Range_default_instance_); +} +inline ::apollo::decision::Range* ObjectDebug::release_route_l() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDebug.route_l) + + ::apollo::decision::Range* temp = route_l_; + route_l_ = NULL; + return temp; +} +inline ::apollo::decision::Range* ObjectDebug::mutable_route_l() { + + if (route_l_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::Range>(GetArenaNoVirtual()); + route_l_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDebug.route_l) + return route_l_; +} +inline void ObjectDebug::set_allocated_route_l(::apollo::decision::Range* route_l) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete route_l_; + } + if (route_l) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + route_l = ::google::protobuf::internal::GetOwnedMessage( + message_arena, route_l, submessage_arena); + } + + } else { + + } + route_l_ = route_l; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDebug.route_l) +} + +// bool on_route = 5; +inline void ObjectDebug::clear_on_route() { + on_route_ = false; +} +inline bool ObjectDebug::on_route() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDebug.on_route) + return on_route_; +} +inline void ObjectDebug::set_on_route(bool value) { + + on_route_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectDebug.on_route) +} + +// string lane_id = 6; +inline void ObjectDebug::clear_lane_id() { + lane_id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& ObjectDebug::lane_id() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDebug.lane_id) + return lane_id_.GetNoArena(); +} +inline void ObjectDebug::set_lane_id(const ::std::string& value) { + + lane_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.decision.ObjectDebug.lane_id) +} +#if LANG_CXX11 +inline void ObjectDebug::set_lane_id(::std::string&& value) { + + lane_id_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.decision.ObjectDebug.lane_id) +} +#endif +inline void ObjectDebug::set_lane_id(const char* value) { + GOOGLE_DCHECK(value != NULL); + + lane_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.decision.ObjectDebug.lane_id) +} +inline void ObjectDebug::set_lane_id(const char* value, size_t size) { + + lane_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.decision.ObjectDebug.lane_id) +} +inline ::std::string* ObjectDebug::mutable_lane_id() { + + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDebug.lane_id) + return lane_id_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* ObjectDebug::release_lane_id() { + // @@protoc_insertion_point(field_release:apollo.decision.ObjectDebug.lane_id) + + return lane_id_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void ObjectDebug::set_allocated_lane_id(::std::string* lane_id) { + if (lane_id != NULL) { + + } else { + + } + lane_id_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), lane_id); + // @@protoc_insertion_point(field_set_allocated:apollo.decision.ObjectDebug.lane_id) +} + +// double lane_s = 7; +inline void ObjectDebug::clear_lane_s() { + lane_s_ = 0; +} +inline double ObjectDebug::lane_s() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDebug.lane_s) + return lane_s_; +} +inline void ObjectDebug::set_lane_s(double value) { + + lane_s_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectDebug.lane_s) +} + +// bool on_lane = 8; +inline void ObjectDebug::clear_on_lane() { + on_lane_ = false; +} +inline bool ObjectDebug::on_lane() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDebug.on_lane) + return on_lane_; +} +inline void ObjectDebug::set_on_lane(bool value) { + + on_lane_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectDebug.on_lane) +} + +// double path_speed = 9; +inline void ObjectDebug::clear_path_speed() { + path_speed_ = 0; +} +inline double ObjectDebug::path_speed() const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDebug.path_speed) + return path_speed_; +} +inline void ObjectDebug::set_path_speed(double value) { + + path_speed_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ObjectDebug.path_speed) +} + +// repeated .apollo.common.Point3D st_region = 10; +inline int ObjectDebug::st_region_size() const { + return st_region_.size(); +} +inline ::apollo::common::Point3D* ObjectDebug::mutable_st_region(int index) { + // @@protoc_insertion_point(field_mutable:apollo.decision.ObjectDebug.st_region) + return st_region_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::common::Point3D >* +ObjectDebug::mutable_st_region() { + // @@protoc_insertion_point(field_mutable_list:apollo.decision.ObjectDebug.st_region) + return &st_region_; +} +inline const ::apollo::common::Point3D& ObjectDebug::st_region(int index) const { + // @@protoc_insertion_point(field_get:apollo.decision.ObjectDebug.st_region) + return st_region_.Get(index); +} +inline ::apollo::common::Point3D* ObjectDebug::add_st_region() { + // @@protoc_insertion_point(field_add:apollo.decision.ObjectDebug.st_region) + return st_region_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::common::Point3D >& +ObjectDebug::st_region() const { + // @@protoc_insertion_point(field_list:apollo.decision.ObjectDebug.st_region) + return st_region_; +} + +// ------------------------------------------------------------------- + +// LatencyStats + +// double total_time_ms = 1; +inline void LatencyStats::clear_total_time_ms() { + total_time_ms_ = 0; +} +inline double LatencyStats::total_time_ms() const { + // @@protoc_insertion_point(field_get:apollo.decision.LatencyStats.total_time_ms) + return total_time_ms_; +} +inline void LatencyStats::set_total_time_ms(double value) { + + total_time_ms_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LatencyStats.total_time_ms) +} + +// double sensor_read_time_ms = 2; +inline void LatencyStats::clear_sensor_read_time_ms() { + sensor_read_time_ms_ = 0; +} +inline double LatencyStats::sensor_read_time_ms() const { + // @@protoc_insertion_point(field_get:apollo.decision.LatencyStats.sensor_read_time_ms) + return sensor_read_time_ms_; +} +inline void LatencyStats::set_sensor_read_time_ms(double value) { + + sensor_read_time_ms_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LatencyStats.sensor_read_time_ms) +} + +// double adc_prepare_time_ms = 3; +inline void LatencyStats::clear_adc_prepare_time_ms() { + adc_prepare_time_ms_ = 0; +} +inline double LatencyStats::adc_prepare_time_ms() const { + // @@protoc_insertion_point(field_get:apollo.decision.LatencyStats.adc_prepare_time_ms) + return adc_prepare_time_ms_; +} +inline void LatencyStats::set_adc_prepare_time_ms(double value) { + + adc_prepare_time_ms_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LatencyStats.adc_prepare_time_ms) +} + +// double obj_prepare_time_ms = 4; +inline void LatencyStats::clear_obj_prepare_time_ms() { + obj_prepare_time_ms_ = 0; +} +inline double LatencyStats::obj_prepare_time_ms() const { + // @@protoc_insertion_point(field_get:apollo.decision.LatencyStats.obj_prepare_time_ms) + return obj_prepare_time_ms_; +} +inline void LatencyStats::set_obj_prepare_time_ms(double value) { + + obj_prepare_time_ms_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LatencyStats.obj_prepare_time_ms) +} + +// double world_rule_time_ms = 5; +inline void LatencyStats::clear_world_rule_time_ms() { + world_rule_time_ms_ = 0; +} +inline double LatencyStats::world_rule_time_ms() const { + // @@protoc_insertion_point(field_get:apollo.decision.LatencyStats.world_rule_time_ms) + return world_rule_time_ms_; +} +inline void LatencyStats::set_world_rule_time_ms(double value) { + + world_rule_time_ms_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LatencyStats.world_rule_time_ms) +} + +// double st_graph_time_ms = 6; +inline void LatencyStats::clear_st_graph_time_ms() { + st_graph_time_ms_ = 0; +} +inline double LatencyStats::st_graph_time_ms() const { + // @@protoc_insertion_point(field_get:apollo.decision.LatencyStats.st_graph_time_ms) + return st_graph_time_ms_; +} +inline void LatencyStats::set_st_graph_time_ms(double value) { + + st_graph_time_ms_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LatencyStats.st_graph_time_ms) +} + +// double gateway_receive_delay_ms = 8; +inline void LatencyStats::clear_gateway_receive_delay_ms() { + gateway_receive_delay_ms_ = 0; +} +inline double LatencyStats::gateway_receive_delay_ms() const { + // @@protoc_insertion_point(field_get:apollo.decision.LatencyStats.gateway_receive_delay_ms) + return gateway_receive_delay_ms_; +} +inline void LatencyStats::set_gateway_receive_delay_ms(double value) { + + gateway_receive_delay_ms_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LatencyStats.gateway_receive_delay_ms) +} + +// double perception_receive_delay_ms = 9; +inline void LatencyStats::clear_perception_receive_delay_ms() { + perception_receive_delay_ms_ = 0; +} +inline double LatencyStats::perception_receive_delay_ms() const { + // @@protoc_insertion_point(field_get:apollo.decision.LatencyStats.perception_receive_delay_ms) + return perception_receive_delay_ms_; +} +inline void LatencyStats::set_perception_receive_delay_ms(double value) { + + perception_receive_delay_ms_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LatencyStats.perception_receive_delay_ms) +} + +// double prediction_receive_delay_ms = 10; +inline void LatencyStats::clear_prediction_receive_delay_ms() { + prediction_receive_delay_ms_ = 0; +} +inline double LatencyStats::prediction_receive_delay_ms() const { + // @@protoc_insertion_point(field_get:apollo.decision.LatencyStats.prediction_receive_delay_ms) + return prediction_receive_delay_ms_; +} +inline void LatencyStats::set_prediction_receive_delay_ms(double value) { + + prediction_receive_delay_ms_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LatencyStats.prediction_receive_delay_ms) +} + +// double signal_receive_delay_ms = 11; +inline void LatencyStats::clear_signal_receive_delay_ms() { + signal_receive_delay_ms_ = 0; +} +inline double LatencyStats::signal_receive_delay_ms() const { + // @@protoc_insertion_point(field_get:apollo.decision.LatencyStats.signal_receive_delay_ms) + return signal_receive_delay_ms_; +} +inline void LatencyStats::set_signal_receive_delay_ms(double value) { + + signal_receive_delay_ms_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LatencyStats.signal_receive_delay_ms) +} + +// double perception_interval_ms = 12; +inline void LatencyStats::clear_perception_interval_ms() { + perception_interval_ms_ = 0; +} +inline double LatencyStats::perception_interval_ms() const { + // @@protoc_insertion_point(field_get:apollo.decision.LatencyStats.perception_interval_ms) + return perception_interval_ms_; +} +inline void LatencyStats::set_perception_interval_ms(double value) { + + perception_interval_ms_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LatencyStats.perception_interval_ms) +} + +// double prediction_interval_ms = 13; +inline void LatencyStats::clear_prediction_interval_ms() { + prediction_interval_ms_ = 0; +} +inline double LatencyStats::prediction_interval_ms() const { + // @@protoc_insertion_point(field_get:apollo.decision.LatencyStats.prediction_interval_ms) + return prediction_interval_ms_; +} +inline void LatencyStats::set_prediction_interval_ms(double value) { + + prediction_interval_ms_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LatencyStats.prediction_interval_ms) +} + +// ------------------------------------------------------------------- + +// Stats + +// .apollo.decision.LatencyStats latency_stats = 1; +inline bool Stats::has_latency_stats() const { + return this != internal_default_instance() && latency_stats_ != NULL; +} +inline void Stats::clear_latency_stats() { + if (GetArenaNoVirtual() == NULL && latency_stats_ != NULL) { + delete latency_stats_; + } + latency_stats_ = NULL; +} +inline const ::apollo::decision::LatencyStats& Stats::_internal_latency_stats() const { + return *latency_stats_; +} +inline const ::apollo::decision::LatencyStats& Stats::latency_stats() const { + const ::apollo::decision::LatencyStats* p = latency_stats_; + // @@protoc_insertion_point(field_get:apollo.decision.Stats.latency_stats) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_LatencyStats_default_instance_); +} +inline ::apollo::decision::LatencyStats* Stats::release_latency_stats() { + // @@protoc_insertion_point(field_release:apollo.decision.Stats.latency_stats) + + ::apollo::decision::LatencyStats* temp = latency_stats_; + latency_stats_ = NULL; + return temp; +} +inline ::apollo::decision::LatencyStats* Stats::mutable_latency_stats() { + + if (latency_stats_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::LatencyStats>(GetArenaNoVirtual()); + latency_stats_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.Stats.latency_stats) + return latency_stats_; +} +inline void Stats::set_allocated_latency_stats(::apollo::decision::LatencyStats* latency_stats) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete latency_stats_; + } + if (latency_stats) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + latency_stats = ::google::protobuf::internal::GetOwnedMessage( + message_arena, latency_stats, submessage_arena); + } + + } else { + + } + latency_stats_ = latency_stats; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.Stats.latency_stats) +} + +// ------------------------------------------------------------------- + +// ModuleDebug + +// uint32 gateway_sequence_num = 1; +inline void ModuleDebug::clear_gateway_sequence_num() { + gateway_sequence_num_ = 0u; +} +inline ::google::protobuf::uint32 ModuleDebug::gateway_sequence_num() const { + // @@protoc_insertion_point(field_get:apollo.decision.ModuleDebug.gateway_sequence_num) + return gateway_sequence_num_; +} +inline void ModuleDebug::set_gateway_sequence_num(::google::protobuf::uint32 value) { + + gateway_sequence_num_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ModuleDebug.gateway_sequence_num) +} + +// uint32 perception_sequence_num = 2; +inline void ModuleDebug::clear_perception_sequence_num() { + perception_sequence_num_ = 0u; +} +inline ::google::protobuf::uint32 ModuleDebug::perception_sequence_num() const { + // @@protoc_insertion_point(field_get:apollo.decision.ModuleDebug.perception_sequence_num) + return perception_sequence_num_; +} +inline void ModuleDebug::set_perception_sequence_num(::google::protobuf::uint32 value) { + + perception_sequence_num_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ModuleDebug.perception_sequence_num) +} + +// uint32 prediction_sequence_num = 3; +inline void ModuleDebug::clear_prediction_sequence_num() { + prediction_sequence_num_ = 0u; +} +inline ::google::protobuf::uint32 ModuleDebug::prediction_sequence_num() const { + // @@protoc_insertion_point(field_get:apollo.decision.ModuleDebug.prediction_sequence_num) + return prediction_sequence_num_; +} +inline void ModuleDebug::set_prediction_sequence_num(::google::protobuf::uint32 value) { + + prediction_sequence_num_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ModuleDebug.prediction_sequence_num) +} + +// uint32 signal_sequence_num = 4; +inline void ModuleDebug::clear_signal_sequence_num() { + signal_sequence_num_ = 0u; +} +inline ::google::protobuf::uint32 ModuleDebug::signal_sequence_num() const { + // @@protoc_insertion_point(field_get:apollo.decision.ModuleDebug.signal_sequence_num) + return signal_sequence_num_; +} +inline void ModuleDebug::set_signal_sequence_num(::google::protobuf::uint32 value) { + + signal_sequence_num_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.ModuleDebug.signal_sequence_num) +} + +// ------------------------------------------------------------------- + +// Debug + +// .apollo.decision.MasterVehicleDebug master_vehicle = 1; +inline bool Debug::has_master_vehicle() const { + return this != internal_default_instance() && master_vehicle_ != NULL; +} +inline void Debug::clear_master_vehicle() { + if (GetArenaNoVirtual() == NULL && master_vehicle_ != NULL) { + delete master_vehicle_; + } + master_vehicle_ = NULL; +} +inline const ::apollo::decision::MasterVehicleDebug& Debug::_internal_master_vehicle() const { + return *master_vehicle_; +} +inline const ::apollo::decision::MasterVehicleDebug& Debug::master_vehicle() const { + const ::apollo::decision::MasterVehicleDebug* p = master_vehicle_; + // @@protoc_insertion_point(field_get:apollo.decision.Debug.master_vehicle) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_MasterVehicleDebug_default_instance_); +} +inline ::apollo::decision::MasterVehicleDebug* Debug::release_master_vehicle() { + // @@protoc_insertion_point(field_release:apollo.decision.Debug.master_vehicle) + + ::apollo::decision::MasterVehicleDebug* temp = master_vehicle_; + master_vehicle_ = NULL; + return temp; +} +inline ::apollo::decision::MasterVehicleDebug* Debug::mutable_master_vehicle() { + + if (master_vehicle_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::MasterVehicleDebug>(GetArenaNoVirtual()); + master_vehicle_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.Debug.master_vehicle) + return master_vehicle_; +} +inline void Debug::set_allocated_master_vehicle(::apollo::decision::MasterVehicleDebug* master_vehicle) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete master_vehicle_; + } + if (master_vehicle) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + master_vehicle = ::google::protobuf::internal::GetOwnedMessage( + message_arena, master_vehicle, submessage_arena); + } + + } else { + + } + master_vehicle_ = master_vehicle; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.Debug.master_vehicle) +} + +// .apollo.decision.MainDecision original_decision = 2; +inline bool Debug::has_original_decision() const { + return this != internal_default_instance() && original_decision_ != NULL; +} +inline void Debug::clear_original_decision() { + if (GetArenaNoVirtual() == NULL && original_decision_ != NULL) { + delete original_decision_; + } + original_decision_ = NULL; +} +inline const ::apollo::decision::MainDecision& Debug::_internal_original_decision() const { + return *original_decision_; +} +inline const ::apollo::decision::MainDecision& Debug::original_decision() const { + const ::apollo::decision::MainDecision* p = original_decision_; + // @@protoc_insertion_point(field_get:apollo.decision.Debug.original_decision) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_MainDecision_default_instance_); +} +inline ::apollo::decision::MainDecision* Debug::release_original_decision() { + // @@protoc_insertion_point(field_release:apollo.decision.Debug.original_decision) + + ::apollo::decision::MainDecision* temp = original_decision_; + original_decision_ = NULL; + return temp; +} +inline ::apollo::decision::MainDecision* Debug::mutable_original_decision() { + + if (original_decision_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::MainDecision>(GetArenaNoVirtual()); + original_decision_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.Debug.original_decision) + return original_decision_; +} +inline void Debug::set_allocated_original_decision(::apollo::decision::MainDecision* original_decision) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete original_decision_; + } + if (original_decision) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + original_decision = ::google::protobuf::internal::GetOwnedMessage( + message_arena, original_decision, submessage_arena); + } + + } else { + + } + original_decision_ = original_decision; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.Debug.original_decision) +} + +// repeated .apollo.decision.ObjectDebug object = 3; +inline int Debug::object_size() const { + return object_.size(); +} +inline void Debug::clear_object() { + object_.Clear(); +} +inline ::apollo::decision::ObjectDebug* Debug::mutable_object(int index) { + // @@protoc_insertion_point(field_mutable:apollo.decision.Debug.object) + return object_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDebug >* +Debug::mutable_object() { + // @@protoc_insertion_point(field_mutable_list:apollo.decision.Debug.object) + return &object_; +} +inline const ::apollo::decision::ObjectDebug& Debug::object(int index) const { + // @@protoc_insertion_point(field_get:apollo.decision.Debug.object) + return object_.Get(index); +} +inline ::apollo::decision::ObjectDebug* Debug::add_object() { + // @@protoc_insertion_point(field_add:apollo.decision.Debug.object) + return object_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDebug >& +Debug::object() const { + // @@protoc_insertion_point(field_list:apollo.decision.Debug.object) + return object_; +} + +// bytes map_version = 5; +inline void Debug::clear_map_version() { + map_version_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& Debug::map_version() const { + // @@protoc_insertion_point(field_get:apollo.decision.Debug.map_version) + return map_version_.GetNoArena(); +} +inline void Debug::set_map_version(const ::std::string& value) { + + map_version_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.decision.Debug.map_version) +} +#if LANG_CXX11 +inline void Debug::set_map_version(::std::string&& value) { + + map_version_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.decision.Debug.map_version) +} +#endif +inline void Debug::set_map_version(const char* value) { + GOOGLE_DCHECK(value != NULL); + + map_version_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.decision.Debug.map_version) +} +inline void Debug::set_map_version(const void* value, size_t size) { + + map_version_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.decision.Debug.map_version) +} +inline ::std::string* Debug::mutable_map_version() { + + // @@protoc_insertion_point(field_mutable:apollo.decision.Debug.map_version) + return map_version_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* Debug::release_map_version() { + // @@protoc_insertion_point(field_release:apollo.decision.Debug.map_version) + + return map_version_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void Debug::set_allocated_map_version(::std::string* map_version) { + if (map_version != NULL) { + + } else { + + } + map_version_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), map_version); + // @@protoc_insertion_point(field_set_allocated:apollo.decision.Debug.map_version) +} + +// bytes decision_version = 7; +inline void Debug::clear_decision_version() { + decision_version_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& Debug::decision_version() const { + // @@protoc_insertion_point(field_get:apollo.decision.Debug.decision_version) + return decision_version_.GetNoArena(); +} +inline void Debug::set_decision_version(const ::std::string& value) { + + decision_version_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.decision.Debug.decision_version) +} +#if LANG_CXX11 +inline void Debug::set_decision_version(::std::string&& value) { + + decision_version_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.decision.Debug.decision_version) +} +#endif +inline void Debug::set_decision_version(const char* value) { + GOOGLE_DCHECK(value != NULL); + + decision_version_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.decision.Debug.decision_version) +} +inline void Debug::set_decision_version(const void* value, size_t size) { + + decision_version_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.decision.Debug.decision_version) +} +inline ::std::string* Debug::mutable_decision_version() { + + // @@protoc_insertion_point(field_mutable:apollo.decision.Debug.decision_version) + return decision_version_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* Debug::release_decision_version() { + // @@protoc_insertion_point(field_release:apollo.decision.Debug.decision_version) + + return decision_version_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void Debug::set_allocated_decision_version(::std::string* decision_version) { + if (decision_version != NULL) { + + } else { + + } + decision_version_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), decision_version); + // @@protoc_insertion_point(field_set_allocated:apollo.decision.Debug.decision_version) +} + +// .apollo.decision.ModuleDebug module_debug = 6; +inline bool Debug::has_module_debug() const { + return this != internal_default_instance() && module_debug_ != NULL; +} +inline void Debug::clear_module_debug() { + if (GetArenaNoVirtual() == NULL && module_debug_ != NULL) { + delete module_debug_; + } + module_debug_ = NULL; +} +inline const ::apollo::decision::ModuleDebug& Debug::_internal_module_debug() const { + return *module_debug_; +} +inline const ::apollo::decision::ModuleDebug& Debug::module_debug() const { + const ::apollo::decision::ModuleDebug* p = module_debug_; + // @@protoc_insertion_point(field_get:apollo.decision.Debug.module_debug) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_ModuleDebug_default_instance_); +} +inline ::apollo::decision::ModuleDebug* Debug::release_module_debug() { + // @@protoc_insertion_point(field_release:apollo.decision.Debug.module_debug) + + ::apollo::decision::ModuleDebug* temp = module_debug_; + module_debug_ = NULL; + return temp; +} +inline ::apollo::decision::ModuleDebug* Debug::mutable_module_debug() { + + if (module_debug_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::ModuleDebug>(GetArenaNoVirtual()); + module_debug_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.Debug.module_debug) + return module_debug_; +} +inline void Debug::set_allocated_module_debug(::apollo::decision::ModuleDebug* module_debug) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete module_debug_; + } + if (module_debug) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + module_debug = ::google::protobuf::internal::GetOwnedMessage( + message_arena, module_debug, submessage_arena); + } + + } else { + + } + module_debug_ = module_debug; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.Debug.module_debug) +} + +// ------------------------------------------------------------------- + +// LightSignal + +// bool emergency = 1; +inline void LightSignal::clear_emergency() { + emergency_ = false; +} +inline bool LightSignal::emergency() const { + // @@protoc_insertion_point(field_get:apollo.decision.LightSignal.emergency) + return emergency_; +} +inline void LightSignal::set_emergency(bool value) { + + emergency_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LightSignal.emergency) +} + +// .apollo.decision.LightSignal.TurnSignal turn_signal = 2; +inline void LightSignal::clear_turn_signal() { + turn_signal_ = 0; +} +inline ::apollo::decision::LightSignal_TurnSignal LightSignal::turn_signal() const { + // @@protoc_insertion_point(field_get:apollo.decision.LightSignal.turn_signal) + return static_cast< ::apollo::decision::LightSignal_TurnSignal >(turn_signal_); +} +inline void LightSignal::set_turn_signal(::apollo::decision::LightSignal_TurnSignal value) { + + turn_signal_ = value; + // @@protoc_insertion_point(field_set:apollo.decision.LightSignal.turn_signal) +} + +// ------------------------------------------------------------------- + +// DecisionResult + +// .apollo.common.Header header = 1; +inline bool DecisionResult::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& DecisionResult::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& DecisionResult::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.decision.DecisionResult.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* DecisionResult::release_header() { + // @@protoc_insertion_point(field_release:apollo.decision.DecisionResult.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* DecisionResult::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.DecisionResult.header) + return header_; +} +inline void DecisionResult::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.DecisionResult.header) +} + +// .apollo.decision.ObjectDecisions object_decision = 2; +inline bool DecisionResult::has_object_decision() const { + return this != internal_default_instance() && object_decision_ != NULL; +} +inline void DecisionResult::clear_object_decision() { + if (GetArenaNoVirtual() == NULL && object_decision_ != NULL) { + delete object_decision_; + } + object_decision_ = NULL; +} +inline const ::apollo::decision::ObjectDecisions& DecisionResult::_internal_object_decision() const { + return *object_decision_; +} +inline const ::apollo::decision::ObjectDecisions& DecisionResult::object_decision() const { + const ::apollo::decision::ObjectDecisions* p = object_decision_; + // @@protoc_insertion_point(field_get:apollo.decision.DecisionResult.object_decision) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_ObjectDecisions_default_instance_); +} +inline ::apollo::decision::ObjectDecisions* DecisionResult::release_object_decision() { + // @@protoc_insertion_point(field_release:apollo.decision.DecisionResult.object_decision) + + ::apollo::decision::ObjectDecisions* temp = object_decision_; + object_decision_ = NULL; + return temp; +} +inline ::apollo::decision::ObjectDecisions* DecisionResult::mutable_object_decision() { + + if (object_decision_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::ObjectDecisions>(GetArenaNoVirtual()); + object_decision_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.DecisionResult.object_decision) + return object_decision_; +} +inline void DecisionResult::set_allocated_object_decision(::apollo::decision::ObjectDecisions* object_decision) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete object_decision_; + } + if (object_decision) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + object_decision = ::google::protobuf::internal::GetOwnedMessage( + message_arena, object_decision, submessage_arena); + } + + } else { + + } + object_decision_ = object_decision; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.DecisionResult.object_decision) +} + +// .apollo.decision.MainDecision main_decision = 3; +inline bool DecisionResult::has_main_decision() const { + return this != internal_default_instance() && main_decision_ != NULL; +} +inline void DecisionResult::clear_main_decision() { + if (GetArenaNoVirtual() == NULL && main_decision_ != NULL) { + delete main_decision_; + } + main_decision_ = NULL; +} +inline const ::apollo::decision::MainDecision& DecisionResult::_internal_main_decision() const { + return *main_decision_; +} +inline const ::apollo::decision::MainDecision& DecisionResult::main_decision() const { + const ::apollo::decision::MainDecision* p = main_decision_; + // @@protoc_insertion_point(field_get:apollo.decision.DecisionResult.main_decision) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_MainDecision_default_instance_); +} +inline ::apollo::decision::MainDecision* DecisionResult::release_main_decision() { + // @@protoc_insertion_point(field_release:apollo.decision.DecisionResult.main_decision) + + ::apollo::decision::MainDecision* temp = main_decision_; + main_decision_ = NULL; + return temp; +} +inline ::apollo::decision::MainDecision* DecisionResult::mutable_main_decision() { + + if (main_decision_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::MainDecision>(GetArenaNoVirtual()); + main_decision_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.DecisionResult.main_decision) + return main_decision_; +} +inline void DecisionResult::set_allocated_main_decision(::apollo::decision::MainDecision* main_decision) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete main_decision_; + } + if (main_decision) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + main_decision = ::google::protobuf::internal::GetOwnedMessage( + message_arena, main_decision, submessage_arena); + } + + } else { + + } + main_decision_ = main_decision; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.DecisionResult.main_decision) +} + +// .apollo.decision.Debug debug = 4; +inline bool DecisionResult::has_debug() const { + return this != internal_default_instance() && debug_ != NULL; +} +inline void DecisionResult::clear_debug() { + if (GetArenaNoVirtual() == NULL && debug_ != NULL) { + delete debug_; + } + debug_ = NULL; +} +inline const ::apollo::decision::Debug& DecisionResult::_internal_debug() const { + return *debug_; +} +inline const ::apollo::decision::Debug& DecisionResult::debug() const { + const ::apollo::decision::Debug* p = debug_; + // @@protoc_insertion_point(field_get:apollo.decision.DecisionResult.debug) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_Debug_default_instance_); +} +inline ::apollo::decision::Debug* DecisionResult::release_debug() { + // @@protoc_insertion_point(field_release:apollo.decision.DecisionResult.debug) + + ::apollo::decision::Debug* temp = debug_; + debug_ = NULL; + return temp; +} +inline ::apollo::decision::Debug* DecisionResult::mutable_debug() { + + if (debug_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::Debug>(GetArenaNoVirtual()); + debug_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.DecisionResult.debug) + return debug_; +} +inline void DecisionResult::set_allocated_debug(::apollo::decision::Debug* debug) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete debug_; + } + if (debug) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + debug = ::google::protobuf::internal::GetOwnedMessage( + message_arena, debug, submessage_arena); + } + + } else { + + } + debug_ = debug; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.DecisionResult.debug) +} + +// .apollo.decision.Stats stats = 6; +inline bool DecisionResult::has_stats() const { + return this != internal_default_instance() && stats_ != NULL; +} +inline void DecisionResult::clear_stats() { + if (GetArenaNoVirtual() == NULL && stats_ != NULL) { + delete stats_; + } + stats_ = NULL; +} +inline const ::apollo::decision::Stats& DecisionResult::_internal_stats() const { + return *stats_; +} +inline const ::apollo::decision::Stats& DecisionResult::stats() const { + const ::apollo::decision::Stats* p = stats_; + // @@protoc_insertion_point(field_get:apollo.decision.DecisionResult.stats) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_Stats_default_instance_); +} +inline ::apollo::decision::Stats* DecisionResult::release_stats() { + // @@protoc_insertion_point(field_release:apollo.decision.DecisionResult.stats) + + ::apollo::decision::Stats* temp = stats_; + stats_ = NULL; + return temp; +} +inline ::apollo::decision::Stats* DecisionResult::mutable_stats() { + + if (stats_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::Stats>(GetArenaNoVirtual()); + stats_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.DecisionResult.stats) + return stats_; +} +inline void DecisionResult::set_allocated_stats(::apollo::decision::Stats* stats) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete stats_; + } + if (stats) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + stats = ::google::protobuf::internal::GetOwnedMessage( + message_arena, stats, submessage_arena); + } + + } else { + + } + stats_ = stats; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.DecisionResult.stats) +} + +// .apollo.canbus.Signal signal = 7; +inline bool DecisionResult::has_signal() const { + return this != internal_default_instance() && signal_ != NULL; +} +inline const ::apollo::canbus::Signal& DecisionResult::_internal_signal() const { + return *signal_; +} +inline const ::apollo::canbus::Signal& DecisionResult::signal() const { + const ::apollo::canbus::Signal* p = signal_; + // @@protoc_insertion_point(field_get:apollo.decision.DecisionResult.signal) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Signal_default_instance_); +} +inline ::apollo::canbus::Signal* DecisionResult::release_signal() { + // @@protoc_insertion_point(field_release:apollo.decision.DecisionResult.signal) + + ::apollo::canbus::Signal* temp = signal_; + signal_ = NULL; + return temp; +} +inline ::apollo::canbus::Signal* DecisionResult::mutable_signal() { + + if (signal_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Signal>(GetArenaNoVirtual()); + signal_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.DecisionResult.signal) + return signal_; +} +inline void DecisionResult::set_allocated_signal(::apollo::canbus::Signal* signal) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(signal_); + } + if (signal) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + signal = ::google::protobuf::internal::GetOwnedMessage( + message_arena, signal, submessage_arena); + } + + } else { + + } + signal_ = signal; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.DecisionResult.signal) +} + +// .apollo.decision.LightSignal light_signal = 5; +inline bool DecisionResult::has_light_signal() const { + return this != internal_default_instance() && light_signal_ != NULL; +} +inline void DecisionResult::clear_light_signal() { + if (GetArenaNoVirtual() == NULL && light_signal_ != NULL) { + delete light_signal_; + } + light_signal_ = NULL; +} +inline const ::apollo::decision::LightSignal& DecisionResult::_internal_light_signal() const { + return *light_signal_; +} +inline const ::apollo::decision::LightSignal& DecisionResult::light_signal() const { + const ::apollo::decision::LightSignal* p = light_signal_; + // @@protoc_insertion_point(field_get:apollo.decision.DecisionResult.light_signal) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_LightSignal_default_instance_); +} +inline ::apollo::decision::LightSignal* DecisionResult::release_light_signal() { + // @@protoc_insertion_point(field_release:apollo.decision.DecisionResult.light_signal) + + ::apollo::decision::LightSignal* temp = light_signal_; + light_signal_ = NULL; + return temp; +} +inline ::apollo::decision::LightSignal* DecisionResult::mutable_light_signal() { + + if (light_signal_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::LightSignal>(GetArenaNoVirtual()); + light_signal_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.decision.DecisionResult.light_signal) + return light_signal_; +} +inline void DecisionResult::set_allocated_light_signal(::apollo::decision::LightSignal* light_signal) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete light_signal_; + } + if (light_signal) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + light_signal = ::google::protobuf::internal::GetOwnedMessage( + message_arena, light_signal, submessage_arena); + } + + } else { + + } + light_signal_ = light_signal; + // @@protoc_insertion_point(field_set_allocated:apollo.decision.DecisionResult.light_signal) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace decision +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::decision::ObjectNudge_Type> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::decision::ObjectNudge_Type>() { + return ::apollo::decision::ObjectNudge_Type_descriptor(); +} +template <> struct is_proto_enum< ::apollo::decision::ObjectSidePass_Type> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::decision::ObjectSidePass_Type>() { + return ::apollo::decision::ObjectSidePass_Type_descriptor(); +} +template <> struct is_proto_enum< ::apollo::decision::ObjectDecision_ObjectType> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::decision::ObjectDecision_ObjectType>() { + return ::apollo::decision::ObjectDecision_ObjectType_descriptor(); +} +template <> struct is_proto_enum< ::apollo::decision::MainEmergencyStop_ReasonCode> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::decision::MainEmergencyStop_ReasonCode>() { + return ::apollo::decision::MainEmergencyStop_ReasonCode_descriptor(); +} +template <> struct is_proto_enum< ::apollo::decision::MainChangeLane_Type> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::decision::MainChangeLane_Type>() { + return ::apollo::decision::MainChangeLane_Type_descriptor(); +} +template <> struct is_proto_enum< ::apollo::decision::MainParking_Type> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::decision::MainParking_Type>() { + return ::apollo::decision::MainParking_Type_descriptor(); +} +template <> struct is_proto_enum< ::apollo::decision::LightSignal_TurnSignal> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::decision::LightSignal_TurnSignal>() { + return ::apollo::decision::LightSignal_TurnSignal_descriptor(); +} +template <> struct is_proto_enum< ::apollo::decision::StopReasonCode> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::decision::StopReasonCode>() { + return ::apollo::decision::StopReasonCode_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/camera.pb.cc b/apollo_msgs/include/apollo_msgs/proto/localization/camera.pb.cc new file mode 100644 index 0000000..ba25fed --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/camera.pb.cc @@ -0,0 +1,501 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/camera.proto + +#include "apollo_msgs/proto/localization/camera.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace apollo { +namespace localization { +class CameraDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Camera_default_instance_; +} // namespace localization +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto { +static void InitDefaultsCamera() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::localization::_Camera_default_instance_; + new (ptr) ::apollo::localization::Camera(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::localization::Camera::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_Camera = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsCamera}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_Camera.base); +} + +::google::protobuf::Metadata file_level_metadata[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Camera, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Camera, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Camera, image_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Camera, width_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Camera, height_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::localization::Camera)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::localization::_Camera_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/localization/camera.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 1); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n+apollo_msgs/proto/localization/camera." + "proto\022\023apollo.localization\032%apollo_msgs/" + "proto/common/header.proto\"]\n\006Camera\022%\n\006h" + "eader\030\001 \001(\0132\025.apollo.common.Header\022\r\n\005im" + "age\030\002 \001(\014\022\r\n\005width\030\003 \001(\r\022\016\n\006height\030\004 \001(\r" + "b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 208); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/localization/camera.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto +namespace apollo { +namespace localization { + +// =================================================================== + +void Camera::InitAsDefaultInstance() { + ::apollo::localization::_Camera_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); +} +void Camera::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Camera::kHeaderFieldNumber; +const int Camera::kImageFieldNumber; +const int Camera::kWidthFieldNumber; +const int Camera::kHeightFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Camera::Camera() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto::scc_info_Camera.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.localization.Camera) +} +Camera::Camera(const Camera& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + image_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.image().size() > 0) { + image_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.image_); + } + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + ::memcpy(&width_, &from.width_, + static_cast(reinterpret_cast(&height_) - + reinterpret_cast(&width_)) + sizeof(height_)); + // @@protoc_insertion_point(copy_constructor:apollo.localization.Camera) +} + +void Camera::SharedCtor() { + image_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&header_, 0, static_cast( + reinterpret_cast(&height_) - + reinterpret_cast(&header_)) + sizeof(height_)); +} + +Camera::~Camera() { + // @@protoc_insertion_point(destructor:apollo.localization.Camera) + SharedDtor(); +} + +void Camera::SharedDtor() { + image_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (this != internal_default_instance()) delete header_; +} + +void Camera::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Camera::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Camera& Camera::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto::scc_info_Camera.base); + return *internal_default_instance(); +} + + +void Camera::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.localization.Camera) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + image_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + ::memset(&width_, 0, static_cast( + reinterpret_cast(&height_) - + reinterpret_cast(&width_)) + sizeof(height_)); + _internal_metadata_.Clear(); +} + +bool Camera::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.localization.Camera) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // bytes image = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( + input, this->mutable_image())); + } else { + goto handle_unusual; + } + break; + } + + // uint32 width = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &width_))); + } else { + goto handle_unusual; + } + break; + } + + // uint32 height = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(32u /* 32 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &height_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.localization.Camera) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.localization.Camera) + return false; +#undef DO_ +} + +void Camera::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.localization.Camera) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // bytes image = 2; + if (this->image().size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteBytesMaybeAliased( + 2, this->image(), output); + } + + // uint32 width = 3; + if (this->width() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(3, this->width(), output); + } + + // uint32 height = 4; + if (this->height() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(4, this->height(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.localization.Camera) +} + +::google::protobuf::uint8* Camera::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.localization.Camera) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // bytes image = 2; + if (this->image().size() > 0) { + target = + ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( + 2, this->image(), target); + } + + // uint32 width = 3; + if (this->width() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(3, this->width(), target); + } + + // uint32 height = 4; + if (this->height() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(4, this->height(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.localization.Camera) + return target; +} + +size_t Camera::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.localization.Camera) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // bytes image = 2; + if (this->image().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::BytesSize( + this->image()); + } + + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // uint32 width = 3; + if (this->width() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->width()); + } + + // uint32 height = 4; + if (this->height() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->height()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Camera::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.localization.Camera) + GOOGLE_DCHECK_NE(&from, this); + const Camera* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.localization.Camera) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.localization.Camera) + MergeFrom(*source); + } +} + +void Camera::MergeFrom(const Camera& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.localization.Camera) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.image().size() > 0) { + + image_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.image_); + } + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.width() != 0) { + set_width(from.width()); + } + if (from.height() != 0) { + set_height(from.height()); + } +} + +void Camera::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.localization.Camera) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Camera::CopyFrom(const Camera& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.localization.Camera) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Camera::IsInitialized() const { + return true; +} + +void Camera::Swap(Camera* other) { + if (other == this) return; + InternalSwap(other); +} +void Camera::InternalSwap(Camera* other) { + using std::swap; + image_.Swap(&other->image_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(header_, other->header_); + swap(width_, other->width_); + swap(height_, other->height_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Camera::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::localization::Camera* Arena::CreateMaybeMessage< ::apollo::localization::Camera >(Arena* arena) { + return Arena::CreateInternal< ::apollo::localization::Camera >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/camera.pb.h b/apollo_msgs/include/apollo_msgs/proto/localization/camera.pb.h new file mode 100644 index 0000000..9504670 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/camera.pb.h @@ -0,0 +1,353 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/camera.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include "apollo_msgs/proto/common/header.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[1]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto +namespace apollo { +namespace localization { +class Camera; +class CameraDefaultTypeInternal; +extern CameraDefaultTypeInternal _Camera_default_instance_; +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::localization::Camera* Arena::CreateMaybeMessage<::apollo::localization::Camera>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace localization { + +// =================================================================== + +class Camera : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.localization.Camera) */ { + public: + Camera(); + virtual ~Camera(); + + Camera(const Camera& from); + + inline Camera& operator=(const Camera& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Camera(Camera&& from) noexcept + : Camera() { + *this = ::std::move(from); + } + + inline Camera& operator=(Camera&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Camera& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Camera* internal_default_instance() { + return reinterpret_cast( + &_Camera_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(Camera* other); + friend void swap(Camera& a, Camera& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Camera* New() const final { + return CreateMaybeMessage(NULL); + } + + Camera* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Camera& from); + void MergeFrom(const Camera& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Camera* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // bytes image = 2; + void clear_image(); + static const int kImageFieldNumber = 2; + const ::std::string& image() const; + void set_image(const ::std::string& value); + #if LANG_CXX11 + void set_image(::std::string&& value); + #endif + void set_image(const char* value); + void set_image(const void* value, size_t size); + ::std::string* mutable_image(); + ::std::string* release_image(); + void set_allocated_image(::std::string* image); + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // uint32 width = 3; + void clear_width(); + static const int kWidthFieldNumber = 3; + ::google::protobuf::uint32 width() const; + void set_width(::google::protobuf::uint32 value); + + // uint32 height = 4; + void clear_height(); + static const int kHeightFieldNumber = 4; + ::google::protobuf::uint32 height() const; + void set_height(::google::protobuf::uint32 value); + + // @@protoc_insertion_point(class_scope:apollo.localization.Camera) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr image_; + ::apollo::common::Header* header_; + ::google::protobuf::uint32 width_; + ::google::protobuf::uint32 height_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// Camera + +// .apollo.common.Header header = 1; +inline bool Camera::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& Camera::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& Camera::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.localization.Camera.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* Camera::release_header() { + // @@protoc_insertion_point(field_release:apollo.localization.Camera.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* Camera::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Camera.header) + return header_; +} +inline void Camera::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Camera.header) +} + +// bytes image = 2; +inline void Camera::clear_image() { + image_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& Camera::image() const { + // @@protoc_insertion_point(field_get:apollo.localization.Camera.image) + return image_.GetNoArena(); +} +inline void Camera::set_image(const ::std::string& value) { + + image_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.localization.Camera.image) +} +#if LANG_CXX11 +inline void Camera::set_image(::std::string&& value) { + + image_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.localization.Camera.image) +} +#endif +inline void Camera::set_image(const char* value) { + GOOGLE_DCHECK(value != NULL); + + image_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.localization.Camera.image) +} +inline void Camera::set_image(const void* value, size_t size) { + + image_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.localization.Camera.image) +} +inline ::std::string* Camera::mutable_image() { + + // @@protoc_insertion_point(field_mutable:apollo.localization.Camera.image) + return image_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* Camera::release_image() { + // @@protoc_insertion_point(field_release:apollo.localization.Camera.image) + + return image_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void Camera::set_allocated_image(::std::string* image) { + if (image != NULL) { + + } else { + + } + image_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), image); + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Camera.image) +} + +// uint32 width = 3; +inline void Camera::clear_width() { + width_ = 0u; +} +inline ::google::protobuf::uint32 Camera::width() const { + // @@protoc_insertion_point(field_get:apollo.localization.Camera.width) + return width_; +} +inline void Camera::set_width(::google::protobuf::uint32 value) { + + width_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.Camera.width) +} + +// uint32 height = 4; +inline void Camera::clear_height() { + height_ = 0u; +} +inline ::google::protobuf::uint32 Camera::height() const { + // @@protoc_insertion_point(field_get:apollo.localization.Camera.height) + return height_; +} +inline void Camera::set_height(::google::protobuf::uint32 value) { + + height_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.Camera.height) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) + +} // namespace localization +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fcamera_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/camera_parameter.pb.cc b/apollo_msgs/include/apollo_msgs/proto/localization/camera_parameter.pb.cc new file mode 100644 index 0000000..fe4adda --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/camera_parameter.pb.cc @@ -0,0 +1,1220 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/camera_parameter.proto + +#include "apollo_msgs/proto/localization/camera_parameter.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_CameraExtrinsicParameter; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_CameraIntrinsicParameter; +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto +namespace apollo { +namespace localization { +class CameraIntrinsicParameterDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _CameraIntrinsicParameter_default_instance_; +class CameraExtrinsicParameterDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _CameraExtrinsicParameter_default_instance_; +class CameraParameterDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _CameraParameter_default_instance_; +} // namespace localization +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto { +static void InitDefaultsCameraIntrinsicParameter() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::localization::_CameraIntrinsicParameter_default_instance_; + new (ptr) ::apollo::localization::CameraIntrinsicParameter(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::localization::CameraIntrinsicParameter::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_CameraIntrinsicParameter = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsCameraIntrinsicParameter}, {}}; + +static void InitDefaultsCameraExtrinsicParameter() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::localization::_CameraExtrinsicParameter_default_instance_; + new (ptr) ::apollo::localization::CameraExtrinsicParameter(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::localization::CameraExtrinsicParameter::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_CameraExtrinsicParameter = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsCameraExtrinsicParameter}, {}}; + +static void InitDefaultsCameraParameter() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::localization::_CameraParameter_default_instance_; + new (ptr) ::apollo::localization::CameraParameter(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::localization::CameraParameter::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_CameraParameter = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsCameraParameter}, { + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::scc_info_CameraIntrinsicParameter.base, + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::scc_info_CameraExtrinsicParameter.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_CameraIntrinsicParameter.base); + ::google::protobuf::internal::InitSCC(&scc_info_CameraExtrinsicParameter.base); + ::google::protobuf::internal::InitSCC(&scc_info_CameraParameter.base); +} + +::google::protobuf::Metadata file_level_metadata[3]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraIntrinsicParameter, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraIntrinsicParameter, fx_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraIntrinsicParameter, fy_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraIntrinsicParameter, cx_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraIntrinsicParameter, cy_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraExtrinsicParameter, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraExtrinsicParameter, roll_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraExtrinsicParameter, pitch_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraExtrinsicParameter, yaw_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraExtrinsicParameter, tx_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraExtrinsicParameter, ty_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraExtrinsicParameter, tz_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraParameter, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraParameter, intrisic_parameter_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::CameraParameter, extrisic_parameter_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::localization::CameraIntrinsicParameter)}, + { 9, -1, sizeof(::apollo::localization::CameraExtrinsicParameter)}, + { 20, -1, sizeof(::apollo::localization::CameraParameter)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::localization::_CameraIntrinsicParameter_default_instance_), + reinterpret_cast(&::apollo::localization::_CameraExtrinsicParameter_default_instance_), + reinterpret_cast(&::apollo::localization::_CameraParameter_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/localization/camera_parameter.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 3); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n5apollo_msgs/proto/localization/camera_" + "parameter.proto\022\023apollo.localization\"J\n\030" + "CameraIntrinsicParameter\022\n\n\002fx\030\001 \001(\001\022\n\n\002" + "fy\030\002 \001(\001\022\n\n\002cx\030\003 \001(\001\022\n\n\002cy\030\004 \001(\001\"h\n\030Came" + "raExtrinsicParameter\022\014\n\004roll\030\001 \001(\001\022\r\n\005pi" + "tch\030\002 \001(\001\022\013\n\003yaw\030\003 \001(\001\022\n\n\002tx\030\004 \001(\001\022\n\n\002ty" + "\030\005 \001(\001\022\n\n\002tz\030\006 \001(\001\"\247\001\n\017CameraParameter\022I" + "\n\022intrisic_parameter\030\001 \001(\0132-.apollo.loca" + "lization.CameraIntrinsicParameter\022I\n\022ext" + "risic_parameter\030\002 \001(\0132-.apollo.localizat" + "ion.CameraExtrinsicParameterb\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 436); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/localization/camera_parameter.proto", &protobuf_RegisterTypes); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto +namespace apollo { +namespace localization { + +// =================================================================== + +void CameraIntrinsicParameter::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int CameraIntrinsicParameter::kFxFieldNumber; +const int CameraIntrinsicParameter::kFyFieldNumber; +const int CameraIntrinsicParameter::kCxFieldNumber; +const int CameraIntrinsicParameter::kCyFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +CameraIntrinsicParameter::CameraIntrinsicParameter() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::scc_info_CameraIntrinsicParameter.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.localization.CameraIntrinsicParameter) +} +CameraIntrinsicParameter::CameraIntrinsicParameter(const CameraIntrinsicParameter& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&fx_, &from.fx_, + static_cast(reinterpret_cast(&cy_) - + reinterpret_cast(&fx_)) + sizeof(cy_)); + // @@protoc_insertion_point(copy_constructor:apollo.localization.CameraIntrinsicParameter) +} + +void CameraIntrinsicParameter::SharedCtor() { + ::memset(&fx_, 0, static_cast( + reinterpret_cast(&cy_) - + reinterpret_cast(&fx_)) + sizeof(cy_)); +} + +CameraIntrinsicParameter::~CameraIntrinsicParameter() { + // @@protoc_insertion_point(destructor:apollo.localization.CameraIntrinsicParameter) + SharedDtor(); +} + +void CameraIntrinsicParameter::SharedDtor() { +} + +void CameraIntrinsicParameter::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* CameraIntrinsicParameter::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const CameraIntrinsicParameter& CameraIntrinsicParameter::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::scc_info_CameraIntrinsicParameter.base); + return *internal_default_instance(); +} + + +void CameraIntrinsicParameter::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.localization.CameraIntrinsicParameter) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&fx_, 0, static_cast( + reinterpret_cast(&cy_) - + reinterpret_cast(&fx_)) + sizeof(cy_)); + _internal_metadata_.Clear(); +} + +bool CameraIntrinsicParameter::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.localization.CameraIntrinsicParameter) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double fx = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &fx_))); + } else { + goto handle_unusual; + } + break; + } + + // double fy = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &fy_))); + } else { + goto handle_unusual; + } + break; + } + + // double cx = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &cx_))); + } else { + goto handle_unusual; + } + break; + } + + // double cy = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &cy_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.localization.CameraIntrinsicParameter) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.localization.CameraIntrinsicParameter) + return false; +#undef DO_ +} + +void CameraIntrinsicParameter::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.localization.CameraIntrinsicParameter) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double fx = 1; + if (this->fx() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->fx(), output); + } + + // double fy = 2; + if (this->fy() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->fy(), output); + } + + // double cx = 3; + if (this->cx() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->cx(), output); + } + + // double cy = 4; + if (this->cy() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->cy(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.localization.CameraIntrinsicParameter) +} + +::google::protobuf::uint8* CameraIntrinsicParameter::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.localization.CameraIntrinsicParameter) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double fx = 1; + if (this->fx() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->fx(), target); + } + + // double fy = 2; + if (this->fy() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->fy(), target); + } + + // double cx = 3; + if (this->cx() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->cx(), target); + } + + // double cy = 4; + if (this->cy() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->cy(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.localization.CameraIntrinsicParameter) + return target; +} + +size_t CameraIntrinsicParameter::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.localization.CameraIntrinsicParameter) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double fx = 1; + if (this->fx() != 0) { + total_size += 1 + 8; + } + + // double fy = 2; + if (this->fy() != 0) { + total_size += 1 + 8; + } + + // double cx = 3; + if (this->cx() != 0) { + total_size += 1 + 8; + } + + // double cy = 4; + if (this->cy() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void CameraIntrinsicParameter::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.localization.CameraIntrinsicParameter) + GOOGLE_DCHECK_NE(&from, this); + const CameraIntrinsicParameter* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.localization.CameraIntrinsicParameter) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.localization.CameraIntrinsicParameter) + MergeFrom(*source); + } +} + +void CameraIntrinsicParameter::MergeFrom(const CameraIntrinsicParameter& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.localization.CameraIntrinsicParameter) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.fx() != 0) { + set_fx(from.fx()); + } + if (from.fy() != 0) { + set_fy(from.fy()); + } + if (from.cx() != 0) { + set_cx(from.cx()); + } + if (from.cy() != 0) { + set_cy(from.cy()); + } +} + +void CameraIntrinsicParameter::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.localization.CameraIntrinsicParameter) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void CameraIntrinsicParameter::CopyFrom(const CameraIntrinsicParameter& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.localization.CameraIntrinsicParameter) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool CameraIntrinsicParameter::IsInitialized() const { + return true; +} + +void CameraIntrinsicParameter::Swap(CameraIntrinsicParameter* other) { + if (other == this) return; + InternalSwap(other); +} +void CameraIntrinsicParameter::InternalSwap(CameraIntrinsicParameter* other) { + using std::swap; + swap(fx_, other->fx_); + swap(fy_, other->fy_); + swap(cx_, other->cx_); + swap(cy_, other->cy_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata CameraIntrinsicParameter::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void CameraExtrinsicParameter::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int CameraExtrinsicParameter::kRollFieldNumber; +const int CameraExtrinsicParameter::kPitchFieldNumber; +const int CameraExtrinsicParameter::kYawFieldNumber; +const int CameraExtrinsicParameter::kTxFieldNumber; +const int CameraExtrinsicParameter::kTyFieldNumber; +const int CameraExtrinsicParameter::kTzFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +CameraExtrinsicParameter::CameraExtrinsicParameter() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::scc_info_CameraExtrinsicParameter.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.localization.CameraExtrinsicParameter) +} +CameraExtrinsicParameter::CameraExtrinsicParameter(const CameraExtrinsicParameter& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&roll_, &from.roll_, + static_cast(reinterpret_cast(&tz_) - + reinterpret_cast(&roll_)) + sizeof(tz_)); + // @@protoc_insertion_point(copy_constructor:apollo.localization.CameraExtrinsicParameter) +} + +void CameraExtrinsicParameter::SharedCtor() { + ::memset(&roll_, 0, static_cast( + reinterpret_cast(&tz_) - + reinterpret_cast(&roll_)) + sizeof(tz_)); +} + +CameraExtrinsicParameter::~CameraExtrinsicParameter() { + // @@protoc_insertion_point(destructor:apollo.localization.CameraExtrinsicParameter) + SharedDtor(); +} + +void CameraExtrinsicParameter::SharedDtor() { +} + +void CameraExtrinsicParameter::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* CameraExtrinsicParameter::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const CameraExtrinsicParameter& CameraExtrinsicParameter::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::scc_info_CameraExtrinsicParameter.base); + return *internal_default_instance(); +} + + +void CameraExtrinsicParameter::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.localization.CameraExtrinsicParameter) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&roll_, 0, static_cast( + reinterpret_cast(&tz_) - + reinterpret_cast(&roll_)) + sizeof(tz_)); + _internal_metadata_.Clear(); +} + +bool CameraExtrinsicParameter::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.localization.CameraExtrinsicParameter) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double roll = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &roll_))); + } else { + goto handle_unusual; + } + break; + } + + // double pitch = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &pitch_))); + } else { + goto handle_unusual; + } + break; + } + + // double yaw = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &yaw_))); + } else { + goto handle_unusual; + } + break; + } + + // double tx = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &tx_))); + } else { + goto handle_unusual; + } + break; + } + + // double ty = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &ty_))); + } else { + goto handle_unusual; + } + break; + } + + // double tz = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &tz_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.localization.CameraExtrinsicParameter) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.localization.CameraExtrinsicParameter) + return false; +#undef DO_ +} + +void CameraExtrinsicParameter::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.localization.CameraExtrinsicParameter) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double roll = 1; + if (this->roll() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->roll(), output); + } + + // double pitch = 2; + if (this->pitch() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->pitch(), output); + } + + // double yaw = 3; + if (this->yaw() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->yaw(), output); + } + + // double tx = 4; + if (this->tx() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->tx(), output); + } + + // double ty = 5; + if (this->ty() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->ty(), output); + } + + // double tz = 6; + if (this->tz() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->tz(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.localization.CameraExtrinsicParameter) +} + +::google::protobuf::uint8* CameraExtrinsicParameter::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.localization.CameraExtrinsicParameter) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double roll = 1; + if (this->roll() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->roll(), target); + } + + // double pitch = 2; + if (this->pitch() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->pitch(), target); + } + + // double yaw = 3; + if (this->yaw() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->yaw(), target); + } + + // double tx = 4; + if (this->tx() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->tx(), target); + } + + // double ty = 5; + if (this->ty() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->ty(), target); + } + + // double tz = 6; + if (this->tz() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->tz(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.localization.CameraExtrinsicParameter) + return target; +} + +size_t CameraExtrinsicParameter::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.localization.CameraExtrinsicParameter) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double roll = 1; + if (this->roll() != 0) { + total_size += 1 + 8; + } + + // double pitch = 2; + if (this->pitch() != 0) { + total_size += 1 + 8; + } + + // double yaw = 3; + if (this->yaw() != 0) { + total_size += 1 + 8; + } + + // double tx = 4; + if (this->tx() != 0) { + total_size += 1 + 8; + } + + // double ty = 5; + if (this->ty() != 0) { + total_size += 1 + 8; + } + + // double tz = 6; + if (this->tz() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void CameraExtrinsicParameter::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.localization.CameraExtrinsicParameter) + GOOGLE_DCHECK_NE(&from, this); + const CameraExtrinsicParameter* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.localization.CameraExtrinsicParameter) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.localization.CameraExtrinsicParameter) + MergeFrom(*source); + } +} + +void CameraExtrinsicParameter::MergeFrom(const CameraExtrinsicParameter& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.localization.CameraExtrinsicParameter) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.roll() != 0) { + set_roll(from.roll()); + } + if (from.pitch() != 0) { + set_pitch(from.pitch()); + } + if (from.yaw() != 0) { + set_yaw(from.yaw()); + } + if (from.tx() != 0) { + set_tx(from.tx()); + } + if (from.ty() != 0) { + set_ty(from.ty()); + } + if (from.tz() != 0) { + set_tz(from.tz()); + } +} + +void CameraExtrinsicParameter::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.localization.CameraExtrinsicParameter) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void CameraExtrinsicParameter::CopyFrom(const CameraExtrinsicParameter& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.localization.CameraExtrinsicParameter) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool CameraExtrinsicParameter::IsInitialized() const { + return true; +} + +void CameraExtrinsicParameter::Swap(CameraExtrinsicParameter* other) { + if (other == this) return; + InternalSwap(other); +} +void CameraExtrinsicParameter::InternalSwap(CameraExtrinsicParameter* other) { + using std::swap; + swap(roll_, other->roll_); + swap(pitch_, other->pitch_); + swap(yaw_, other->yaw_); + swap(tx_, other->tx_); + swap(ty_, other->ty_); + swap(tz_, other->tz_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata CameraExtrinsicParameter::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void CameraParameter::InitAsDefaultInstance() { + ::apollo::localization::_CameraParameter_default_instance_._instance.get_mutable()->intrisic_parameter_ = const_cast< ::apollo::localization::CameraIntrinsicParameter*>( + ::apollo::localization::CameraIntrinsicParameter::internal_default_instance()); + ::apollo::localization::_CameraParameter_default_instance_._instance.get_mutable()->extrisic_parameter_ = const_cast< ::apollo::localization::CameraExtrinsicParameter*>( + ::apollo::localization::CameraExtrinsicParameter::internal_default_instance()); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int CameraParameter::kIntrisicParameterFieldNumber; +const int CameraParameter::kExtrisicParameterFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +CameraParameter::CameraParameter() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::scc_info_CameraParameter.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.localization.CameraParameter) +} +CameraParameter::CameraParameter(const CameraParameter& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_intrisic_parameter()) { + intrisic_parameter_ = new ::apollo::localization::CameraIntrinsicParameter(*from.intrisic_parameter_); + } else { + intrisic_parameter_ = NULL; + } + if (from.has_extrisic_parameter()) { + extrisic_parameter_ = new ::apollo::localization::CameraExtrinsicParameter(*from.extrisic_parameter_); + } else { + extrisic_parameter_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.localization.CameraParameter) +} + +void CameraParameter::SharedCtor() { + ::memset(&intrisic_parameter_, 0, static_cast( + reinterpret_cast(&extrisic_parameter_) - + reinterpret_cast(&intrisic_parameter_)) + sizeof(extrisic_parameter_)); +} + +CameraParameter::~CameraParameter() { + // @@protoc_insertion_point(destructor:apollo.localization.CameraParameter) + SharedDtor(); +} + +void CameraParameter::SharedDtor() { + if (this != internal_default_instance()) delete intrisic_parameter_; + if (this != internal_default_instance()) delete extrisic_parameter_; +} + +void CameraParameter::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* CameraParameter::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const CameraParameter& CameraParameter::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::scc_info_CameraParameter.base); + return *internal_default_instance(); +} + + +void CameraParameter::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.localization.CameraParameter) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && intrisic_parameter_ != NULL) { + delete intrisic_parameter_; + } + intrisic_parameter_ = NULL; + if (GetArenaNoVirtual() == NULL && extrisic_parameter_ != NULL) { + delete extrisic_parameter_; + } + extrisic_parameter_ = NULL; + _internal_metadata_.Clear(); +} + +bool CameraParameter::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.localization.CameraParameter) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.localization.CameraIntrinsicParameter intrisic_parameter = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_intrisic_parameter())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.localization.CameraExtrinsicParameter extrisic_parameter = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_extrisic_parameter())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.localization.CameraParameter) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.localization.CameraParameter) + return false; +#undef DO_ +} + +void CameraParameter::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.localization.CameraParameter) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.localization.CameraIntrinsicParameter intrisic_parameter = 1; + if (this->has_intrisic_parameter()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_intrisic_parameter(), output); + } + + // .apollo.localization.CameraExtrinsicParameter extrisic_parameter = 2; + if (this->has_extrisic_parameter()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_extrisic_parameter(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.localization.CameraParameter) +} + +::google::protobuf::uint8* CameraParameter::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.localization.CameraParameter) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.localization.CameraIntrinsicParameter intrisic_parameter = 1; + if (this->has_intrisic_parameter()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_intrisic_parameter(), deterministic, target); + } + + // .apollo.localization.CameraExtrinsicParameter extrisic_parameter = 2; + if (this->has_extrisic_parameter()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_extrisic_parameter(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.localization.CameraParameter) + return target; +} + +size_t CameraParameter::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.localization.CameraParameter) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.localization.CameraIntrinsicParameter intrisic_parameter = 1; + if (this->has_intrisic_parameter()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *intrisic_parameter_); + } + + // .apollo.localization.CameraExtrinsicParameter extrisic_parameter = 2; + if (this->has_extrisic_parameter()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *extrisic_parameter_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void CameraParameter::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.localization.CameraParameter) + GOOGLE_DCHECK_NE(&from, this); + const CameraParameter* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.localization.CameraParameter) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.localization.CameraParameter) + MergeFrom(*source); + } +} + +void CameraParameter::MergeFrom(const CameraParameter& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.localization.CameraParameter) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_intrisic_parameter()) { + mutable_intrisic_parameter()->::apollo::localization::CameraIntrinsicParameter::MergeFrom(from.intrisic_parameter()); + } + if (from.has_extrisic_parameter()) { + mutable_extrisic_parameter()->::apollo::localization::CameraExtrinsicParameter::MergeFrom(from.extrisic_parameter()); + } +} + +void CameraParameter::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.localization.CameraParameter) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void CameraParameter::CopyFrom(const CameraParameter& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.localization.CameraParameter) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool CameraParameter::IsInitialized() const { + return true; +} + +void CameraParameter::Swap(CameraParameter* other) { + if (other == this) return; + InternalSwap(other); +} +void CameraParameter::InternalSwap(CameraParameter* other) { + using std::swap; + swap(intrisic_parameter_, other->intrisic_parameter_); + swap(extrisic_parameter_, other->extrisic_parameter_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata CameraParameter::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::localization::CameraIntrinsicParameter* Arena::CreateMaybeMessage< ::apollo::localization::CameraIntrinsicParameter >(Arena* arena) { + return Arena::CreateInternal< ::apollo::localization::CameraIntrinsicParameter >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::localization::CameraExtrinsicParameter* Arena::CreateMaybeMessage< ::apollo::localization::CameraExtrinsicParameter >(Arena* arena) { + return Arena::CreateInternal< ::apollo::localization::CameraExtrinsicParameter >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::localization::CameraParameter* Arena::CreateMaybeMessage< ::apollo::localization::CameraParameter >(Arena* arena) { + return Arena::CreateInternal< ::apollo::localization::CameraParameter >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/camera_parameter.pb.h b/apollo_msgs/include/apollo_msgs/proto/localization/camera_parameter.pb.h new file mode 100644 index 0000000..015c06f --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/camera_parameter.pb.h @@ -0,0 +1,737 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/camera_parameter.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[3]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto +namespace apollo { +namespace localization { +class CameraExtrinsicParameter; +class CameraExtrinsicParameterDefaultTypeInternal; +extern CameraExtrinsicParameterDefaultTypeInternal _CameraExtrinsicParameter_default_instance_; +class CameraIntrinsicParameter; +class CameraIntrinsicParameterDefaultTypeInternal; +extern CameraIntrinsicParameterDefaultTypeInternal _CameraIntrinsicParameter_default_instance_; +class CameraParameter; +class CameraParameterDefaultTypeInternal; +extern CameraParameterDefaultTypeInternal _CameraParameter_default_instance_; +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::localization::CameraExtrinsicParameter* Arena::CreateMaybeMessage<::apollo::localization::CameraExtrinsicParameter>(Arena*); +template<> ::apollo::localization::CameraIntrinsicParameter* Arena::CreateMaybeMessage<::apollo::localization::CameraIntrinsicParameter>(Arena*); +template<> ::apollo::localization::CameraParameter* Arena::CreateMaybeMessage<::apollo::localization::CameraParameter>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace localization { + +// =================================================================== + +class CameraIntrinsicParameter : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.localization.CameraIntrinsicParameter) */ { + public: + CameraIntrinsicParameter(); + virtual ~CameraIntrinsicParameter(); + + CameraIntrinsicParameter(const CameraIntrinsicParameter& from); + + inline CameraIntrinsicParameter& operator=(const CameraIntrinsicParameter& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + CameraIntrinsicParameter(CameraIntrinsicParameter&& from) noexcept + : CameraIntrinsicParameter() { + *this = ::std::move(from); + } + + inline CameraIntrinsicParameter& operator=(CameraIntrinsicParameter&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const CameraIntrinsicParameter& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const CameraIntrinsicParameter* internal_default_instance() { + return reinterpret_cast( + &_CameraIntrinsicParameter_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(CameraIntrinsicParameter* other); + friend void swap(CameraIntrinsicParameter& a, CameraIntrinsicParameter& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline CameraIntrinsicParameter* New() const final { + return CreateMaybeMessage(NULL); + } + + CameraIntrinsicParameter* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const CameraIntrinsicParameter& from); + void MergeFrom(const CameraIntrinsicParameter& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(CameraIntrinsicParameter* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double fx = 1; + void clear_fx(); + static const int kFxFieldNumber = 1; + double fx() const; + void set_fx(double value); + + // double fy = 2; + void clear_fy(); + static const int kFyFieldNumber = 2; + double fy() const; + void set_fy(double value); + + // double cx = 3; + void clear_cx(); + static const int kCxFieldNumber = 3; + double cx() const; + void set_cx(double value); + + // double cy = 4; + void clear_cy(); + static const int kCyFieldNumber = 4; + double cy() const; + void set_cy(double value); + + // @@protoc_insertion_point(class_scope:apollo.localization.CameraIntrinsicParameter) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double fx_; + double fy_; + double cx_; + double cy_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class CameraExtrinsicParameter : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.localization.CameraExtrinsicParameter) */ { + public: + CameraExtrinsicParameter(); + virtual ~CameraExtrinsicParameter(); + + CameraExtrinsicParameter(const CameraExtrinsicParameter& from); + + inline CameraExtrinsicParameter& operator=(const CameraExtrinsicParameter& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + CameraExtrinsicParameter(CameraExtrinsicParameter&& from) noexcept + : CameraExtrinsicParameter() { + *this = ::std::move(from); + } + + inline CameraExtrinsicParameter& operator=(CameraExtrinsicParameter&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const CameraExtrinsicParameter& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const CameraExtrinsicParameter* internal_default_instance() { + return reinterpret_cast( + &_CameraExtrinsicParameter_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(CameraExtrinsicParameter* other); + friend void swap(CameraExtrinsicParameter& a, CameraExtrinsicParameter& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline CameraExtrinsicParameter* New() const final { + return CreateMaybeMessage(NULL); + } + + CameraExtrinsicParameter* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const CameraExtrinsicParameter& from); + void MergeFrom(const CameraExtrinsicParameter& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(CameraExtrinsicParameter* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double roll = 1; + void clear_roll(); + static const int kRollFieldNumber = 1; + double roll() const; + void set_roll(double value); + + // double pitch = 2; + void clear_pitch(); + static const int kPitchFieldNumber = 2; + double pitch() const; + void set_pitch(double value); + + // double yaw = 3; + void clear_yaw(); + static const int kYawFieldNumber = 3; + double yaw() const; + void set_yaw(double value); + + // double tx = 4; + void clear_tx(); + static const int kTxFieldNumber = 4; + double tx() const; + void set_tx(double value); + + // double ty = 5; + void clear_ty(); + static const int kTyFieldNumber = 5; + double ty() const; + void set_ty(double value); + + // double tz = 6; + void clear_tz(); + static const int kTzFieldNumber = 6; + double tz() const; + void set_tz(double value); + + // @@protoc_insertion_point(class_scope:apollo.localization.CameraExtrinsicParameter) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double roll_; + double pitch_; + double yaw_; + double tx_; + double ty_; + double tz_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class CameraParameter : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.localization.CameraParameter) */ { + public: + CameraParameter(); + virtual ~CameraParameter(); + + CameraParameter(const CameraParameter& from); + + inline CameraParameter& operator=(const CameraParameter& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + CameraParameter(CameraParameter&& from) noexcept + : CameraParameter() { + *this = ::std::move(from); + } + + inline CameraParameter& operator=(CameraParameter&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const CameraParameter& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const CameraParameter* internal_default_instance() { + return reinterpret_cast( + &_CameraParameter_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + void Swap(CameraParameter* other); + friend void swap(CameraParameter& a, CameraParameter& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline CameraParameter* New() const final { + return CreateMaybeMessage(NULL); + } + + CameraParameter* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const CameraParameter& from); + void MergeFrom(const CameraParameter& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(CameraParameter* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.localization.CameraIntrinsicParameter intrisic_parameter = 1; + bool has_intrisic_parameter() const; + void clear_intrisic_parameter(); + static const int kIntrisicParameterFieldNumber = 1; + private: + const ::apollo::localization::CameraIntrinsicParameter& _internal_intrisic_parameter() const; + public: + const ::apollo::localization::CameraIntrinsicParameter& intrisic_parameter() const; + ::apollo::localization::CameraIntrinsicParameter* release_intrisic_parameter(); + ::apollo::localization::CameraIntrinsicParameter* mutable_intrisic_parameter(); + void set_allocated_intrisic_parameter(::apollo::localization::CameraIntrinsicParameter* intrisic_parameter); + + // .apollo.localization.CameraExtrinsicParameter extrisic_parameter = 2; + bool has_extrisic_parameter() const; + void clear_extrisic_parameter(); + static const int kExtrisicParameterFieldNumber = 2; + private: + const ::apollo::localization::CameraExtrinsicParameter& _internal_extrisic_parameter() const; + public: + const ::apollo::localization::CameraExtrinsicParameter& extrisic_parameter() const; + ::apollo::localization::CameraExtrinsicParameter* release_extrisic_parameter(); + ::apollo::localization::CameraExtrinsicParameter* mutable_extrisic_parameter(); + void set_allocated_extrisic_parameter(::apollo::localization::CameraExtrinsicParameter* extrisic_parameter); + + // @@protoc_insertion_point(class_scope:apollo.localization.CameraParameter) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::localization::CameraIntrinsicParameter* intrisic_parameter_; + ::apollo::localization::CameraExtrinsicParameter* extrisic_parameter_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// CameraIntrinsicParameter + +// double fx = 1; +inline void CameraIntrinsicParameter::clear_fx() { + fx_ = 0; +} +inline double CameraIntrinsicParameter::fx() const { + // @@protoc_insertion_point(field_get:apollo.localization.CameraIntrinsicParameter.fx) + return fx_; +} +inline void CameraIntrinsicParameter::set_fx(double value) { + + fx_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.CameraIntrinsicParameter.fx) +} + +// double fy = 2; +inline void CameraIntrinsicParameter::clear_fy() { + fy_ = 0; +} +inline double CameraIntrinsicParameter::fy() const { + // @@protoc_insertion_point(field_get:apollo.localization.CameraIntrinsicParameter.fy) + return fy_; +} +inline void CameraIntrinsicParameter::set_fy(double value) { + + fy_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.CameraIntrinsicParameter.fy) +} + +// double cx = 3; +inline void CameraIntrinsicParameter::clear_cx() { + cx_ = 0; +} +inline double CameraIntrinsicParameter::cx() const { + // @@protoc_insertion_point(field_get:apollo.localization.CameraIntrinsicParameter.cx) + return cx_; +} +inline void CameraIntrinsicParameter::set_cx(double value) { + + cx_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.CameraIntrinsicParameter.cx) +} + +// double cy = 4; +inline void CameraIntrinsicParameter::clear_cy() { + cy_ = 0; +} +inline double CameraIntrinsicParameter::cy() const { + // @@protoc_insertion_point(field_get:apollo.localization.CameraIntrinsicParameter.cy) + return cy_; +} +inline void CameraIntrinsicParameter::set_cy(double value) { + + cy_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.CameraIntrinsicParameter.cy) +} + +// ------------------------------------------------------------------- + +// CameraExtrinsicParameter + +// double roll = 1; +inline void CameraExtrinsicParameter::clear_roll() { + roll_ = 0; +} +inline double CameraExtrinsicParameter::roll() const { + // @@protoc_insertion_point(field_get:apollo.localization.CameraExtrinsicParameter.roll) + return roll_; +} +inline void CameraExtrinsicParameter::set_roll(double value) { + + roll_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.CameraExtrinsicParameter.roll) +} + +// double pitch = 2; +inline void CameraExtrinsicParameter::clear_pitch() { + pitch_ = 0; +} +inline double CameraExtrinsicParameter::pitch() const { + // @@protoc_insertion_point(field_get:apollo.localization.CameraExtrinsicParameter.pitch) + return pitch_; +} +inline void CameraExtrinsicParameter::set_pitch(double value) { + + pitch_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.CameraExtrinsicParameter.pitch) +} + +// double yaw = 3; +inline void CameraExtrinsicParameter::clear_yaw() { + yaw_ = 0; +} +inline double CameraExtrinsicParameter::yaw() const { + // @@protoc_insertion_point(field_get:apollo.localization.CameraExtrinsicParameter.yaw) + return yaw_; +} +inline void CameraExtrinsicParameter::set_yaw(double value) { + + yaw_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.CameraExtrinsicParameter.yaw) +} + +// double tx = 4; +inline void CameraExtrinsicParameter::clear_tx() { + tx_ = 0; +} +inline double CameraExtrinsicParameter::tx() const { + // @@protoc_insertion_point(field_get:apollo.localization.CameraExtrinsicParameter.tx) + return tx_; +} +inline void CameraExtrinsicParameter::set_tx(double value) { + + tx_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.CameraExtrinsicParameter.tx) +} + +// double ty = 5; +inline void CameraExtrinsicParameter::clear_ty() { + ty_ = 0; +} +inline double CameraExtrinsicParameter::ty() const { + // @@protoc_insertion_point(field_get:apollo.localization.CameraExtrinsicParameter.ty) + return ty_; +} +inline void CameraExtrinsicParameter::set_ty(double value) { + + ty_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.CameraExtrinsicParameter.ty) +} + +// double tz = 6; +inline void CameraExtrinsicParameter::clear_tz() { + tz_ = 0; +} +inline double CameraExtrinsicParameter::tz() const { + // @@protoc_insertion_point(field_get:apollo.localization.CameraExtrinsicParameter.tz) + return tz_; +} +inline void CameraExtrinsicParameter::set_tz(double value) { + + tz_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.CameraExtrinsicParameter.tz) +} + +// ------------------------------------------------------------------- + +// CameraParameter + +// .apollo.localization.CameraIntrinsicParameter intrisic_parameter = 1; +inline bool CameraParameter::has_intrisic_parameter() const { + return this != internal_default_instance() && intrisic_parameter_ != NULL; +} +inline void CameraParameter::clear_intrisic_parameter() { + if (GetArenaNoVirtual() == NULL && intrisic_parameter_ != NULL) { + delete intrisic_parameter_; + } + intrisic_parameter_ = NULL; +} +inline const ::apollo::localization::CameraIntrinsicParameter& CameraParameter::_internal_intrisic_parameter() const { + return *intrisic_parameter_; +} +inline const ::apollo::localization::CameraIntrinsicParameter& CameraParameter::intrisic_parameter() const { + const ::apollo::localization::CameraIntrinsicParameter* p = intrisic_parameter_; + // @@protoc_insertion_point(field_get:apollo.localization.CameraParameter.intrisic_parameter) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::localization::_CameraIntrinsicParameter_default_instance_); +} +inline ::apollo::localization::CameraIntrinsicParameter* CameraParameter::release_intrisic_parameter() { + // @@protoc_insertion_point(field_release:apollo.localization.CameraParameter.intrisic_parameter) + + ::apollo::localization::CameraIntrinsicParameter* temp = intrisic_parameter_; + intrisic_parameter_ = NULL; + return temp; +} +inline ::apollo::localization::CameraIntrinsicParameter* CameraParameter::mutable_intrisic_parameter() { + + if (intrisic_parameter_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::localization::CameraIntrinsicParameter>(GetArenaNoVirtual()); + intrisic_parameter_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.CameraParameter.intrisic_parameter) + return intrisic_parameter_; +} +inline void CameraParameter::set_allocated_intrisic_parameter(::apollo::localization::CameraIntrinsicParameter* intrisic_parameter) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete intrisic_parameter_; + } + if (intrisic_parameter) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + intrisic_parameter = ::google::protobuf::internal::GetOwnedMessage( + message_arena, intrisic_parameter, submessage_arena); + } + + } else { + + } + intrisic_parameter_ = intrisic_parameter; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.CameraParameter.intrisic_parameter) +} + +// .apollo.localization.CameraExtrinsicParameter extrisic_parameter = 2; +inline bool CameraParameter::has_extrisic_parameter() const { + return this != internal_default_instance() && extrisic_parameter_ != NULL; +} +inline void CameraParameter::clear_extrisic_parameter() { + if (GetArenaNoVirtual() == NULL && extrisic_parameter_ != NULL) { + delete extrisic_parameter_; + } + extrisic_parameter_ = NULL; +} +inline const ::apollo::localization::CameraExtrinsicParameter& CameraParameter::_internal_extrisic_parameter() const { + return *extrisic_parameter_; +} +inline const ::apollo::localization::CameraExtrinsicParameter& CameraParameter::extrisic_parameter() const { + const ::apollo::localization::CameraExtrinsicParameter* p = extrisic_parameter_; + // @@protoc_insertion_point(field_get:apollo.localization.CameraParameter.extrisic_parameter) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::localization::_CameraExtrinsicParameter_default_instance_); +} +inline ::apollo::localization::CameraExtrinsicParameter* CameraParameter::release_extrisic_parameter() { + // @@protoc_insertion_point(field_release:apollo.localization.CameraParameter.extrisic_parameter) + + ::apollo::localization::CameraExtrinsicParameter* temp = extrisic_parameter_; + extrisic_parameter_ = NULL; + return temp; +} +inline ::apollo::localization::CameraExtrinsicParameter* CameraParameter::mutable_extrisic_parameter() { + + if (extrisic_parameter_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::localization::CameraExtrinsicParameter>(GetArenaNoVirtual()); + extrisic_parameter_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.CameraParameter.extrisic_parameter) + return extrisic_parameter_; +} +inline void CameraParameter::set_allocated_extrisic_parameter(::apollo::localization::CameraExtrinsicParameter* extrisic_parameter) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete extrisic_parameter_; + } + if (extrisic_parameter) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + extrisic_parameter = ::google::protobuf::internal::GetOwnedMessage( + message_arena, extrisic_parameter, submessage_arena); + } + + } else { + + } + extrisic_parameter_ = extrisic_parameter; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.CameraParameter.extrisic_parameter) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace localization +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fcamera_5fparameter_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/gps.pb.cc b/apollo_msgs/include/apollo_msgs/proto/localization/gps.pb.cc new file mode 100644 index 0000000..212612a --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/gps.pb.cc @@ -0,0 +1,436 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/gps.proto + +#include "apollo_msgs/proto/localization/gps.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto ::google::protobuf::internal::SCCInfo<3> scc_info_Pose; +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto +namespace apollo { +namespace localization { +class GpsDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Gps_default_instance_; +} // namespace localization +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto { +static void InitDefaultsGps() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::localization::_Gps_default_instance_; + new (ptr) ::apollo::localization::Gps(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::localization::Gps::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_Gps = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsGps}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base, + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::scc_info_Pose.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_Gps.base); +} + +::google::protobuf::Metadata file_level_metadata[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Gps, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Gps, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Gps, localization_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::localization::Gps)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::localization::_Gps_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/localization/gps.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 1); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n(apollo_msgs/proto/localization/gps.pro" + "to\022\023apollo.localization\032%apollo_msgs/pro" + "to/common/header.proto\032)apollo_msgs/prot" + "o/localization/pose.proto\"]\n\003Gps\022%\n\006head" + "er\030\001 \001(\0132\025.apollo.common.Header\022/\n\014local" + "ization\030\002 \001(\0132\031.apollo.localization.Pose" + "b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 248); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/localization/gps.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto +namespace apollo { +namespace localization { + +// =================================================================== + +void Gps::InitAsDefaultInstance() { + ::apollo::localization::_Gps_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); + ::apollo::localization::_Gps_default_instance_._instance.get_mutable()->localization_ = const_cast< ::apollo::localization::Pose*>( + ::apollo::localization::Pose::internal_default_instance()); +} +void Gps::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +void Gps::clear_localization() { + if (GetArenaNoVirtual() == NULL && localization_ != NULL) { + delete localization_; + } + localization_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Gps::kHeaderFieldNumber; +const int Gps::kLocalizationFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Gps::Gps() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto::scc_info_Gps.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.localization.Gps) +} +Gps::Gps(const Gps& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + if (from.has_localization()) { + localization_ = new ::apollo::localization::Pose(*from.localization_); + } else { + localization_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.localization.Gps) +} + +void Gps::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&localization_) - + reinterpret_cast(&header_)) + sizeof(localization_)); +} + +Gps::~Gps() { + // @@protoc_insertion_point(destructor:apollo.localization.Gps) + SharedDtor(); +} + +void Gps::SharedDtor() { + if (this != internal_default_instance()) delete header_; + if (this != internal_default_instance()) delete localization_; +} + +void Gps::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Gps::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Gps& Gps::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto::scc_info_Gps.base); + return *internal_default_instance(); +} + + +void Gps::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.localization.Gps) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + if (GetArenaNoVirtual() == NULL && localization_ != NULL) { + delete localization_; + } + localization_ = NULL; + _internal_metadata_.Clear(); +} + +bool Gps::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.localization.Gps) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.localization.Pose localization = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_localization())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.localization.Gps) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.localization.Gps) + return false; +#undef DO_ +} + +void Gps::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.localization.Gps) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // .apollo.localization.Pose localization = 2; + if (this->has_localization()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_localization(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.localization.Gps) +} + +::google::protobuf::uint8* Gps::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.localization.Gps) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // .apollo.localization.Pose localization = 2; + if (this->has_localization()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_localization(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.localization.Gps) + return target; +} + +size_t Gps::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.localization.Gps) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.localization.Pose localization = 2; + if (this->has_localization()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *localization_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Gps::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.localization.Gps) + GOOGLE_DCHECK_NE(&from, this); + const Gps* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.localization.Gps) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.localization.Gps) + MergeFrom(*source); + } +} + +void Gps::MergeFrom(const Gps& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.localization.Gps) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.has_localization()) { + mutable_localization()->::apollo::localization::Pose::MergeFrom(from.localization()); + } +} + +void Gps::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.localization.Gps) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Gps::CopyFrom(const Gps& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.localization.Gps) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Gps::IsInitialized() const { + return true; +} + +void Gps::Swap(Gps* other) { + if (other == this) return; + InternalSwap(other); +} +void Gps::InternalSwap(Gps* other) { + using std::swap; + swap(header_, other->header_); + swap(localization_, other->localization_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Gps::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::localization::Gps* Arena::CreateMaybeMessage< ::apollo::localization::Gps >(Arena* arena) { + return Arena::CreateInternal< ::apollo::localization::Gps >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/gps.pb.h b/apollo_msgs/include/apollo_msgs/proto/localization/gps.pb.h new file mode 100644 index 0000000..bf6ac39 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/gps.pb.h @@ -0,0 +1,305 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/gps.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include "apollo_msgs/proto/common/header.pb.h" +#include "apollo_msgs/proto/localization/pose.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[1]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto +namespace apollo { +namespace localization { +class Gps; +class GpsDefaultTypeInternal; +extern GpsDefaultTypeInternal _Gps_default_instance_; +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::localization::Gps* Arena::CreateMaybeMessage<::apollo::localization::Gps>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace localization { + +// =================================================================== + +class Gps : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.localization.Gps) */ { + public: + Gps(); + virtual ~Gps(); + + Gps(const Gps& from); + + inline Gps& operator=(const Gps& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Gps(Gps&& from) noexcept + : Gps() { + *this = ::std::move(from); + } + + inline Gps& operator=(Gps&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Gps& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Gps* internal_default_instance() { + return reinterpret_cast( + &_Gps_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(Gps* other); + friend void swap(Gps& a, Gps& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Gps* New() const final { + return CreateMaybeMessage(NULL); + } + + Gps* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Gps& from); + void MergeFrom(const Gps& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Gps* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.localization.Pose localization = 2; + bool has_localization() const; + void clear_localization(); + static const int kLocalizationFieldNumber = 2; + private: + const ::apollo::localization::Pose& _internal_localization() const; + public: + const ::apollo::localization::Pose& localization() const; + ::apollo::localization::Pose* release_localization(); + ::apollo::localization::Pose* mutable_localization(); + void set_allocated_localization(::apollo::localization::Pose* localization); + + // @@protoc_insertion_point(class_scope:apollo.localization.Gps) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::Header* header_; + ::apollo::localization::Pose* localization_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// Gps + +// .apollo.common.Header header = 1; +inline bool Gps::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& Gps::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& Gps::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.localization.Gps.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* Gps::release_header() { + // @@protoc_insertion_point(field_release:apollo.localization.Gps.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* Gps::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Gps.header) + return header_; +} +inline void Gps::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Gps.header) +} + +// .apollo.localization.Pose localization = 2; +inline bool Gps::has_localization() const { + return this != internal_default_instance() && localization_ != NULL; +} +inline const ::apollo::localization::Pose& Gps::_internal_localization() const { + return *localization_; +} +inline const ::apollo::localization::Pose& Gps::localization() const { + const ::apollo::localization::Pose* p = localization_; + // @@protoc_insertion_point(field_get:apollo.localization.Gps.localization) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::localization::_Pose_default_instance_); +} +inline ::apollo::localization::Pose* Gps::release_localization() { + // @@protoc_insertion_point(field_release:apollo.localization.Gps.localization) + + ::apollo::localization::Pose* temp = localization_; + localization_ = NULL; + return temp; +} +inline ::apollo::localization::Pose* Gps::mutable_localization() { + + if (localization_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::localization::Pose>(GetArenaNoVirtual()); + localization_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Gps.localization) + return localization_; +} +inline void Gps::set_allocated_localization(::apollo::localization::Pose* localization) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(localization_); + } + if (localization) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + localization = ::google::protobuf::internal::GetOwnedMessage( + message_arena, localization, submessage_arena); + } + + } else { + + } + localization_ = localization; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Gps.localization) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) + +} // namespace localization +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fgps_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/imu.pb.cc b/apollo_msgs/include/apollo_msgs/proto/localization/imu.pb.cc new file mode 100644 index 0000000..6a4ae35 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/imu.pb.cc @@ -0,0 +1,435 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/imu.proto + +#include "apollo_msgs/proto/localization/imu.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto ::google::protobuf::internal::SCCInfo<3> scc_info_Pose; +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto +namespace apollo { +namespace localization { +class ImuDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Imu_default_instance_; +} // namespace localization +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto { +static void InitDefaultsImu() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::localization::_Imu_default_instance_; + new (ptr) ::apollo::localization::Imu(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::localization::Imu::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_Imu = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsImu}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base, + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::scc_info_Pose.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_Imu.base); +} + +::google::protobuf::Metadata file_level_metadata[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Imu, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Imu, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Imu, imu_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::localization::Imu)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::localization::_Imu_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/localization/imu.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 1); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n(apollo_msgs/proto/localization/imu.pro" + "to\022\023apollo.localization\032%apollo_msgs/pro" + "to/common/header.proto\032)apollo_msgs/prot" + "o/localization/pose.proto\"T\n\003Imu\022%\n\006head" + "er\030\001 \001(\0132\025.apollo.common.Header\022&\n\003imu\030\003" + " \001(\0132\031.apollo.localization.Poseb\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 239); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/localization/imu.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto +namespace apollo { +namespace localization { + +// =================================================================== + +void Imu::InitAsDefaultInstance() { + ::apollo::localization::_Imu_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); + ::apollo::localization::_Imu_default_instance_._instance.get_mutable()->imu_ = const_cast< ::apollo::localization::Pose*>( + ::apollo::localization::Pose::internal_default_instance()); +} +void Imu::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +void Imu::clear_imu() { + if (GetArenaNoVirtual() == NULL && imu_ != NULL) { + delete imu_; + } + imu_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Imu::kHeaderFieldNumber; +const int Imu::kImuFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Imu::Imu() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto::scc_info_Imu.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.localization.Imu) +} +Imu::Imu(const Imu& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + if (from.has_imu()) { + imu_ = new ::apollo::localization::Pose(*from.imu_); + } else { + imu_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.localization.Imu) +} + +void Imu::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&imu_) - + reinterpret_cast(&header_)) + sizeof(imu_)); +} + +Imu::~Imu() { + // @@protoc_insertion_point(destructor:apollo.localization.Imu) + SharedDtor(); +} + +void Imu::SharedDtor() { + if (this != internal_default_instance()) delete header_; + if (this != internal_default_instance()) delete imu_; +} + +void Imu::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Imu::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Imu& Imu::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto::scc_info_Imu.base); + return *internal_default_instance(); +} + + +void Imu::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.localization.Imu) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + if (GetArenaNoVirtual() == NULL && imu_ != NULL) { + delete imu_; + } + imu_ = NULL; + _internal_metadata_.Clear(); +} + +bool Imu::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.localization.Imu) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.localization.Pose imu = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_imu())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.localization.Imu) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.localization.Imu) + return false; +#undef DO_ +} + +void Imu::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.localization.Imu) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // .apollo.localization.Pose imu = 3; + if (this->has_imu()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_imu(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.localization.Imu) +} + +::google::protobuf::uint8* Imu::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.localization.Imu) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // .apollo.localization.Pose imu = 3; + if (this->has_imu()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_imu(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.localization.Imu) + return target; +} + +size_t Imu::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.localization.Imu) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.localization.Pose imu = 3; + if (this->has_imu()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *imu_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Imu::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.localization.Imu) + GOOGLE_DCHECK_NE(&from, this); + const Imu* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.localization.Imu) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.localization.Imu) + MergeFrom(*source); + } +} + +void Imu::MergeFrom(const Imu& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.localization.Imu) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.has_imu()) { + mutable_imu()->::apollo::localization::Pose::MergeFrom(from.imu()); + } +} + +void Imu::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.localization.Imu) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Imu::CopyFrom(const Imu& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.localization.Imu) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Imu::IsInitialized() const { + return true; +} + +void Imu::Swap(Imu* other) { + if (other == this) return; + InternalSwap(other); +} +void Imu::InternalSwap(Imu* other) { + using std::swap; + swap(header_, other->header_); + swap(imu_, other->imu_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Imu::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::localization::Imu* Arena::CreateMaybeMessage< ::apollo::localization::Imu >(Arena* arena) { + return Arena::CreateInternal< ::apollo::localization::Imu >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/imu.pb.h b/apollo_msgs/include/apollo_msgs/proto/localization/imu.pb.h new file mode 100644 index 0000000..f69ff12 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/imu.pb.h @@ -0,0 +1,305 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/imu.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include "apollo_msgs/proto/common/header.pb.h" +#include "apollo_msgs/proto/localization/pose.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[1]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto +namespace apollo { +namespace localization { +class Imu; +class ImuDefaultTypeInternal; +extern ImuDefaultTypeInternal _Imu_default_instance_; +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::localization::Imu* Arena::CreateMaybeMessage<::apollo::localization::Imu>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace localization { + +// =================================================================== + +class Imu : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.localization.Imu) */ { + public: + Imu(); + virtual ~Imu(); + + Imu(const Imu& from); + + inline Imu& operator=(const Imu& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Imu(Imu&& from) noexcept + : Imu() { + *this = ::std::move(from); + } + + inline Imu& operator=(Imu&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Imu& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Imu* internal_default_instance() { + return reinterpret_cast( + &_Imu_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(Imu* other); + friend void swap(Imu& a, Imu& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Imu* New() const final { + return CreateMaybeMessage(NULL); + } + + Imu* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Imu& from); + void MergeFrom(const Imu& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Imu* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.localization.Pose imu = 3; + bool has_imu() const; + void clear_imu(); + static const int kImuFieldNumber = 3; + private: + const ::apollo::localization::Pose& _internal_imu() const; + public: + const ::apollo::localization::Pose& imu() const; + ::apollo::localization::Pose* release_imu(); + ::apollo::localization::Pose* mutable_imu(); + void set_allocated_imu(::apollo::localization::Pose* imu); + + // @@protoc_insertion_point(class_scope:apollo.localization.Imu) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::Header* header_; + ::apollo::localization::Pose* imu_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// Imu + +// .apollo.common.Header header = 1; +inline bool Imu::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& Imu::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& Imu::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.localization.Imu.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* Imu::release_header() { + // @@protoc_insertion_point(field_release:apollo.localization.Imu.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* Imu::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Imu.header) + return header_; +} +inline void Imu::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Imu.header) +} + +// .apollo.localization.Pose imu = 3; +inline bool Imu::has_imu() const { + return this != internal_default_instance() && imu_ != NULL; +} +inline const ::apollo::localization::Pose& Imu::_internal_imu() const { + return *imu_; +} +inline const ::apollo::localization::Pose& Imu::imu() const { + const ::apollo::localization::Pose* p = imu_; + // @@protoc_insertion_point(field_get:apollo.localization.Imu.imu) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::localization::_Pose_default_instance_); +} +inline ::apollo::localization::Pose* Imu::release_imu() { + // @@protoc_insertion_point(field_release:apollo.localization.Imu.imu) + + ::apollo::localization::Pose* temp = imu_; + imu_ = NULL; + return temp; +} +inline ::apollo::localization::Pose* Imu::mutable_imu() { + + if (imu_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::localization::Pose>(GetArenaNoVirtual()); + imu_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Imu.imu) + return imu_; +} +inline void Imu::set_allocated_imu(::apollo::localization::Pose* imu) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(imu_); + } + if (imu) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + imu = ::google::protobuf::internal::GetOwnedMessage( + message_arena, imu, submessage_arena); + } + + } else { + + } + imu_ = imu; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Imu.imu) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) + +} // namespace localization +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fimu_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/localization.pb.cc b/apollo_msgs/include/apollo_msgs/proto/localization/localization.pb.cc new file mode 100644 index 0000000..05bf3db --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/localization.pb.cc @@ -0,0 +1,1040 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/localization.proto + +#include "apollo_msgs/proto/localization/localization.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Point3D; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Uncertainty; +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto ::google::protobuf::internal::SCCInfo<3> scc_info_Pose; +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto +namespace apollo { +namespace localization { +class UncertaintyDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Uncertainty_default_instance_; +class LocalizationEstimateDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _LocalizationEstimate_default_instance_; +} // namespace localization +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto { +static void InitDefaultsUncertainty() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::localization::_Uncertainty_default_instance_; + new (ptr) ::apollo::localization::Uncertainty(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::localization::Uncertainty::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_Uncertainty = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsUncertainty}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_Point3D.base,}}; + +static void InitDefaultsLocalizationEstimate() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::localization::_LocalizationEstimate_default_instance_; + new (ptr) ::apollo::localization::LocalizationEstimate(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::localization::LocalizationEstimate::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<3> scc_info_LocalizationEstimate = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 3, InitDefaultsLocalizationEstimate}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base, + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::scc_info_Pose.base, + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::scc_info_Uncertainty.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_Uncertainty.base); + ::google::protobuf::internal::InitSCC(&scc_info_LocalizationEstimate.base); +} + +::google::protobuf::Metadata file_level_metadata[2]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Uncertainty, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Uncertainty, position_std_dev_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Uncertainty, orientation_std_dev_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Uncertainty, linear_velocity_std_dev_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Uncertainty, linear_acceleration_std_dev_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Uncertainty, angular_velocity_std_dev_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::LocalizationEstimate, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::LocalizationEstimate, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::LocalizationEstimate, pose_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::LocalizationEstimate, uncertainty_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::LocalizationEstimate, measurement_time_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::localization::Uncertainty)}, + { 10, -1, sizeof(::apollo::localization::LocalizationEstimate)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::localization::_Uncertainty_default_instance_), + reinterpret_cast(&::apollo::localization::_LocalizationEstimate_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/localization/localization.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 2); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n1apollo_msgs/proto/localization/localiz" + "ation.proto\022\023apollo.localization\032%apollo" + "_msgs/proto/common/header.proto\032)apollo_" + "msgs/proto/localization/pose.proto\032\'apol" + "lo_msgs/proto/common/geometry.proto\"\244\002\n\013" + "Uncertainty\0220\n\020position_std_dev\030\001 \001(\0132\026." + "apollo.common.Point3D\0223\n\023orientation_std" + "_dev\030\002 \001(\0132\026.apollo.common.Point3D\0227\n\027li" + "near_velocity_std_dev\030\003 \001(\0132\026.apollo.com" + "mon.Point3D\022;\n\033linear_acceleration_std_d" + "ev\030\004 \001(\0132\026.apollo.common.Point3D\0228\n\030angu" + "lar_velocity_std_dev\030\005 \001(\0132\026.apollo.comm" + "on.Point3D\"\267\001\n\024LocalizationEstimate\022%\n\006h" + "eader\030\001 \001(\0132\025.apollo.common.Header\022\'\n\004po" + "se\030\002 \001(\0132\031.apollo.localization.Pose\0225\n\013u" + "ncertainty\030\003 \001(\0132 .apollo.localization.U" + "ncertainty\022\030\n\020measurement_time\030\004 \001(\001b\006pr" + "oto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 684); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/localization/localization.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto +namespace apollo { +namespace localization { + +// =================================================================== + +void Uncertainty::InitAsDefaultInstance() { + ::apollo::localization::_Uncertainty_default_instance_._instance.get_mutable()->position_std_dev_ = const_cast< ::apollo::common::Point3D*>( + ::apollo::common::Point3D::internal_default_instance()); + ::apollo::localization::_Uncertainty_default_instance_._instance.get_mutable()->orientation_std_dev_ = const_cast< ::apollo::common::Point3D*>( + ::apollo::common::Point3D::internal_default_instance()); + ::apollo::localization::_Uncertainty_default_instance_._instance.get_mutable()->linear_velocity_std_dev_ = const_cast< ::apollo::common::Point3D*>( + ::apollo::common::Point3D::internal_default_instance()); + ::apollo::localization::_Uncertainty_default_instance_._instance.get_mutable()->linear_acceleration_std_dev_ = const_cast< ::apollo::common::Point3D*>( + ::apollo::common::Point3D::internal_default_instance()); + ::apollo::localization::_Uncertainty_default_instance_._instance.get_mutable()->angular_velocity_std_dev_ = const_cast< ::apollo::common::Point3D*>( + ::apollo::common::Point3D::internal_default_instance()); +} +void Uncertainty::clear_position_std_dev() { + if (GetArenaNoVirtual() == NULL && position_std_dev_ != NULL) { + delete position_std_dev_; + } + position_std_dev_ = NULL; +} +void Uncertainty::clear_orientation_std_dev() { + if (GetArenaNoVirtual() == NULL && orientation_std_dev_ != NULL) { + delete orientation_std_dev_; + } + orientation_std_dev_ = NULL; +} +void Uncertainty::clear_linear_velocity_std_dev() { + if (GetArenaNoVirtual() == NULL && linear_velocity_std_dev_ != NULL) { + delete linear_velocity_std_dev_; + } + linear_velocity_std_dev_ = NULL; +} +void Uncertainty::clear_linear_acceleration_std_dev() { + if (GetArenaNoVirtual() == NULL && linear_acceleration_std_dev_ != NULL) { + delete linear_acceleration_std_dev_; + } + linear_acceleration_std_dev_ = NULL; +} +void Uncertainty::clear_angular_velocity_std_dev() { + if (GetArenaNoVirtual() == NULL && angular_velocity_std_dev_ != NULL) { + delete angular_velocity_std_dev_; + } + angular_velocity_std_dev_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Uncertainty::kPositionStdDevFieldNumber; +const int Uncertainty::kOrientationStdDevFieldNumber; +const int Uncertainty::kLinearVelocityStdDevFieldNumber; +const int Uncertainty::kLinearAccelerationStdDevFieldNumber; +const int Uncertainty::kAngularVelocityStdDevFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Uncertainty::Uncertainty() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::scc_info_Uncertainty.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.localization.Uncertainty) +} +Uncertainty::Uncertainty(const Uncertainty& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_position_std_dev()) { + position_std_dev_ = new ::apollo::common::Point3D(*from.position_std_dev_); + } else { + position_std_dev_ = NULL; + } + if (from.has_orientation_std_dev()) { + orientation_std_dev_ = new ::apollo::common::Point3D(*from.orientation_std_dev_); + } else { + orientation_std_dev_ = NULL; + } + if (from.has_linear_velocity_std_dev()) { + linear_velocity_std_dev_ = new ::apollo::common::Point3D(*from.linear_velocity_std_dev_); + } else { + linear_velocity_std_dev_ = NULL; + } + if (from.has_linear_acceleration_std_dev()) { + linear_acceleration_std_dev_ = new ::apollo::common::Point3D(*from.linear_acceleration_std_dev_); + } else { + linear_acceleration_std_dev_ = NULL; + } + if (from.has_angular_velocity_std_dev()) { + angular_velocity_std_dev_ = new ::apollo::common::Point3D(*from.angular_velocity_std_dev_); + } else { + angular_velocity_std_dev_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.localization.Uncertainty) +} + +void Uncertainty::SharedCtor() { + ::memset(&position_std_dev_, 0, static_cast( + reinterpret_cast(&angular_velocity_std_dev_) - + reinterpret_cast(&position_std_dev_)) + sizeof(angular_velocity_std_dev_)); +} + +Uncertainty::~Uncertainty() { + // @@protoc_insertion_point(destructor:apollo.localization.Uncertainty) + SharedDtor(); +} + +void Uncertainty::SharedDtor() { + if (this != internal_default_instance()) delete position_std_dev_; + if (this != internal_default_instance()) delete orientation_std_dev_; + if (this != internal_default_instance()) delete linear_velocity_std_dev_; + if (this != internal_default_instance()) delete linear_acceleration_std_dev_; + if (this != internal_default_instance()) delete angular_velocity_std_dev_; +} + +void Uncertainty::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Uncertainty::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Uncertainty& Uncertainty::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::scc_info_Uncertainty.base); + return *internal_default_instance(); +} + + +void Uncertainty::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.localization.Uncertainty) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && position_std_dev_ != NULL) { + delete position_std_dev_; + } + position_std_dev_ = NULL; + if (GetArenaNoVirtual() == NULL && orientation_std_dev_ != NULL) { + delete orientation_std_dev_; + } + orientation_std_dev_ = NULL; + if (GetArenaNoVirtual() == NULL && linear_velocity_std_dev_ != NULL) { + delete linear_velocity_std_dev_; + } + linear_velocity_std_dev_ = NULL; + if (GetArenaNoVirtual() == NULL && linear_acceleration_std_dev_ != NULL) { + delete linear_acceleration_std_dev_; + } + linear_acceleration_std_dev_ = NULL; + if (GetArenaNoVirtual() == NULL && angular_velocity_std_dev_ != NULL) { + delete angular_velocity_std_dev_; + } + angular_velocity_std_dev_ = NULL; + _internal_metadata_.Clear(); +} + +bool Uncertainty::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.localization.Uncertainty) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Point3D position_std_dev = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_position_std_dev())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Point3D orientation_std_dev = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_orientation_std_dev())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Point3D linear_velocity_std_dev = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_linear_velocity_std_dev())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Point3D linear_acceleration_std_dev = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_linear_acceleration_std_dev())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Point3D angular_velocity_std_dev = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_angular_velocity_std_dev())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.localization.Uncertainty) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.localization.Uncertainty) + return false; +#undef DO_ +} + +void Uncertainty::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.localization.Uncertainty) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Point3D position_std_dev = 1; + if (this->has_position_std_dev()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_position_std_dev(), output); + } + + // .apollo.common.Point3D orientation_std_dev = 2; + if (this->has_orientation_std_dev()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_orientation_std_dev(), output); + } + + // .apollo.common.Point3D linear_velocity_std_dev = 3; + if (this->has_linear_velocity_std_dev()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_linear_velocity_std_dev(), output); + } + + // .apollo.common.Point3D linear_acceleration_std_dev = 4; + if (this->has_linear_acceleration_std_dev()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, this->_internal_linear_acceleration_std_dev(), output); + } + + // .apollo.common.Point3D angular_velocity_std_dev = 5; + if (this->has_angular_velocity_std_dev()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, this->_internal_angular_velocity_std_dev(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.localization.Uncertainty) +} + +::google::protobuf::uint8* Uncertainty::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.localization.Uncertainty) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Point3D position_std_dev = 1; + if (this->has_position_std_dev()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_position_std_dev(), deterministic, target); + } + + // .apollo.common.Point3D orientation_std_dev = 2; + if (this->has_orientation_std_dev()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_orientation_std_dev(), deterministic, target); + } + + // .apollo.common.Point3D linear_velocity_std_dev = 3; + if (this->has_linear_velocity_std_dev()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_linear_velocity_std_dev(), deterministic, target); + } + + // .apollo.common.Point3D linear_acceleration_std_dev = 4; + if (this->has_linear_acceleration_std_dev()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->_internal_linear_acceleration_std_dev(), deterministic, target); + } + + // .apollo.common.Point3D angular_velocity_std_dev = 5; + if (this->has_angular_velocity_std_dev()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 5, this->_internal_angular_velocity_std_dev(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.localization.Uncertainty) + return target; +} + +size_t Uncertainty::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.localization.Uncertainty) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.Point3D position_std_dev = 1; + if (this->has_position_std_dev()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *position_std_dev_); + } + + // .apollo.common.Point3D orientation_std_dev = 2; + if (this->has_orientation_std_dev()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *orientation_std_dev_); + } + + // .apollo.common.Point3D linear_velocity_std_dev = 3; + if (this->has_linear_velocity_std_dev()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *linear_velocity_std_dev_); + } + + // .apollo.common.Point3D linear_acceleration_std_dev = 4; + if (this->has_linear_acceleration_std_dev()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *linear_acceleration_std_dev_); + } + + // .apollo.common.Point3D angular_velocity_std_dev = 5; + if (this->has_angular_velocity_std_dev()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *angular_velocity_std_dev_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Uncertainty::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.localization.Uncertainty) + GOOGLE_DCHECK_NE(&from, this); + const Uncertainty* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.localization.Uncertainty) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.localization.Uncertainty) + MergeFrom(*source); + } +} + +void Uncertainty::MergeFrom(const Uncertainty& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.localization.Uncertainty) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_position_std_dev()) { + mutable_position_std_dev()->::apollo::common::Point3D::MergeFrom(from.position_std_dev()); + } + if (from.has_orientation_std_dev()) { + mutable_orientation_std_dev()->::apollo::common::Point3D::MergeFrom(from.orientation_std_dev()); + } + if (from.has_linear_velocity_std_dev()) { + mutable_linear_velocity_std_dev()->::apollo::common::Point3D::MergeFrom(from.linear_velocity_std_dev()); + } + if (from.has_linear_acceleration_std_dev()) { + mutable_linear_acceleration_std_dev()->::apollo::common::Point3D::MergeFrom(from.linear_acceleration_std_dev()); + } + if (from.has_angular_velocity_std_dev()) { + mutable_angular_velocity_std_dev()->::apollo::common::Point3D::MergeFrom(from.angular_velocity_std_dev()); + } +} + +void Uncertainty::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.localization.Uncertainty) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Uncertainty::CopyFrom(const Uncertainty& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.localization.Uncertainty) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Uncertainty::IsInitialized() const { + return true; +} + +void Uncertainty::Swap(Uncertainty* other) { + if (other == this) return; + InternalSwap(other); +} +void Uncertainty::InternalSwap(Uncertainty* other) { + using std::swap; + swap(position_std_dev_, other->position_std_dev_); + swap(orientation_std_dev_, other->orientation_std_dev_); + swap(linear_velocity_std_dev_, other->linear_velocity_std_dev_); + swap(linear_acceleration_std_dev_, other->linear_acceleration_std_dev_); + swap(angular_velocity_std_dev_, other->angular_velocity_std_dev_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Uncertainty::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void LocalizationEstimate::InitAsDefaultInstance() { + ::apollo::localization::_LocalizationEstimate_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); + ::apollo::localization::_LocalizationEstimate_default_instance_._instance.get_mutable()->pose_ = const_cast< ::apollo::localization::Pose*>( + ::apollo::localization::Pose::internal_default_instance()); + ::apollo::localization::_LocalizationEstimate_default_instance_._instance.get_mutable()->uncertainty_ = const_cast< ::apollo::localization::Uncertainty*>( + ::apollo::localization::Uncertainty::internal_default_instance()); +} +void LocalizationEstimate::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +void LocalizationEstimate::clear_pose() { + if (GetArenaNoVirtual() == NULL && pose_ != NULL) { + delete pose_; + } + pose_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int LocalizationEstimate::kHeaderFieldNumber; +const int LocalizationEstimate::kPoseFieldNumber; +const int LocalizationEstimate::kUncertaintyFieldNumber; +const int LocalizationEstimate::kMeasurementTimeFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +LocalizationEstimate::LocalizationEstimate() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::scc_info_LocalizationEstimate.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.localization.LocalizationEstimate) +} +LocalizationEstimate::LocalizationEstimate(const LocalizationEstimate& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + if (from.has_pose()) { + pose_ = new ::apollo::localization::Pose(*from.pose_); + } else { + pose_ = NULL; + } + if (from.has_uncertainty()) { + uncertainty_ = new ::apollo::localization::Uncertainty(*from.uncertainty_); + } else { + uncertainty_ = NULL; + } + measurement_time_ = from.measurement_time_; + // @@protoc_insertion_point(copy_constructor:apollo.localization.LocalizationEstimate) +} + +void LocalizationEstimate::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&measurement_time_) - + reinterpret_cast(&header_)) + sizeof(measurement_time_)); +} + +LocalizationEstimate::~LocalizationEstimate() { + // @@protoc_insertion_point(destructor:apollo.localization.LocalizationEstimate) + SharedDtor(); +} + +void LocalizationEstimate::SharedDtor() { + if (this != internal_default_instance()) delete header_; + if (this != internal_default_instance()) delete pose_; + if (this != internal_default_instance()) delete uncertainty_; +} + +void LocalizationEstimate::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* LocalizationEstimate::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const LocalizationEstimate& LocalizationEstimate::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::scc_info_LocalizationEstimate.base); + return *internal_default_instance(); +} + + +void LocalizationEstimate::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.localization.LocalizationEstimate) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + if (GetArenaNoVirtual() == NULL && pose_ != NULL) { + delete pose_; + } + pose_ = NULL; + if (GetArenaNoVirtual() == NULL && uncertainty_ != NULL) { + delete uncertainty_; + } + uncertainty_ = NULL; + measurement_time_ = 0; + _internal_metadata_.Clear(); +} + +bool LocalizationEstimate::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.localization.LocalizationEstimate) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.localization.Pose pose = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_pose())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.localization.Uncertainty uncertainty = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_uncertainty())); + } else { + goto handle_unusual; + } + break; + } + + // double measurement_time = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &measurement_time_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.localization.LocalizationEstimate) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.localization.LocalizationEstimate) + return false; +#undef DO_ +} + +void LocalizationEstimate::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.localization.LocalizationEstimate) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // .apollo.localization.Pose pose = 2; + if (this->has_pose()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_pose(), output); + } + + // .apollo.localization.Uncertainty uncertainty = 3; + if (this->has_uncertainty()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_uncertainty(), output); + } + + // double measurement_time = 4; + if (this->measurement_time() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->measurement_time(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.localization.LocalizationEstimate) +} + +::google::protobuf::uint8* LocalizationEstimate::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.localization.LocalizationEstimate) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // .apollo.localization.Pose pose = 2; + if (this->has_pose()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_pose(), deterministic, target); + } + + // .apollo.localization.Uncertainty uncertainty = 3; + if (this->has_uncertainty()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_uncertainty(), deterministic, target); + } + + // double measurement_time = 4; + if (this->measurement_time() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->measurement_time(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.localization.LocalizationEstimate) + return target; +} + +size_t LocalizationEstimate::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.localization.LocalizationEstimate) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.localization.Pose pose = 2; + if (this->has_pose()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *pose_); + } + + // .apollo.localization.Uncertainty uncertainty = 3; + if (this->has_uncertainty()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *uncertainty_); + } + + // double measurement_time = 4; + if (this->measurement_time() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void LocalizationEstimate::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.localization.LocalizationEstimate) + GOOGLE_DCHECK_NE(&from, this); + const LocalizationEstimate* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.localization.LocalizationEstimate) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.localization.LocalizationEstimate) + MergeFrom(*source); + } +} + +void LocalizationEstimate::MergeFrom(const LocalizationEstimate& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.localization.LocalizationEstimate) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.has_pose()) { + mutable_pose()->::apollo::localization::Pose::MergeFrom(from.pose()); + } + if (from.has_uncertainty()) { + mutable_uncertainty()->::apollo::localization::Uncertainty::MergeFrom(from.uncertainty()); + } + if (from.measurement_time() != 0) { + set_measurement_time(from.measurement_time()); + } +} + +void LocalizationEstimate::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.localization.LocalizationEstimate) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void LocalizationEstimate::CopyFrom(const LocalizationEstimate& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.localization.LocalizationEstimate) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool LocalizationEstimate::IsInitialized() const { + return true; +} + +void LocalizationEstimate::Swap(LocalizationEstimate* other) { + if (other == this) return; + InternalSwap(other); +} +void LocalizationEstimate::InternalSwap(LocalizationEstimate* other) { + using std::swap; + swap(header_, other->header_); + swap(pose_, other->pose_); + swap(uncertainty_, other->uncertainty_); + swap(measurement_time_, other->measurement_time_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata LocalizationEstimate::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::localization::Uncertainty* Arena::CreateMaybeMessage< ::apollo::localization::Uncertainty >(Arena* arena) { + return Arena::CreateInternal< ::apollo::localization::Uncertainty >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::localization::LocalizationEstimate* Arena::CreateMaybeMessage< ::apollo::localization::LocalizationEstimate >(Arena* arena) { + return Arena::CreateInternal< ::apollo::localization::LocalizationEstimate >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/localization.pb.h b/apollo_msgs/include/apollo_msgs/proto/localization/localization.pb.h new file mode 100644 index 0000000..462d7a4 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/localization.pb.h @@ -0,0 +1,805 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/localization.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include "apollo_msgs/proto/common/header.pb.h" +#include "apollo_msgs/proto/localization/pose.pb.h" +#include "apollo_msgs/proto/common/geometry.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[2]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto +namespace apollo { +namespace localization { +class LocalizationEstimate; +class LocalizationEstimateDefaultTypeInternal; +extern LocalizationEstimateDefaultTypeInternal _LocalizationEstimate_default_instance_; +class Uncertainty; +class UncertaintyDefaultTypeInternal; +extern UncertaintyDefaultTypeInternal _Uncertainty_default_instance_; +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::localization::LocalizationEstimate* Arena::CreateMaybeMessage<::apollo::localization::LocalizationEstimate>(Arena*); +template<> ::apollo::localization::Uncertainty* Arena::CreateMaybeMessage<::apollo::localization::Uncertainty>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace localization { + +// =================================================================== + +class Uncertainty : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.localization.Uncertainty) */ { + public: + Uncertainty(); + virtual ~Uncertainty(); + + Uncertainty(const Uncertainty& from); + + inline Uncertainty& operator=(const Uncertainty& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Uncertainty(Uncertainty&& from) noexcept + : Uncertainty() { + *this = ::std::move(from); + } + + inline Uncertainty& operator=(Uncertainty&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Uncertainty& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Uncertainty* internal_default_instance() { + return reinterpret_cast( + &_Uncertainty_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(Uncertainty* other); + friend void swap(Uncertainty& a, Uncertainty& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Uncertainty* New() const final { + return CreateMaybeMessage(NULL); + } + + Uncertainty* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Uncertainty& from); + void MergeFrom(const Uncertainty& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Uncertainty* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.common.Point3D position_std_dev = 1; + bool has_position_std_dev() const; + void clear_position_std_dev(); + static const int kPositionStdDevFieldNumber = 1; + private: + const ::apollo::common::Point3D& _internal_position_std_dev() const; + public: + const ::apollo::common::Point3D& position_std_dev() const; + ::apollo::common::Point3D* release_position_std_dev(); + ::apollo::common::Point3D* mutable_position_std_dev(); + void set_allocated_position_std_dev(::apollo::common::Point3D* position_std_dev); + + // .apollo.common.Point3D orientation_std_dev = 2; + bool has_orientation_std_dev() const; + void clear_orientation_std_dev(); + static const int kOrientationStdDevFieldNumber = 2; + private: + const ::apollo::common::Point3D& _internal_orientation_std_dev() const; + public: + const ::apollo::common::Point3D& orientation_std_dev() const; + ::apollo::common::Point3D* release_orientation_std_dev(); + ::apollo::common::Point3D* mutable_orientation_std_dev(); + void set_allocated_orientation_std_dev(::apollo::common::Point3D* orientation_std_dev); + + // .apollo.common.Point3D linear_velocity_std_dev = 3; + bool has_linear_velocity_std_dev() const; + void clear_linear_velocity_std_dev(); + static const int kLinearVelocityStdDevFieldNumber = 3; + private: + const ::apollo::common::Point3D& _internal_linear_velocity_std_dev() const; + public: + const ::apollo::common::Point3D& linear_velocity_std_dev() const; + ::apollo::common::Point3D* release_linear_velocity_std_dev(); + ::apollo::common::Point3D* mutable_linear_velocity_std_dev(); + void set_allocated_linear_velocity_std_dev(::apollo::common::Point3D* linear_velocity_std_dev); + + // .apollo.common.Point3D linear_acceleration_std_dev = 4; + bool has_linear_acceleration_std_dev() const; + void clear_linear_acceleration_std_dev(); + static const int kLinearAccelerationStdDevFieldNumber = 4; + private: + const ::apollo::common::Point3D& _internal_linear_acceleration_std_dev() const; + public: + const ::apollo::common::Point3D& linear_acceleration_std_dev() const; + ::apollo::common::Point3D* release_linear_acceleration_std_dev(); + ::apollo::common::Point3D* mutable_linear_acceleration_std_dev(); + void set_allocated_linear_acceleration_std_dev(::apollo::common::Point3D* linear_acceleration_std_dev); + + // .apollo.common.Point3D angular_velocity_std_dev = 5; + bool has_angular_velocity_std_dev() const; + void clear_angular_velocity_std_dev(); + static const int kAngularVelocityStdDevFieldNumber = 5; + private: + const ::apollo::common::Point3D& _internal_angular_velocity_std_dev() const; + public: + const ::apollo::common::Point3D& angular_velocity_std_dev() const; + ::apollo::common::Point3D* release_angular_velocity_std_dev(); + ::apollo::common::Point3D* mutable_angular_velocity_std_dev(); + void set_allocated_angular_velocity_std_dev(::apollo::common::Point3D* angular_velocity_std_dev); + + // @@protoc_insertion_point(class_scope:apollo.localization.Uncertainty) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::Point3D* position_std_dev_; + ::apollo::common::Point3D* orientation_std_dev_; + ::apollo::common::Point3D* linear_velocity_std_dev_; + ::apollo::common::Point3D* linear_acceleration_std_dev_; + ::apollo::common::Point3D* angular_velocity_std_dev_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class LocalizationEstimate : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.localization.LocalizationEstimate) */ { + public: + LocalizationEstimate(); + virtual ~LocalizationEstimate(); + + LocalizationEstimate(const LocalizationEstimate& from); + + inline LocalizationEstimate& operator=(const LocalizationEstimate& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + LocalizationEstimate(LocalizationEstimate&& from) noexcept + : LocalizationEstimate() { + *this = ::std::move(from); + } + + inline LocalizationEstimate& operator=(LocalizationEstimate&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const LocalizationEstimate& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const LocalizationEstimate* internal_default_instance() { + return reinterpret_cast( + &_LocalizationEstimate_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(LocalizationEstimate* other); + friend void swap(LocalizationEstimate& a, LocalizationEstimate& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline LocalizationEstimate* New() const final { + return CreateMaybeMessage(NULL); + } + + LocalizationEstimate* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const LocalizationEstimate& from); + void MergeFrom(const LocalizationEstimate& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(LocalizationEstimate* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.localization.Pose pose = 2; + bool has_pose() const; + void clear_pose(); + static const int kPoseFieldNumber = 2; + private: + const ::apollo::localization::Pose& _internal_pose() const; + public: + const ::apollo::localization::Pose& pose() const; + ::apollo::localization::Pose* release_pose(); + ::apollo::localization::Pose* mutable_pose(); + void set_allocated_pose(::apollo::localization::Pose* pose); + + // .apollo.localization.Uncertainty uncertainty = 3; + bool has_uncertainty() const; + void clear_uncertainty(); + static const int kUncertaintyFieldNumber = 3; + private: + const ::apollo::localization::Uncertainty& _internal_uncertainty() const; + public: + const ::apollo::localization::Uncertainty& uncertainty() const; + ::apollo::localization::Uncertainty* release_uncertainty(); + ::apollo::localization::Uncertainty* mutable_uncertainty(); + void set_allocated_uncertainty(::apollo::localization::Uncertainty* uncertainty); + + // double measurement_time = 4; + void clear_measurement_time(); + static const int kMeasurementTimeFieldNumber = 4; + double measurement_time() const; + void set_measurement_time(double value); + + // @@protoc_insertion_point(class_scope:apollo.localization.LocalizationEstimate) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::Header* header_; + ::apollo::localization::Pose* pose_; + ::apollo::localization::Uncertainty* uncertainty_; + double measurement_time_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// Uncertainty + +// .apollo.common.Point3D position_std_dev = 1; +inline bool Uncertainty::has_position_std_dev() const { + return this != internal_default_instance() && position_std_dev_ != NULL; +} +inline const ::apollo::common::Point3D& Uncertainty::_internal_position_std_dev() const { + return *position_std_dev_; +} +inline const ::apollo::common::Point3D& Uncertainty::position_std_dev() const { + const ::apollo::common::Point3D* p = position_std_dev_; + // @@protoc_insertion_point(field_get:apollo.localization.Uncertainty.position_std_dev) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Point3D_default_instance_); +} +inline ::apollo::common::Point3D* Uncertainty::release_position_std_dev() { + // @@protoc_insertion_point(field_release:apollo.localization.Uncertainty.position_std_dev) + + ::apollo::common::Point3D* temp = position_std_dev_; + position_std_dev_ = NULL; + return temp; +} +inline ::apollo::common::Point3D* Uncertainty::mutable_position_std_dev() { + + if (position_std_dev_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Point3D>(GetArenaNoVirtual()); + position_std_dev_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Uncertainty.position_std_dev) + return position_std_dev_; +} +inline void Uncertainty::set_allocated_position_std_dev(::apollo::common::Point3D* position_std_dev) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(position_std_dev_); + } + if (position_std_dev) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + position_std_dev = ::google::protobuf::internal::GetOwnedMessage( + message_arena, position_std_dev, submessage_arena); + } + + } else { + + } + position_std_dev_ = position_std_dev; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Uncertainty.position_std_dev) +} + +// .apollo.common.Point3D orientation_std_dev = 2; +inline bool Uncertainty::has_orientation_std_dev() const { + return this != internal_default_instance() && orientation_std_dev_ != NULL; +} +inline const ::apollo::common::Point3D& Uncertainty::_internal_orientation_std_dev() const { + return *orientation_std_dev_; +} +inline const ::apollo::common::Point3D& Uncertainty::orientation_std_dev() const { + const ::apollo::common::Point3D* p = orientation_std_dev_; + // @@protoc_insertion_point(field_get:apollo.localization.Uncertainty.orientation_std_dev) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Point3D_default_instance_); +} +inline ::apollo::common::Point3D* Uncertainty::release_orientation_std_dev() { + // @@protoc_insertion_point(field_release:apollo.localization.Uncertainty.orientation_std_dev) + + ::apollo::common::Point3D* temp = orientation_std_dev_; + orientation_std_dev_ = NULL; + return temp; +} +inline ::apollo::common::Point3D* Uncertainty::mutable_orientation_std_dev() { + + if (orientation_std_dev_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Point3D>(GetArenaNoVirtual()); + orientation_std_dev_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Uncertainty.orientation_std_dev) + return orientation_std_dev_; +} +inline void Uncertainty::set_allocated_orientation_std_dev(::apollo::common::Point3D* orientation_std_dev) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(orientation_std_dev_); + } + if (orientation_std_dev) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + orientation_std_dev = ::google::protobuf::internal::GetOwnedMessage( + message_arena, orientation_std_dev, submessage_arena); + } + + } else { + + } + orientation_std_dev_ = orientation_std_dev; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Uncertainty.orientation_std_dev) +} + +// .apollo.common.Point3D linear_velocity_std_dev = 3; +inline bool Uncertainty::has_linear_velocity_std_dev() const { + return this != internal_default_instance() && linear_velocity_std_dev_ != NULL; +} +inline const ::apollo::common::Point3D& Uncertainty::_internal_linear_velocity_std_dev() const { + return *linear_velocity_std_dev_; +} +inline const ::apollo::common::Point3D& Uncertainty::linear_velocity_std_dev() const { + const ::apollo::common::Point3D* p = linear_velocity_std_dev_; + // @@protoc_insertion_point(field_get:apollo.localization.Uncertainty.linear_velocity_std_dev) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Point3D_default_instance_); +} +inline ::apollo::common::Point3D* Uncertainty::release_linear_velocity_std_dev() { + // @@protoc_insertion_point(field_release:apollo.localization.Uncertainty.linear_velocity_std_dev) + + ::apollo::common::Point3D* temp = linear_velocity_std_dev_; + linear_velocity_std_dev_ = NULL; + return temp; +} +inline ::apollo::common::Point3D* Uncertainty::mutable_linear_velocity_std_dev() { + + if (linear_velocity_std_dev_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Point3D>(GetArenaNoVirtual()); + linear_velocity_std_dev_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Uncertainty.linear_velocity_std_dev) + return linear_velocity_std_dev_; +} +inline void Uncertainty::set_allocated_linear_velocity_std_dev(::apollo::common::Point3D* linear_velocity_std_dev) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(linear_velocity_std_dev_); + } + if (linear_velocity_std_dev) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + linear_velocity_std_dev = ::google::protobuf::internal::GetOwnedMessage( + message_arena, linear_velocity_std_dev, submessage_arena); + } + + } else { + + } + linear_velocity_std_dev_ = linear_velocity_std_dev; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Uncertainty.linear_velocity_std_dev) +} + +// .apollo.common.Point3D linear_acceleration_std_dev = 4; +inline bool Uncertainty::has_linear_acceleration_std_dev() const { + return this != internal_default_instance() && linear_acceleration_std_dev_ != NULL; +} +inline const ::apollo::common::Point3D& Uncertainty::_internal_linear_acceleration_std_dev() const { + return *linear_acceleration_std_dev_; +} +inline const ::apollo::common::Point3D& Uncertainty::linear_acceleration_std_dev() const { + const ::apollo::common::Point3D* p = linear_acceleration_std_dev_; + // @@protoc_insertion_point(field_get:apollo.localization.Uncertainty.linear_acceleration_std_dev) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Point3D_default_instance_); +} +inline ::apollo::common::Point3D* Uncertainty::release_linear_acceleration_std_dev() { + // @@protoc_insertion_point(field_release:apollo.localization.Uncertainty.linear_acceleration_std_dev) + + ::apollo::common::Point3D* temp = linear_acceleration_std_dev_; + linear_acceleration_std_dev_ = NULL; + return temp; +} +inline ::apollo::common::Point3D* Uncertainty::mutable_linear_acceleration_std_dev() { + + if (linear_acceleration_std_dev_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Point3D>(GetArenaNoVirtual()); + linear_acceleration_std_dev_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Uncertainty.linear_acceleration_std_dev) + return linear_acceleration_std_dev_; +} +inline void Uncertainty::set_allocated_linear_acceleration_std_dev(::apollo::common::Point3D* linear_acceleration_std_dev) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(linear_acceleration_std_dev_); + } + if (linear_acceleration_std_dev) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + linear_acceleration_std_dev = ::google::protobuf::internal::GetOwnedMessage( + message_arena, linear_acceleration_std_dev, submessage_arena); + } + + } else { + + } + linear_acceleration_std_dev_ = linear_acceleration_std_dev; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Uncertainty.linear_acceleration_std_dev) +} + +// .apollo.common.Point3D angular_velocity_std_dev = 5; +inline bool Uncertainty::has_angular_velocity_std_dev() const { + return this != internal_default_instance() && angular_velocity_std_dev_ != NULL; +} +inline const ::apollo::common::Point3D& Uncertainty::_internal_angular_velocity_std_dev() const { + return *angular_velocity_std_dev_; +} +inline const ::apollo::common::Point3D& Uncertainty::angular_velocity_std_dev() const { + const ::apollo::common::Point3D* p = angular_velocity_std_dev_; + // @@protoc_insertion_point(field_get:apollo.localization.Uncertainty.angular_velocity_std_dev) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Point3D_default_instance_); +} +inline ::apollo::common::Point3D* Uncertainty::release_angular_velocity_std_dev() { + // @@protoc_insertion_point(field_release:apollo.localization.Uncertainty.angular_velocity_std_dev) + + ::apollo::common::Point3D* temp = angular_velocity_std_dev_; + angular_velocity_std_dev_ = NULL; + return temp; +} +inline ::apollo::common::Point3D* Uncertainty::mutable_angular_velocity_std_dev() { + + if (angular_velocity_std_dev_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Point3D>(GetArenaNoVirtual()); + angular_velocity_std_dev_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Uncertainty.angular_velocity_std_dev) + return angular_velocity_std_dev_; +} +inline void Uncertainty::set_allocated_angular_velocity_std_dev(::apollo::common::Point3D* angular_velocity_std_dev) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(angular_velocity_std_dev_); + } + if (angular_velocity_std_dev) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + angular_velocity_std_dev = ::google::protobuf::internal::GetOwnedMessage( + message_arena, angular_velocity_std_dev, submessage_arena); + } + + } else { + + } + angular_velocity_std_dev_ = angular_velocity_std_dev; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Uncertainty.angular_velocity_std_dev) +} + +// ------------------------------------------------------------------- + +// LocalizationEstimate + +// .apollo.common.Header header = 1; +inline bool LocalizationEstimate::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& LocalizationEstimate::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& LocalizationEstimate::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.localization.LocalizationEstimate.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* LocalizationEstimate::release_header() { + // @@protoc_insertion_point(field_release:apollo.localization.LocalizationEstimate.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* LocalizationEstimate::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.LocalizationEstimate.header) + return header_; +} +inline void LocalizationEstimate::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.LocalizationEstimate.header) +} + +// .apollo.localization.Pose pose = 2; +inline bool LocalizationEstimate::has_pose() const { + return this != internal_default_instance() && pose_ != NULL; +} +inline const ::apollo::localization::Pose& LocalizationEstimate::_internal_pose() const { + return *pose_; +} +inline const ::apollo::localization::Pose& LocalizationEstimate::pose() const { + const ::apollo::localization::Pose* p = pose_; + // @@protoc_insertion_point(field_get:apollo.localization.LocalizationEstimate.pose) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::localization::_Pose_default_instance_); +} +inline ::apollo::localization::Pose* LocalizationEstimate::release_pose() { + // @@protoc_insertion_point(field_release:apollo.localization.LocalizationEstimate.pose) + + ::apollo::localization::Pose* temp = pose_; + pose_ = NULL; + return temp; +} +inline ::apollo::localization::Pose* LocalizationEstimate::mutable_pose() { + + if (pose_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::localization::Pose>(GetArenaNoVirtual()); + pose_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.LocalizationEstimate.pose) + return pose_; +} +inline void LocalizationEstimate::set_allocated_pose(::apollo::localization::Pose* pose) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(pose_); + } + if (pose) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + pose = ::google::protobuf::internal::GetOwnedMessage( + message_arena, pose, submessage_arena); + } + + } else { + + } + pose_ = pose; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.LocalizationEstimate.pose) +} + +// .apollo.localization.Uncertainty uncertainty = 3; +inline bool LocalizationEstimate::has_uncertainty() const { + return this != internal_default_instance() && uncertainty_ != NULL; +} +inline void LocalizationEstimate::clear_uncertainty() { + if (GetArenaNoVirtual() == NULL && uncertainty_ != NULL) { + delete uncertainty_; + } + uncertainty_ = NULL; +} +inline const ::apollo::localization::Uncertainty& LocalizationEstimate::_internal_uncertainty() const { + return *uncertainty_; +} +inline const ::apollo::localization::Uncertainty& LocalizationEstimate::uncertainty() const { + const ::apollo::localization::Uncertainty* p = uncertainty_; + // @@protoc_insertion_point(field_get:apollo.localization.LocalizationEstimate.uncertainty) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::localization::_Uncertainty_default_instance_); +} +inline ::apollo::localization::Uncertainty* LocalizationEstimate::release_uncertainty() { + // @@protoc_insertion_point(field_release:apollo.localization.LocalizationEstimate.uncertainty) + + ::apollo::localization::Uncertainty* temp = uncertainty_; + uncertainty_ = NULL; + return temp; +} +inline ::apollo::localization::Uncertainty* LocalizationEstimate::mutable_uncertainty() { + + if (uncertainty_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::localization::Uncertainty>(GetArenaNoVirtual()); + uncertainty_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.LocalizationEstimate.uncertainty) + return uncertainty_; +} +inline void LocalizationEstimate::set_allocated_uncertainty(::apollo::localization::Uncertainty* uncertainty) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete uncertainty_; + } + if (uncertainty) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + uncertainty = ::google::protobuf::internal::GetOwnedMessage( + message_arena, uncertainty, submessage_arena); + } + + } else { + + } + uncertainty_ = uncertainty; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.LocalizationEstimate.uncertainty) +} + +// double measurement_time = 4; +inline void LocalizationEstimate::clear_measurement_time() { + measurement_time_ = 0; +} +inline double LocalizationEstimate::measurement_time() const { + // @@protoc_insertion_point(field_get:apollo.localization.LocalizationEstimate.measurement_time) + return measurement_time_; +} +inline void LocalizationEstimate::set_measurement_time(double value) { + + measurement_time_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.LocalizationEstimate.measurement_time) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace localization +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/localization_config.pb.cc b/apollo_msgs/include/apollo_msgs/proto/localization/localization_config.pb.cc new file mode 100644 index 0000000..dede23a --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/localization_config.pb.cc @@ -0,0 +1,374 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/localization_config.proto + +#include "apollo_msgs/proto/localization/localization_config.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace apollo { +namespace localization { +class LocalizationConfigDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _LocalizationConfig_default_instance_; +} // namespace localization +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto { +static void InitDefaultsLocalizationConfig() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::localization::_LocalizationConfig_default_instance_; + new (ptr) ::apollo::localization::LocalizationConfig(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::localization::LocalizationConfig::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_LocalizationConfig = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsLocalizationConfig}, {}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_LocalizationConfig.base); +} + +::google::protobuf::Metadata file_level_metadata[1]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::LocalizationConfig, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::LocalizationConfig, localization_type_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::localization::LocalizationConfig)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::localization::_LocalizationConfig_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/localization/localization_config.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 1); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n8apollo_msgs/proto/localization/localiz" + "ation_config.proto\022\023apollo.localization\"" + "\222\001\n\022LocalizationConfig\022S\n\021localization_t" + "ype\030\001 \001(\01628.apollo.localization.Localiza" + "tionConfig.LocalizationType\"\'\n\020Localizat" + "ionType\022\007\n\003RTK\020\000\022\n\n\006CAMERA\020\001b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 236); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/localization/localization_config.proto", &protobuf_RegisterTypes); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto +namespace apollo { +namespace localization { +const ::google::protobuf::EnumDescriptor* LocalizationConfig_LocalizationType_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto::file_level_enum_descriptors[0]; +} +bool LocalizationConfig_LocalizationType_IsValid(int value) { + switch (value) { + case 0: + case 1: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const LocalizationConfig_LocalizationType LocalizationConfig::RTK; +const LocalizationConfig_LocalizationType LocalizationConfig::CAMERA; +const LocalizationConfig_LocalizationType LocalizationConfig::LocalizationType_MIN; +const LocalizationConfig_LocalizationType LocalizationConfig::LocalizationType_MAX; +const int LocalizationConfig::LocalizationType_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +// =================================================================== + +void LocalizationConfig::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int LocalizationConfig::kLocalizationTypeFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +LocalizationConfig::LocalizationConfig() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto::scc_info_LocalizationConfig.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.localization.LocalizationConfig) +} +LocalizationConfig::LocalizationConfig(const LocalizationConfig& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + localization_type_ = from.localization_type_; + // @@protoc_insertion_point(copy_constructor:apollo.localization.LocalizationConfig) +} + +void LocalizationConfig::SharedCtor() { + localization_type_ = 0; +} + +LocalizationConfig::~LocalizationConfig() { + // @@protoc_insertion_point(destructor:apollo.localization.LocalizationConfig) + SharedDtor(); +} + +void LocalizationConfig::SharedDtor() { +} + +void LocalizationConfig::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* LocalizationConfig::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const LocalizationConfig& LocalizationConfig::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto::scc_info_LocalizationConfig.base); + return *internal_default_instance(); +} + + +void LocalizationConfig::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.localization.LocalizationConfig) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + localization_type_ = 0; + _internal_metadata_.Clear(); +} + +bool LocalizationConfig::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.localization.LocalizationConfig) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.localization.LocalizationConfig.LocalizationType localization_type = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_localization_type(static_cast< ::apollo::localization::LocalizationConfig_LocalizationType >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.localization.LocalizationConfig) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.localization.LocalizationConfig) + return false; +#undef DO_ +} + +void LocalizationConfig::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.localization.LocalizationConfig) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.localization.LocalizationConfig.LocalizationType localization_type = 1; + if (this->localization_type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->localization_type(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.localization.LocalizationConfig) +} + +::google::protobuf::uint8* LocalizationConfig::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.localization.LocalizationConfig) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.localization.LocalizationConfig.LocalizationType localization_type = 1; + if (this->localization_type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->localization_type(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.localization.LocalizationConfig) + return target; +} + +size_t LocalizationConfig::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.localization.LocalizationConfig) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.localization.LocalizationConfig.LocalizationType localization_type = 1; + if (this->localization_type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->localization_type()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void LocalizationConfig::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.localization.LocalizationConfig) + GOOGLE_DCHECK_NE(&from, this); + const LocalizationConfig* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.localization.LocalizationConfig) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.localization.LocalizationConfig) + MergeFrom(*source); + } +} + +void LocalizationConfig::MergeFrom(const LocalizationConfig& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.localization.LocalizationConfig) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.localization_type() != 0) { + set_localization_type(from.localization_type()); + } +} + +void LocalizationConfig::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.localization.LocalizationConfig) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void LocalizationConfig::CopyFrom(const LocalizationConfig& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.localization.LocalizationConfig) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool LocalizationConfig::IsInitialized() const { + return true; +} + +void LocalizationConfig::Swap(LocalizationConfig* other) { + if (other == this) return; + InternalSwap(other); +} +void LocalizationConfig::InternalSwap(LocalizationConfig* other) { + using std::swap; + swap(localization_type_, other->localization_type_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata LocalizationConfig::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::localization::LocalizationConfig* Arena::CreateMaybeMessage< ::apollo::localization::LocalizationConfig >(Arena* arena) { + return Arena::CreateInternal< ::apollo::localization::LocalizationConfig >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/localization_config.pb.h b/apollo_msgs/include/apollo_msgs/proto/localization/localization_config.pb.h new file mode 100644 index 0000000..0c2927e --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/localization_config.pb.h @@ -0,0 +1,262 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/localization_config.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[1]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto +namespace apollo { +namespace localization { +class LocalizationConfig; +class LocalizationConfigDefaultTypeInternal; +extern LocalizationConfigDefaultTypeInternal _LocalizationConfig_default_instance_; +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::localization::LocalizationConfig* Arena::CreateMaybeMessage<::apollo::localization::LocalizationConfig>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace localization { + +enum LocalizationConfig_LocalizationType { + LocalizationConfig_LocalizationType_RTK = 0, + LocalizationConfig_LocalizationType_CAMERA = 1, + LocalizationConfig_LocalizationType_LocalizationConfig_LocalizationType_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + LocalizationConfig_LocalizationType_LocalizationConfig_LocalizationType_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool LocalizationConfig_LocalizationType_IsValid(int value); +const LocalizationConfig_LocalizationType LocalizationConfig_LocalizationType_LocalizationType_MIN = LocalizationConfig_LocalizationType_RTK; +const LocalizationConfig_LocalizationType LocalizationConfig_LocalizationType_LocalizationType_MAX = LocalizationConfig_LocalizationType_CAMERA; +const int LocalizationConfig_LocalizationType_LocalizationType_ARRAYSIZE = LocalizationConfig_LocalizationType_LocalizationType_MAX + 1; + +const ::google::protobuf::EnumDescriptor* LocalizationConfig_LocalizationType_descriptor(); +inline const ::std::string& LocalizationConfig_LocalizationType_Name(LocalizationConfig_LocalizationType value) { + return ::google::protobuf::internal::NameOfEnum( + LocalizationConfig_LocalizationType_descriptor(), value); +} +inline bool LocalizationConfig_LocalizationType_Parse( + const ::std::string& name, LocalizationConfig_LocalizationType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + LocalizationConfig_LocalizationType_descriptor(), name, value); +} +// =================================================================== + +class LocalizationConfig : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.localization.LocalizationConfig) */ { + public: + LocalizationConfig(); + virtual ~LocalizationConfig(); + + LocalizationConfig(const LocalizationConfig& from); + + inline LocalizationConfig& operator=(const LocalizationConfig& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + LocalizationConfig(LocalizationConfig&& from) noexcept + : LocalizationConfig() { + *this = ::std::move(from); + } + + inline LocalizationConfig& operator=(LocalizationConfig&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const LocalizationConfig& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const LocalizationConfig* internal_default_instance() { + return reinterpret_cast( + &_LocalizationConfig_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(LocalizationConfig* other); + friend void swap(LocalizationConfig& a, LocalizationConfig& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline LocalizationConfig* New() const final { + return CreateMaybeMessage(NULL); + } + + LocalizationConfig* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const LocalizationConfig& from); + void MergeFrom(const LocalizationConfig& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(LocalizationConfig* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef LocalizationConfig_LocalizationType LocalizationType; + static const LocalizationType RTK = + LocalizationConfig_LocalizationType_RTK; + static const LocalizationType CAMERA = + LocalizationConfig_LocalizationType_CAMERA; + static inline bool LocalizationType_IsValid(int value) { + return LocalizationConfig_LocalizationType_IsValid(value); + } + static const LocalizationType LocalizationType_MIN = + LocalizationConfig_LocalizationType_LocalizationType_MIN; + static const LocalizationType LocalizationType_MAX = + LocalizationConfig_LocalizationType_LocalizationType_MAX; + static const int LocalizationType_ARRAYSIZE = + LocalizationConfig_LocalizationType_LocalizationType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + LocalizationType_descriptor() { + return LocalizationConfig_LocalizationType_descriptor(); + } + static inline const ::std::string& LocalizationType_Name(LocalizationType value) { + return LocalizationConfig_LocalizationType_Name(value); + } + static inline bool LocalizationType_Parse(const ::std::string& name, + LocalizationType* value) { + return LocalizationConfig_LocalizationType_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // .apollo.localization.LocalizationConfig.LocalizationType localization_type = 1; + void clear_localization_type(); + static const int kLocalizationTypeFieldNumber = 1; + ::apollo::localization::LocalizationConfig_LocalizationType localization_type() const; + void set_localization_type(::apollo::localization::LocalizationConfig_LocalizationType value); + + // @@protoc_insertion_point(class_scope:apollo.localization.LocalizationConfig) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + int localization_type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// LocalizationConfig + +// .apollo.localization.LocalizationConfig.LocalizationType localization_type = 1; +inline void LocalizationConfig::clear_localization_type() { + localization_type_ = 0; +} +inline ::apollo::localization::LocalizationConfig_LocalizationType LocalizationConfig::localization_type() const { + // @@protoc_insertion_point(field_get:apollo.localization.LocalizationConfig.localization_type) + return static_cast< ::apollo::localization::LocalizationConfig_LocalizationType >(localization_type_); +} +inline void LocalizationConfig::set_localization_type(::apollo::localization::LocalizationConfig_LocalizationType value) { + + localization_type_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.LocalizationConfig.localization_type) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) + +} // namespace localization +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::localization::LocalizationConfig_LocalizationType> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::localization::LocalizationConfig_LocalizationType>() { + return ::apollo::localization::LocalizationConfig_LocalizationType_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2flocalization_5fconfig_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/pose.pb.cc b/apollo_msgs/include/apollo_msgs/proto/localization/pose.pb.cc new file mode 100644 index 0000000..57622fa --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/pose.pb.cc @@ -0,0 +1,758 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/pose.proto + +#include "apollo_msgs/proto/localization/pose.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Point3D; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_PointENU; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Quaternion; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto +namespace apollo { +namespace localization { +class PoseDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Pose_default_instance_; +} // namespace localization +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto { +static void InitDefaultsPose() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::localization::_Pose_default_instance_; + new (ptr) ::apollo::localization::Pose(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::localization::Pose::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<3> scc_info_Pose = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 3, InitDefaultsPose}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_PointENU.base, + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_Quaternion.base, + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::scc_info_Point3D.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_Pose.base); +} + +::google::protobuf::Metadata file_level_metadata[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Pose, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Pose, position_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Pose, orientation_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Pose, linear_velocity_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Pose, linear_acceleration_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Pose, angular_velocity_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Pose, heading_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Pose, linear_acceleration_vrf_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::localization::Pose, angular_velocity_vrf_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::localization::Pose)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::localization::_Pose_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/localization/pose.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 1); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n)apollo_msgs/proto/localization/pose.pr" + "oto\022\023apollo.localization\032\'apollo_msgs/pr" + "oto/common/geometry.proto\"\371\002\n\004Pose\022)\n\010po" + "sition\030\001 \001(\0132\027.apollo.common.PointENU\022.\n" + "\013orientation\030\002 \001(\0132\031.apollo.common.Quate" + "rnion\022/\n\017linear_velocity\030\003 \001(\0132\026.apollo." + "common.Point3D\0223\n\023linear_acceleration\030\004 " + "\001(\0132\026.apollo.common.Point3D\0220\n\020angular_v" + "elocity\030\005 \001(\0132\026.apollo.common.Point3D\022\017\n" + "\007heading\030\006 \001(\001\0227\n\027linear_acceleration_vr" + "f\030\007 \001(\0132\026.apollo.common.Point3D\0224\n\024angul" + "ar_velocity_vrf\030\010 \001(\0132\026.apollo.common.Po" + "int3Db\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 493); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/localization/pose.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fgeometry_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto +namespace apollo { +namespace localization { + +// =================================================================== + +void Pose::InitAsDefaultInstance() { + ::apollo::localization::_Pose_default_instance_._instance.get_mutable()->position_ = const_cast< ::apollo::common::PointENU*>( + ::apollo::common::PointENU::internal_default_instance()); + ::apollo::localization::_Pose_default_instance_._instance.get_mutable()->orientation_ = const_cast< ::apollo::common::Quaternion*>( + ::apollo::common::Quaternion::internal_default_instance()); + ::apollo::localization::_Pose_default_instance_._instance.get_mutable()->linear_velocity_ = const_cast< ::apollo::common::Point3D*>( + ::apollo::common::Point3D::internal_default_instance()); + ::apollo::localization::_Pose_default_instance_._instance.get_mutable()->linear_acceleration_ = const_cast< ::apollo::common::Point3D*>( + ::apollo::common::Point3D::internal_default_instance()); + ::apollo::localization::_Pose_default_instance_._instance.get_mutable()->angular_velocity_ = const_cast< ::apollo::common::Point3D*>( + ::apollo::common::Point3D::internal_default_instance()); + ::apollo::localization::_Pose_default_instance_._instance.get_mutable()->linear_acceleration_vrf_ = const_cast< ::apollo::common::Point3D*>( + ::apollo::common::Point3D::internal_default_instance()); + ::apollo::localization::_Pose_default_instance_._instance.get_mutable()->angular_velocity_vrf_ = const_cast< ::apollo::common::Point3D*>( + ::apollo::common::Point3D::internal_default_instance()); +} +void Pose::clear_position() { + if (GetArenaNoVirtual() == NULL && position_ != NULL) { + delete position_; + } + position_ = NULL; +} +void Pose::clear_orientation() { + if (GetArenaNoVirtual() == NULL && orientation_ != NULL) { + delete orientation_; + } + orientation_ = NULL; +} +void Pose::clear_linear_velocity() { + if (GetArenaNoVirtual() == NULL && linear_velocity_ != NULL) { + delete linear_velocity_; + } + linear_velocity_ = NULL; +} +void Pose::clear_linear_acceleration() { + if (GetArenaNoVirtual() == NULL && linear_acceleration_ != NULL) { + delete linear_acceleration_; + } + linear_acceleration_ = NULL; +} +void Pose::clear_angular_velocity() { + if (GetArenaNoVirtual() == NULL && angular_velocity_ != NULL) { + delete angular_velocity_; + } + angular_velocity_ = NULL; +} +void Pose::clear_linear_acceleration_vrf() { + if (GetArenaNoVirtual() == NULL && linear_acceleration_vrf_ != NULL) { + delete linear_acceleration_vrf_; + } + linear_acceleration_vrf_ = NULL; +} +void Pose::clear_angular_velocity_vrf() { + if (GetArenaNoVirtual() == NULL && angular_velocity_vrf_ != NULL) { + delete angular_velocity_vrf_; + } + angular_velocity_vrf_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Pose::kPositionFieldNumber; +const int Pose::kOrientationFieldNumber; +const int Pose::kLinearVelocityFieldNumber; +const int Pose::kLinearAccelerationFieldNumber; +const int Pose::kAngularVelocityFieldNumber; +const int Pose::kHeadingFieldNumber; +const int Pose::kLinearAccelerationVrfFieldNumber; +const int Pose::kAngularVelocityVrfFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Pose::Pose() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::scc_info_Pose.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.localization.Pose) +} +Pose::Pose(const Pose& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_position()) { + position_ = new ::apollo::common::PointENU(*from.position_); + } else { + position_ = NULL; + } + if (from.has_orientation()) { + orientation_ = new ::apollo::common::Quaternion(*from.orientation_); + } else { + orientation_ = NULL; + } + if (from.has_linear_velocity()) { + linear_velocity_ = new ::apollo::common::Point3D(*from.linear_velocity_); + } else { + linear_velocity_ = NULL; + } + if (from.has_linear_acceleration()) { + linear_acceleration_ = new ::apollo::common::Point3D(*from.linear_acceleration_); + } else { + linear_acceleration_ = NULL; + } + if (from.has_angular_velocity()) { + angular_velocity_ = new ::apollo::common::Point3D(*from.angular_velocity_); + } else { + angular_velocity_ = NULL; + } + if (from.has_linear_acceleration_vrf()) { + linear_acceleration_vrf_ = new ::apollo::common::Point3D(*from.linear_acceleration_vrf_); + } else { + linear_acceleration_vrf_ = NULL; + } + if (from.has_angular_velocity_vrf()) { + angular_velocity_vrf_ = new ::apollo::common::Point3D(*from.angular_velocity_vrf_); + } else { + angular_velocity_vrf_ = NULL; + } + heading_ = from.heading_; + // @@protoc_insertion_point(copy_constructor:apollo.localization.Pose) +} + +void Pose::SharedCtor() { + ::memset(&position_, 0, static_cast( + reinterpret_cast(&heading_) - + reinterpret_cast(&position_)) + sizeof(heading_)); +} + +Pose::~Pose() { + // @@protoc_insertion_point(destructor:apollo.localization.Pose) + SharedDtor(); +} + +void Pose::SharedDtor() { + if (this != internal_default_instance()) delete position_; + if (this != internal_default_instance()) delete orientation_; + if (this != internal_default_instance()) delete linear_velocity_; + if (this != internal_default_instance()) delete linear_acceleration_; + if (this != internal_default_instance()) delete angular_velocity_; + if (this != internal_default_instance()) delete linear_acceleration_vrf_; + if (this != internal_default_instance()) delete angular_velocity_vrf_; +} + +void Pose::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Pose::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Pose& Pose::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::scc_info_Pose.base); + return *internal_default_instance(); +} + + +void Pose::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.localization.Pose) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == NULL && position_ != NULL) { + delete position_; + } + position_ = NULL; + if (GetArenaNoVirtual() == NULL && orientation_ != NULL) { + delete orientation_; + } + orientation_ = NULL; + if (GetArenaNoVirtual() == NULL && linear_velocity_ != NULL) { + delete linear_velocity_; + } + linear_velocity_ = NULL; + if (GetArenaNoVirtual() == NULL && linear_acceleration_ != NULL) { + delete linear_acceleration_; + } + linear_acceleration_ = NULL; + if (GetArenaNoVirtual() == NULL && angular_velocity_ != NULL) { + delete angular_velocity_; + } + angular_velocity_ = NULL; + if (GetArenaNoVirtual() == NULL && linear_acceleration_vrf_ != NULL) { + delete linear_acceleration_vrf_; + } + linear_acceleration_vrf_ = NULL; + if (GetArenaNoVirtual() == NULL && angular_velocity_vrf_ != NULL) { + delete angular_velocity_vrf_; + } + angular_velocity_vrf_ = NULL; + heading_ = 0; + _internal_metadata_.Clear(); +} + +bool Pose::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.localization.Pose) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.PointENU position = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_position())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Quaternion orientation = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_orientation())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Point3D linear_velocity = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_linear_velocity())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Point3D linear_acceleration = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_linear_acceleration())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Point3D angular_velocity = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_angular_velocity())); + } else { + goto handle_unusual; + } + break; + } + + // double heading = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &heading_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Point3D linear_acceleration_vrf = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(58u /* 58 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_linear_acceleration_vrf())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Point3D angular_velocity_vrf = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(66u /* 66 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_angular_velocity_vrf())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.localization.Pose) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.localization.Pose) + return false; +#undef DO_ +} + +void Pose::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.localization.Pose) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.PointENU position = 1; + if (this->has_position()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_position(), output); + } + + // .apollo.common.Quaternion orientation = 2; + if (this->has_orientation()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_orientation(), output); + } + + // .apollo.common.Point3D linear_velocity = 3; + if (this->has_linear_velocity()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_linear_velocity(), output); + } + + // .apollo.common.Point3D linear_acceleration = 4; + if (this->has_linear_acceleration()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, this->_internal_linear_acceleration(), output); + } + + // .apollo.common.Point3D angular_velocity = 5; + if (this->has_angular_velocity()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, this->_internal_angular_velocity(), output); + } + + // double heading = 6; + if (this->heading() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->heading(), output); + } + + // .apollo.common.Point3D linear_acceleration_vrf = 7; + if (this->has_linear_acceleration_vrf()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 7, this->_internal_linear_acceleration_vrf(), output); + } + + // .apollo.common.Point3D angular_velocity_vrf = 8; + if (this->has_angular_velocity_vrf()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 8, this->_internal_angular_velocity_vrf(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.localization.Pose) +} + +::google::protobuf::uint8* Pose::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.localization.Pose) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.PointENU position = 1; + if (this->has_position()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_position(), deterministic, target); + } + + // .apollo.common.Quaternion orientation = 2; + if (this->has_orientation()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_orientation(), deterministic, target); + } + + // .apollo.common.Point3D linear_velocity = 3; + if (this->has_linear_velocity()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_linear_velocity(), deterministic, target); + } + + // .apollo.common.Point3D linear_acceleration = 4; + if (this->has_linear_acceleration()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->_internal_linear_acceleration(), deterministic, target); + } + + // .apollo.common.Point3D angular_velocity = 5; + if (this->has_angular_velocity()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 5, this->_internal_angular_velocity(), deterministic, target); + } + + // double heading = 6; + if (this->heading() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->heading(), target); + } + + // .apollo.common.Point3D linear_acceleration_vrf = 7; + if (this->has_linear_acceleration_vrf()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 7, this->_internal_linear_acceleration_vrf(), deterministic, target); + } + + // .apollo.common.Point3D angular_velocity_vrf = 8; + if (this->has_angular_velocity_vrf()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 8, this->_internal_angular_velocity_vrf(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.localization.Pose) + return target; +} + +size_t Pose::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.localization.Pose) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.common.PointENU position = 1; + if (this->has_position()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *position_); + } + + // .apollo.common.Quaternion orientation = 2; + if (this->has_orientation()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *orientation_); + } + + // .apollo.common.Point3D linear_velocity = 3; + if (this->has_linear_velocity()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *linear_velocity_); + } + + // .apollo.common.Point3D linear_acceleration = 4; + if (this->has_linear_acceleration()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *linear_acceleration_); + } + + // .apollo.common.Point3D angular_velocity = 5; + if (this->has_angular_velocity()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *angular_velocity_); + } + + // .apollo.common.Point3D linear_acceleration_vrf = 7; + if (this->has_linear_acceleration_vrf()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *linear_acceleration_vrf_); + } + + // .apollo.common.Point3D angular_velocity_vrf = 8; + if (this->has_angular_velocity_vrf()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *angular_velocity_vrf_); + } + + // double heading = 6; + if (this->heading() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Pose::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.localization.Pose) + GOOGLE_DCHECK_NE(&from, this); + const Pose* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.localization.Pose) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.localization.Pose) + MergeFrom(*source); + } +} + +void Pose::MergeFrom(const Pose& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.localization.Pose) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_position()) { + mutable_position()->::apollo::common::PointENU::MergeFrom(from.position()); + } + if (from.has_orientation()) { + mutable_orientation()->::apollo::common::Quaternion::MergeFrom(from.orientation()); + } + if (from.has_linear_velocity()) { + mutable_linear_velocity()->::apollo::common::Point3D::MergeFrom(from.linear_velocity()); + } + if (from.has_linear_acceleration()) { + mutable_linear_acceleration()->::apollo::common::Point3D::MergeFrom(from.linear_acceleration()); + } + if (from.has_angular_velocity()) { + mutable_angular_velocity()->::apollo::common::Point3D::MergeFrom(from.angular_velocity()); + } + if (from.has_linear_acceleration_vrf()) { + mutable_linear_acceleration_vrf()->::apollo::common::Point3D::MergeFrom(from.linear_acceleration_vrf()); + } + if (from.has_angular_velocity_vrf()) { + mutable_angular_velocity_vrf()->::apollo::common::Point3D::MergeFrom(from.angular_velocity_vrf()); + } + if (from.heading() != 0) { + set_heading(from.heading()); + } +} + +void Pose::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.localization.Pose) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Pose::CopyFrom(const Pose& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.localization.Pose) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Pose::IsInitialized() const { + return true; +} + +void Pose::Swap(Pose* other) { + if (other == this) return; + InternalSwap(other); +} +void Pose::InternalSwap(Pose* other) { + using std::swap; + swap(position_, other->position_); + swap(orientation_, other->orientation_); + swap(linear_velocity_, other->linear_velocity_); + swap(linear_acceleration_, other->linear_acceleration_); + swap(angular_velocity_, other->angular_velocity_); + swap(linear_acceleration_vrf_, other->linear_acceleration_vrf_); + swap(angular_velocity_vrf_, other->angular_velocity_vrf_); + swap(heading_, other->heading_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Pose::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::localization::Pose* Arena::CreateMaybeMessage< ::apollo::localization::Pose >(Arena* arena) { + return Arena::CreateInternal< ::apollo::localization::Pose >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/localization/pose.pb.h b/apollo_msgs/include/apollo_msgs/proto/localization/pose.pb.h new file mode 100644 index 0000000..04b08d5 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/localization/pose.pb.h @@ -0,0 +1,630 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/localization/pose.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include "apollo_msgs/proto/common/geometry.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[1]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto +namespace apollo { +namespace localization { +class Pose; +class PoseDefaultTypeInternal; +extern PoseDefaultTypeInternal _Pose_default_instance_; +} // namespace localization +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::localization::Pose* Arena::CreateMaybeMessage<::apollo::localization::Pose>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace localization { + +// =================================================================== + +class Pose : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.localization.Pose) */ { + public: + Pose(); + virtual ~Pose(); + + Pose(const Pose& from); + + inline Pose& operator=(const Pose& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Pose(Pose&& from) noexcept + : Pose() { + *this = ::std::move(from); + } + + inline Pose& operator=(Pose&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Pose& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Pose* internal_default_instance() { + return reinterpret_cast( + &_Pose_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(Pose* other); + friend void swap(Pose& a, Pose& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Pose* New() const final { + return CreateMaybeMessage(NULL); + } + + Pose* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Pose& from); + void MergeFrom(const Pose& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Pose* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.common.PointENU position = 1; + bool has_position() const; + void clear_position(); + static const int kPositionFieldNumber = 1; + private: + const ::apollo::common::PointENU& _internal_position() const; + public: + const ::apollo::common::PointENU& position() const; + ::apollo::common::PointENU* release_position(); + ::apollo::common::PointENU* mutable_position(); + void set_allocated_position(::apollo::common::PointENU* position); + + // .apollo.common.Quaternion orientation = 2; + bool has_orientation() const; + void clear_orientation(); + static const int kOrientationFieldNumber = 2; + private: + const ::apollo::common::Quaternion& _internal_orientation() const; + public: + const ::apollo::common::Quaternion& orientation() const; + ::apollo::common::Quaternion* release_orientation(); + ::apollo::common::Quaternion* mutable_orientation(); + void set_allocated_orientation(::apollo::common::Quaternion* orientation); + + // .apollo.common.Point3D linear_velocity = 3; + bool has_linear_velocity() const; + void clear_linear_velocity(); + static const int kLinearVelocityFieldNumber = 3; + private: + const ::apollo::common::Point3D& _internal_linear_velocity() const; + public: + const ::apollo::common::Point3D& linear_velocity() const; + ::apollo::common::Point3D* release_linear_velocity(); + ::apollo::common::Point3D* mutable_linear_velocity(); + void set_allocated_linear_velocity(::apollo::common::Point3D* linear_velocity); + + // .apollo.common.Point3D linear_acceleration = 4; + bool has_linear_acceleration() const; + void clear_linear_acceleration(); + static const int kLinearAccelerationFieldNumber = 4; + private: + const ::apollo::common::Point3D& _internal_linear_acceleration() const; + public: + const ::apollo::common::Point3D& linear_acceleration() const; + ::apollo::common::Point3D* release_linear_acceleration(); + ::apollo::common::Point3D* mutable_linear_acceleration(); + void set_allocated_linear_acceleration(::apollo::common::Point3D* linear_acceleration); + + // .apollo.common.Point3D angular_velocity = 5; + bool has_angular_velocity() const; + void clear_angular_velocity(); + static const int kAngularVelocityFieldNumber = 5; + private: + const ::apollo::common::Point3D& _internal_angular_velocity() const; + public: + const ::apollo::common::Point3D& angular_velocity() const; + ::apollo::common::Point3D* release_angular_velocity(); + ::apollo::common::Point3D* mutable_angular_velocity(); + void set_allocated_angular_velocity(::apollo::common::Point3D* angular_velocity); + + // .apollo.common.Point3D linear_acceleration_vrf = 7; + bool has_linear_acceleration_vrf() const; + void clear_linear_acceleration_vrf(); + static const int kLinearAccelerationVrfFieldNumber = 7; + private: + const ::apollo::common::Point3D& _internal_linear_acceleration_vrf() const; + public: + const ::apollo::common::Point3D& linear_acceleration_vrf() const; + ::apollo::common::Point3D* release_linear_acceleration_vrf(); + ::apollo::common::Point3D* mutable_linear_acceleration_vrf(); + void set_allocated_linear_acceleration_vrf(::apollo::common::Point3D* linear_acceleration_vrf); + + // .apollo.common.Point3D angular_velocity_vrf = 8; + bool has_angular_velocity_vrf() const; + void clear_angular_velocity_vrf(); + static const int kAngularVelocityVrfFieldNumber = 8; + private: + const ::apollo::common::Point3D& _internal_angular_velocity_vrf() const; + public: + const ::apollo::common::Point3D& angular_velocity_vrf() const; + ::apollo::common::Point3D* release_angular_velocity_vrf(); + ::apollo::common::Point3D* mutable_angular_velocity_vrf(); + void set_allocated_angular_velocity_vrf(::apollo::common::Point3D* angular_velocity_vrf); + + // double heading = 6; + void clear_heading(); + static const int kHeadingFieldNumber = 6; + double heading() const; + void set_heading(double value); + + // @@protoc_insertion_point(class_scope:apollo.localization.Pose) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::apollo::common::PointENU* position_; + ::apollo::common::Quaternion* orientation_; + ::apollo::common::Point3D* linear_velocity_; + ::apollo::common::Point3D* linear_acceleration_; + ::apollo::common::Point3D* angular_velocity_; + ::apollo::common::Point3D* linear_acceleration_vrf_; + ::apollo::common::Point3D* angular_velocity_vrf_; + double heading_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// Pose + +// .apollo.common.PointENU position = 1; +inline bool Pose::has_position() const { + return this != internal_default_instance() && position_ != NULL; +} +inline const ::apollo::common::PointENU& Pose::_internal_position() const { + return *position_; +} +inline const ::apollo::common::PointENU& Pose::position() const { + const ::apollo::common::PointENU* p = position_; + // @@protoc_insertion_point(field_get:apollo.localization.Pose.position) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_PointENU_default_instance_); +} +inline ::apollo::common::PointENU* Pose::release_position() { + // @@protoc_insertion_point(field_release:apollo.localization.Pose.position) + + ::apollo::common::PointENU* temp = position_; + position_ = NULL; + return temp; +} +inline ::apollo::common::PointENU* Pose::mutable_position() { + + if (position_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::PointENU>(GetArenaNoVirtual()); + position_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Pose.position) + return position_; +} +inline void Pose::set_allocated_position(::apollo::common::PointENU* position) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(position_); + } + if (position) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + position = ::google::protobuf::internal::GetOwnedMessage( + message_arena, position, submessage_arena); + } + + } else { + + } + position_ = position; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Pose.position) +} + +// .apollo.common.Quaternion orientation = 2; +inline bool Pose::has_orientation() const { + return this != internal_default_instance() && orientation_ != NULL; +} +inline const ::apollo::common::Quaternion& Pose::_internal_orientation() const { + return *orientation_; +} +inline const ::apollo::common::Quaternion& Pose::orientation() const { + const ::apollo::common::Quaternion* p = orientation_; + // @@protoc_insertion_point(field_get:apollo.localization.Pose.orientation) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Quaternion_default_instance_); +} +inline ::apollo::common::Quaternion* Pose::release_orientation() { + // @@protoc_insertion_point(field_release:apollo.localization.Pose.orientation) + + ::apollo::common::Quaternion* temp = orientation_; + orientation_ = NULL; + return temp; +} +inline ::apollo::common::Quaternion* Pose::mutable_orientation() { + + if (orientation_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Quaternion>(GetArenaNoVirtual()); + orientation_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Pose.orientation) + return orientation_; +} +inline void Pose::set_allocated_orientation(::apollo::common::Quaternion* orientation) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(orientation_); + } + if (orientation) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + orientation = ::google::protobuf::internal::GetOwnedMessage( + message_arena, orientation, submessage_arena); + } + + } else { + + } + orientation_ = orientation; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Pose.orientation) +} + +// .apollo.common.Point3D linear_velocity = 3; +inline bool Pose::has_linear_velocity() const { + return this != internal_default_instance() && linear_velocity_ != NULL; +} +inline const ::apollo::common::Point3D& Pose::_internal_linear_velocity() const { + return *linear_velocity_; +} +inline const ::apollo::common::Point3D& Pose::linear_velocity() const { + const ::apollo::common::Point3D* p = linear_velocity_; + // @@protoc_insertion_point(field_get:apollo.localization.Pose.linear_velocity) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Point3D_default_instance_); +} +inline ::apollo::common::Point3D* Pose::release_linear_velocity() { + // @@protoc_insertion_point(field_release:apollo.localization.Pose.linear_velocity) + + ::apollo::common::Point3D* temp = linear_velocity_; + linear_velocity_ = NULL; + return temp; +} +inline ::apollo::common::Point3D* Pose::mutable_linear_velocity() { + + if (linear_velocity_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Point3D>(GetArenaNoVirtual()); + linear_velocity_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Pose.linear_velocity) + return linear_velocity_; +} +inline void Pose::set_allocated_linear_velocity(::apollo::common::Point3D* linear_velocity) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(linear_velocity_); + } + if (linear_velocity) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + linear_velocity = ::google::protobuf::internal::GetOwnedMessage( + message_arena, linear_velocity, submessage_arena); + } + + } else { + + } + linear_velocity_ = linear_velocity; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Pose.linear_velocity) +} + +// .apollo.common.Point3D linear_acceleration = 4; +inline bool Pose::has_linear_acceleration() const { + return this != internal_default_instance() && linear_acceleration_ != NULL; +} +inline const ::apollo::common::Point3D& Pose::_internal_linear_acceleration() const { + return *linear_acceleration_; +} +inline const ::apollo::common::Point3D& Pose::linear_acceleration() const { + const ::apollo::common::Point3D* p = linear_acceleration_; + // @@protoc_insertion_point(field_get:apollo.localization.Pose.linear_acceleration) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Point3D_default_instance_); +} +inline ::apollo::common::Point3D* Pose::release_linear_acceleration() { + // @@protoc_insertion_point(field_release:apollo.localization.Pose.linear_acceleration) + + ::apollo::common::Point3D* temp = linear_acceleration_; + linear_acceleration_ = NULL; + return temp; +} +inline ::apollo::common::Point3D* Pose::mutable_linear_acceleration() { + + if (linear_acceleration_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Point3D>(GetArenaNoVirtual()); + linear_acceleration_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Pose.linear_acceleration) + return linear_acceleration_; +} +inline void Pose::set_allocated_linear_acceleration(::apollo::common::Point3D* linear_acceleration) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(linear_acceleration_); + } + if (linear_acceleration) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + linear_acceleration = ::google::protobuf::internal::GetOwnedMessage( + message_arena, linear_acceleration, submessage_arena); + } + + } else { + + } + linear_acceleration_ = linear_acceleration; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Pose.linear_acceleration) +} + +// .apollo.common.Point3D angular_velocity = 5; +inline bool Pose::has_angular_velocity() const { + return this != internal_default_instance() && angular_velocity_ != NULL; +} +inline const ::apollo::common::Point3D& Pose::_internal_angular_velocity() const { + return *angular_velocity_; +} +inline const ::apollo::common::Point3D& Pose::angular_velocity() const { + const ::apollo::common::Point3D* p = angular_velocity_; + // @@protoc_insertion_point(field_get:apollo.localization.Pose.angular_velocity) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Point3D_default_instance_); +} +inline ::apollo::common::Point3D* Pose::release_angular_velocity() { + // @@protoc_insertion_point(field_release:apollo.localization.Pose.angular_velocity) + + ::apollo::common::Point3D* temp = angular_velocity_; + angular_velocity_ = NULL; + return temp; +} +inline ::apollo::common::Point3D* Pose::mutable_angular_velocity() { + + if (angular_velocity_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Point3D>(GetArenaNoVirtual()); + angular_velocity_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Pose.angular_velocity) + return angular_velocity_; +} +inline void Pose::set_allocated_angular_velocity(::apollo::common::Point3D* angular_velocity) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(angular_velocity_); + } + if (angular_velocity) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + angular_velocity = ::google::protobuf::internal::GetOwnedMessage( + message_arena, angular_velocity, submessage_arena); + } + + } else { + + } + angular_velocity_ = angular_velocity; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Pose.angular_velocity) +} + +// double heading = 6; +inline void Pose::clear_heading() { + heading_ = 0; +} +inline double Pose::heading() const { + // @@protoc_insertion_point(field_get:apollo.localization.Pose.heading) + return heading_; +} +inline void Pose::set_heading(double value) { + + heading_ = value; + // @@protoc_insertion_point(field_set:apollo.localization.Pose.heading) +} + +// .apollo.common.Point3D linear_acceleration_vrf = 7; +inline bool Pose::has_linear_acceleration_vrf() const { + return this != internal_default_instance() && linear_acceleration_vrf_ != NULL; +} +inline const ::apollo::common::Point3D& Pose::_internal_linear_acceleration_vrf() const { + return *linear_acceleration_vrf_; +} +inline const ::apollo::common::Point3D& Pose::linear_acceleration_vrf() const { + const ::apollo::common::Point3D* p = linear_acceleration_vrf_; + // @@protoc_insertion_point(field_get:apollo.localization.Pose.linear_acceleration_vrf) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Point3D_default_instance_); +} +inline ::apollo::common::Point3D* Pose::release_linear_acceleration_vrf() { + // @@protoc_insertion_point(field_release:apollo.localization.Pose.linear_acceleration_vrf) + + ::apollo::common::Point3D* temp = linear_acceleration_vrf_; + linear_acceleration_vrf_ = NULL; + return temp; +} +inline ::apollo::common::Point3D* Pose::mutable_linear_acceleration_vrf() { + + if (linear_acceleration_vrf_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Point3D>(GetArenaNoVirtual()); + linear_acceleration_vrf_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Pose.linear_acceleration_vrf) + return linear_acceleration_vrf_; +} +inline void Pose::set_allocated_linear_acceleration_vrf(::apollo::common::Point3D* linear_acceleration_vrf) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(linear_acceleration_vrf_); + } + if (linear_acceleration_vrf) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + linear_acceleration_vrf = ::google::protobuf::internal::GetOwnedMessage( + message_arena, linear_acceleration_vrf, submessage_arena); + } + + } else { + + } + linear_acceleration_vrf_ = linear_acceleration_vrf; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Pose.linear_acceleration_vrf) +} + +// .apollo.common.Point3D angular_velocity_vrf = 8; +inline bool Pose::has_angular_velocity_vrf() const { + return this != internal_default_instance() && angular_velocity_vrf_ != NULL; +} +inline const ::apollo::common::Point3D& Pose::_internal_angular_velocity_vrf() const { + return *angular_velocity_vrf_; +} +inline const ::apollo::common::Point3D& Pose::angular_velocity_vrf() const { + const ::apollo::common::Point3D* p = angular_velocity_vrf_; + // @@protoc_insertion_point(field_get:apollo.localization.Pose.angular_velocity_vrf) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Point3D_default_instance_); +} +inline ::apollo::common::Point3D* Pose::release_angular_velocity_vrf() { + // @@protoc_insertion_point(field_release:apollo.localization.Pose.angular_velocity_vrf) + + ::apollo::common::Point3D* temp = angular_velocity_vrf_; + angular_velocity_vrf_ = NULL; + return temp; +} +inline ::apollo::common::Point3D* Pose::mutable_angular_velocity_vrf() { + + if (angular_velocity_vrf_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Point3D>(GetArenaNoVirtual()); + angular_velocity_vrf_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.localization.Pose.angular_velocity_vrf) + return angular_velocity_vrf_; +} +inline void Pose::set_allocated_angular_velocity_vrf(::apollo::common::Point3D* angular_velocity_vrf) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(angular_velocity_vrf_); + } + if (angular_velocity_vrf) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + angular_velocity_vrf = ::google::protobuf::internal::GetOwnedMessage( + message_arena, angular_velocity_vrf, submessage_arena); + } + + } else { + + } + angular_velocity_vrf_ = angular_velocity_vrf; + // @@protoc_insertion_point(field_set_allocated:apollo.localization.Pose.angular_velocity_vrf) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ + +// @@protoc_insertion_point(namespace_scope) + +} // namespace localization +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/perception/perception_obstacle.pb.cc b/apollo_msgs/include/apollo_msgs/proto/perception/perception_obstacle.pb.cc new file mode 100644 index 0000000..c623b09 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/perception/perception_obstacle.pb.cc @@ -0,0 +1,1576 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/perception/perception_obstacle.proto + +#include "apollo_msgs/proto/perception/perception_obstacle.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Point; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_PerceptionObstacle; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto +namespace apollo { +namespace perception { +class PointDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Point_default_instance_; +class PerceptionObstacleDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _PerceptionObstacle_default_instance_; +class PerceptionObstaclesDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _PerceptionObstacles_default_instance_; +} // namespace perception +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto { +static void InitDefaultsPoint() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::perception::_Point_default_instance_; + new (ptr) ::apollo::perception::Point(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::perception::Point::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Point = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsPoint}, {}}; + +static void InitDefaultsPerceptionObstacle() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::perception::_PerceptionObstacle_default_instance_; + new (ptr) ::apollo::perception::PerceptionObstacle(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::perception::PerceptionObstacle::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_PerceptionObstacle = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsPerceptionObstacle}, { + &protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::scc_info_Point.base,}}; + +static void InitDefaultsPerceptionObstacles() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::perception::_PerceptionObstacles_default_instance_; + new (ptr) ::apollo::perception::PerceptionObstacles(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::perception::PerceptionObstacles::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_PerceptionObstacles = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsPerceptionObstacles}, { + &protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::scc_info_PerceptionObstacle.base, + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_Point.base); + ::google::protobuf::internal::InitSCC(&scc_info_PerceptionObstacle.base); + ::google::protobuf::internal::InitSCC(&scc_info_PerceptionObstacles.base); +} + +::google::protobuf::Metadata file_level_metadata[3]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[2]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::Point, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::Point, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::Point, y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::Point, z_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacle, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacle, id_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacle, position_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacle, theta_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacle, velocity_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacle, length_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacle, width_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacle, height_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacle, polygon_point_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacle, tracking_time_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacle, type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacle, timestamp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacle, point_cloud_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacles, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacles, perception_obstacle_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacles, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::PerceptionObstacles, error_code_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::perception::Point)}, + { 8, -1, sizeof(::apollo::perception::PerceptionObstacle)}, + { 25, -1, sizeof(::apollo::perception::PerceptionObstacles)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::perception::_Point_default_instance_), + reinterpret_cast(&::apollo::perception::_PerceptionObstacle_default_instance_), + reinterpret_cast(&::apollo::perception::_PerceptionObstacles_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/perception/perception_obstacle.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 3); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n6apollo_msgs/proto/perception/perceptio" + "n_obstacle.proto\022\021apollo.perception\032%apo" + "llo_msgs/proto/common/header.proto\"(\n\005Po" + "int\022\t\n\001x\030\001 \001(\001\022\t\n\001y\030\002 \001(\001\022\t\n\001z\030\003 \001(\001\"\313\003\n" + "\022PerceptionObstacle\022\n\n\002id\030\001 \001(\005\022*\n\010posit" + "ion\030\002 \001(\0132\030.apollo.perception.Point\022\r\n\005t" + "heta\030\003 \001(\001\022*\n\010velocity\030\004 \001(\0132\030.apollo.pe" + "rception.Point\022\016\n\006length\030\005 \001(\001\022\r\n\005width\030" + "\006 \001(\001\022\016\n\006height\030\007 \001(\001\022/\n\rpolygon_point\030\010" + " \003(\0132\030.apollo.perception.Point\022\025\n\rtracki" + "ng_time\030\t \001(\001\0228\n\004type\030\n \001(\0162*.apollo.per" + "ception.PerceptionObstacle.Type\022\021\n\ttimes" + "tamp\030\013 \001(\001\022\023\n\013point_cloud\030\014 \003(\001\"i\n\004Type\022" + "\013\n\007UNKNOWN\020\000\022\023\n\017UNKNOWN_MOVABLE\020\001\022\025\n\021UNK" + "NOWN_UNMOVABLE\020\002\022\016\n\nPEDESTRIAN\020\003\022\013\n\007BICY" + "CLE\020\004\022\013\n\007VEHICLE\020\005\"\274\001\n\023PerceptionObstacl" + "es\022B\n\023perception_obstacle\030\001 \003(\0132%.apollo" + ".perception.PerceptionObstacle\022%\n\006header" + "\030\002 \001(\0132\025.apollo.common.Header\022:\n\nerror_c" + "ode\030\003 \001(\0162&.apollo.perception.Perception" + "ErrorCode*Y\n\023PerceptionErrorCode\022\016\n\nERRO" + "R_NONE\020\000\022\014\n\010ERROR_TF\020\001\022\021\n\rERROR_PROCESS\020" + "\002\022\021\n\rERROR_UNKNOWN\020\003b\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 908); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/perception/perception_obstacle.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto +namespace apollo { +namespace perception { +const ::google::protobuf::EnumDescriptor* PerceptionObstacle_Type_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::file_level_enum_descriptors[0]; +} +bool PerceptionObstacle_Type_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const PerceptionObstacle_Type PerceptionObstacle::UNKNOWN; +const PerceptionObstacle_Type PerceptionObstacle::UNKNOWN_MOVABLE; +const PerceptionObstacle_Type PerceptionObstacle::UNKNOWN_UNMOVABLE; +const PerceptionObstacle_Type PerceptionObstacle::PEDESTRIAN; +const PerceptionObstacle_Type PerceptionObstacle::BICYCLE; +const PerceptionObstacle_Type PerceptionObstacle::VEHICLE; +const PerceptionObstacle_Type PerceptionObstacle::Type_MIN; +const PerceptionObstacle_Type PerceptionObstacle::Type_MAX; +const int PerceptionObstacle::Type_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 +const ::google::protobuf::EnumDescriptor* PerceptionErrorCode_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::file_level_enum_descriptors[1]; +} +bool PerceptionErrorCode_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} + + +// =================================================================== + +void Point::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Point::kXFieldNumber; +const int Point::kYFieldNumber; +const int Point::kZFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Point::Point() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::scc_info_Point.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.perception.Point) +} +Point::Point(const Point& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&x_, &from.x_, + static_cast(reinterpret_cast(&z_) - + reinterpret_cast(&x_)) + sizeof(z_)); + // @@protoc_insertion_point(copy_constructor:apollo.perception.Point) +} + +void Point::SharedCtor() { + ::memset(&x_, 0, static_cast( + reinterpret_cast(&z_) - + reinterpret_cast(&x_)) + sizeof(z_)); +} + +Point::~Point() { + // @@protoc_insertion_point(destructor:apollo.perception.Point) + SharedDtor(); +} + +void Point::SharedDtor() { +} + +void Point::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Point::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Point& Point::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::scc_info_Point.base); + return *internal_default_instance(); +} + + +void Point::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.perception.Point) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&x_, 0, static_cast( + reinterpret_cast(&z_) - + reinterpret_cast(&x_)) + sizeof(z_)); + _internal_metadata_.Clear(); +} + +bool Point::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.perception.Point) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double x = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &x_))); + } else { + goto handle_unusual; + } + break; + } + + // double y = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &y_))); + } else { + goto handle_unusual; + } + break; + } + + // double z = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &z_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.perception.Point) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.perception.Point) + return false; +#undef DO_ +} + +void Point::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.perception.Point) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output); + } + + // double y = 2; + if (this->y() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output); + } + + // double z = 3; + if (this->z() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->z(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.perception.Point) +} + +::google::protobuf::uint8* Point::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.perception.Point) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target); + } + + // double y = 2; + if (this->y() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target); + } + + // double z = 3; + if (this->z() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->z(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.perception.Point) + return target; +} + +size_t Point::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.perception.Point) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double x = 1; + if (this->x() != 0) { + total_size += 1 + 8; + } + + // double y = 2; + if (this->y() != 0) { + total_size += 1 + 8; + } + + // double z = 3; + if (this->z() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Point::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.perception.Point) + GOOGLE_DCHECK_NE(&from, this); + const Point* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.perception.Point) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.perception.Point) + MergeFrom(*source); + } +} + +void Point::MergeFrom(const Point& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.perception.Point) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.x() != 0) { + set_x(from.x()); + } + if (from.y() != 0) { + set_y(from.y()); + } + if (from.z() != 0) { + set_z(from.z()); + } +} + +void Point::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.perception.Point) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Point::CopyFrom(const Point& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.perception.Point) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Point::IsInitialized() const { + return true; +} + +void Point::Swap(Point* other) { + if (other == this) return; + InternalSwap(other); +} +void Point::InternalSwap(Point* other) { + using std::swap; + swap(x_, other->x_); + swap(y_, other->y_); + swap(z_, other->z_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Point::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void PerceptionObstacle::InitAsDefaultInstance() { + ::apollo::perception::_PerceptionObstacle_default_instance_._instance.get_mutable()->position_ = const_cast< ::apollo::perception::Point*>( + ::apollo::perception::Point::internal_default_instance()); + ::apollo::perception::_PerceptionObstacle_default_instance_._instance.get_mutable()->velocity_ = const_cast< ::apollo::perception::Point*>( + ::apollo::perception::Point::internal_default_instance()); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PerceptionObstacle::kIdFieldNumber; +const int PerceptionObstacle::kPositionFieldNumber; +const int PerceptionObstacle::kThetaFieldNumber; +const int PerceptionObstacle::kVelocityFieldNumber; +const int PerceptionObstacle::kLengthFieldNumber; +const int PerceptionObstacle::kWidthFieldNumber; +const int PerceptionObstacle::kHeightFieldNumber; +const int PerceptionObstacle::kPolygonPointFieldNumber; +const int PerceptionObstacle::kTrackingTimeFieldNumber; +const int PerceptionObstacle::kTypeFieldNumber; +const int PerceptionObstacle::kTimestampFieldNumber; +const int PerceptionObstacle::kPointCloudFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PerceptionObstacle::PerceptionObstacle() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::scc_info_PerceptionObstacle.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.perception.PerceptionObstacle) +} +PerceptionObstacle::PerceptionObstacle(const PerceptionObstacle& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + polygon_point_(from.polygon_point_), + point_cloud_(from.point_cloud_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_position()) { + position_ = new ::apollo::perception::Point(*from.position_); + } else { + position_ = NULL; + } + if (from.has_velocity()) { + velocity_ = new ::apollo::perception::Point(*from.velocity_); + } else { + velocity_ = NULL; + } + ::memcpy(&theta_, &from.theta_, + static_cast(reinterpret_cast(×tamp_) - + reinterpret_cast(&theta_)) + sizeof(timestamp_)); + // @@protoc_insertion_point(copy_constructor:apollo.perception.PerceptionObstacle) +} + +void PerceptionObstacle::SharedCtor() { + ::memset(&position_, 0, static_cast( + reinterpret_cast(×tamp_) - + reinterpret_cast(&position_)) + sizeof(timestamp_)); +} + +PerceptionObstacle::~PerceptionObstacle() { + // @@protoc_insertion_point(destructor:apollo.perception.PerceptionObstacle) + SharedDtor(); +} + +void PerceptionObstacle::SharedDtor() { + if (this != internal_default_instance()) delete position_; + if (this != internal_default_instance()) delete velocity_; +} + +void PerceptionObstacle::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* PerceptionObstacle::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const PerceptionObstacle& PerceptionObstacle::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::scc_info_PerceptionObstacle.base); + return *internal_default_instance(); +} + + +void PerceptionObstacle::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.perception.PerceptionObstacle) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + polygon_point_.Clear(); + point_cloud_.Clear(); + if (GetArenaNoVirtual() == NULL && position_ != NULL) { + delete position_; + } + position_ = NULL; + if (GetArenaNoVirtual() == NULL && velocity_ != NULL) { + delete velocity_; + } + velocity_ = NULL; + ::memset(&theta_, 0, static_cast( + reinterpret_cast(×tamp_) - + reinterpret_cast(&theta_)) + sizeof(timestamp_)); + _internal_metadata_.Clear(); +} + +bool PerceptionObstacle::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.perception.PerceptionObstacle) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // int32 id = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &id_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.perception.Point position = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_position())); + } else { + goto handle_unusual; + } + break; + } + + // double theta = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &theta_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.perception.Point velocity = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_velocity())); + } else { + goto handle_unusual; + } + break; + } + + // double length = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &length_))); + } else { + goto handle_unusual; + } + break; + } + + // double width = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &width_))); + } else { + goto handle_unusual; + } + break; + } + + // double height = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &height_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.perception.Point polygon_point = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(66u /* 66 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_polygon_point())); + } else { + goto handle_unusual; + } + break; + } + + // double tracking_time = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(73u /* 73 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &tracking_time_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.perception.PerceptionObstacle.Type type = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(80u /* 80 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_type(static_cast< ::apollo::perception::PerceptionObstacle_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // double timestamp = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(89u /* 89 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, ×tamp_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated double point_cloud = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(98u /* 98 & 0xFF */)) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, this->mutable_point_cloud()))); + } else if ( + static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(97u /* 97 & 0xFF */)) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + 1, 98u, input, this->mutable_point_cloud()))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.perception.PerceptionObstacle) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.perception.PerceptionObstacle) + return false; +#undef DO_ +} + +void PerceptionObstacle::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.perception.PerceptionObstacle) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // int32 id = 1; + if (this->id() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->id(), output); + } + + // .apollo.perception.Point position = 2; + if (this->has_position()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_position(), output); + } + + // double theta = 3; + if (this->theta() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->theta(), output); + } + + // .apollo.perception.Point velocity = 4; + if (this->has_velocity()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, this->_internal_velocity(), output); + } + + // double length = 5; + if (this->length() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->length(), output); + } + + // double width = 6; + if (this->width() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->width(), output); + } + + // double height = 7; + if (this->height() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->height(), output); + } + + // repeated .apollo.perception.Point polygon_point = 8; + for (unsigned int i = 0, + n = static_cast(this->polygon_point_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 8, + this->polygon_point(static_cast(i)), + output); + } + + // double tracking_time = 9; + if (this->tracking_time() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->tracking_time(), output); + } + + // .apollo.perception.PerceptionObstacle.Type type = 10; + if (this->type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 10, this->type(), output); + } + + // double timestamp = 11; + if (this->timestamp() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(11, this->timestamp(), output); + } + + // repeated double point_cloud = 12; + if (this->point_cloud_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(12, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(static_cast< ::google::protobuf::uint32>( + _point_cloud_cached_byte_size_)); + ::google::protobuf::internal::WireFormatLite::WriteDoubleArray( + this->point_cloud().data(), this->point_cloud_size(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.perception.PerceptionObstacle) +} + +::google::protobuf::uint8* PerceptionObstacle::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.perception.PerceptionObstacle) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // int32 id = 1; + if (this->id() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->id(), target); + } + + // .apollo.perception.Point position = 2; + if (this->has_position()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_position(), deterministic, target); + } + + // double theta = 3; + if (this->theta() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->theta(), target); + } + + // .apollo.perception.Point velocity = 4; + if (this->has_velocity()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->_internal_velocity(), deterministic, target); + } + + // double length = 5; + if (this->length() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->length(), target); + } + + // double width = 6; + if (this->width() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->width(), target); + } + + // double height = 7; + if (this->height() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->height(), target); + } + + // repeated .apollo.perception.Point polygon_point = 8; + for (unsigned int i = 0, + n = static_cast(this->polygon_point_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 8, this->polygon_point(static_cast(i)), deterministic, target); + } + + // double tracking_time = 9; + if (this->tracking_time() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->tracking_time(), target); + } + + // .apollo.perception.PerceptionObstacle.Type type = 10; + if (this->type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 10, this->type(), target); + } + + // double timestamp = 11; + if (this->timestamp() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(11, this->timestamp(), target); + } + + // repeated double point_cloud = 12; + if (this->point_cloud_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 12, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + static_cast< ::google::protobuf::int32>( + _point_cloud_cached_byte_size_), target); + target = ::google::protobuf::internal::WireFormatLite:: + WriteDoubleNoTagToArray(this->point_cloud_, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.perception.PerceptionObstacle) + return target; +} + +size_t PerceptionObstacle::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.perception.PerceptionObstacle) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.perception.Point polygon_point = 8; + { + unsigned int count = static_cast(this->polygon_point_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->polygon_point(static_cast(i))); + } + } + + // repeated double point_cloud = 12; + { + unsigned int count = static_cast(this->point_cloud_size()); + size_t data_size = 8UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + static_cast< ::google::protobuf::int32>(data_size)); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _point_cloud_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + // .apollo.perception.Point position = 2; + if (this->has_position()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *position_); + } + + // .apollo.perception.Point velocity = 4; + if (this->has_velocity()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *velocity_); + } + + // double theta = 3; + if (this->theta() != 0) { + total_size += 1 + 8; + } + + // double length = 5; + if (this->length() != 0) { + total_size += 1 + 8; + } + + // int32 id = 1; + if (this->id() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->id()); + } + + // .apollo.perception.PerceptionObstacle.Type type = 10; + if (this->type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->type()); + } + + // double width = 6; + if (this->width() != 0) { + total_size += 1 + 8; + } + + // double height = 7; + if (this->height() != 0) { + total_size += 1 + 8; + } + + // double tracking_time = 9; + if (this->tracking_time() != 0) { + total_size += 1 + 8; + } + + // double timestamp = 11; + if (this->timestamp() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void PerceptionObstacle::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.perception.PerceptionObstacle) + GOOGLE_DCHECK_NE(&from, this); + const PerceptionObstacle* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.perception.PerceptionObstacle) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.perception.PerceptionObstacle) + MergeFrom(*source); + } +} + +void PerceptionObstacle::MergeFrom(const PerceptionObstacle& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.perception.PerceptionObstacle) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + polygon_point_.MergeFrom(from.polygon_point_); + point_cloud_.MergeFrom(from.point_cloud_); + if (from.has_position()) { + mutable_position()->::apollo::perception::Point::MergeFrom(from.position()); + } + if (from.has_velocity()) { + mutable_velocity()->::apollo::perception::Point::MergeFrom(from.velocity()); + } + if (from.theta() != 0) { + set_theta(from.theta()); + } + if (from.length() != 0) { + set_length(from.length()); + } + if (from.id() != 0) { + set_id(from.id()); + } + if (from.type() != 0) { + set_type(from.type()); + } + if (from.width() != 0) { + set_width(from.width()); + } + if (from.height() != 0) { + set_height(from.height()); + } + if (from.tracking_time() != 0) { + set_tracking_time(from.tracking_time()); + } + if (from.timestamp() != 0) { + set_timestamp(from.timestamp()); + } +} + +void PerceptionObstacle::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.perception.PerceptionObstacle) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PerceptionObstacle::CopyFrom(const PerceptionObstacle& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.perception.PerceptionObstacle) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PerceptionObstacle::IsInitialized() const { + return true; +} + +void PerceptionObstacle::Swap(PerceptionObstacle* other) { + if (other == this) return; + InternalSwap(other); +} +void PerceptionObstacle::InternalSwap(PerceptionObstacle* other) { + using std::swap; + CastToBase(&polygon_point_)->InternalSwap(CastToBase(&other->polygon_point_)); + point_cloud_.InternalSwap(&other->point_cloud_); + swap(position_, other->position_); + swap(velocity_, other->velocity_); + swap(theta_, other->theta_); + swap(length_, other->length_); + swap(id_, other->id_); + swap(type_, other->type_); + swap(width_, other->width_); + swap(height_, other->height_); + swap(tracking_time_, other->tracking_time_); + swap(timestamp_, other->timestamp_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata PerceptionObstacle::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void PerceptionObstacles::InitAsDefaultInstance() { + ::apollo::perception::_PerceptionObstacles_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); +} +void PerceptionObstacles::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PerceptionObstacles::kPerceptionObstacleFieldNumber; +const int PerceptionObstacles::kHeaderFieldNumber; +const int PerceptionObstacles::kErrorCodeFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PerceptionObstacles::PerceptionObstacles() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::scc_info_PerceptionObstacles.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.perception.PerceptionObstacles) +} +PerceptionObstacles::PerceptionObstacles(const PerceptionObstacles& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + perception_obstacle_(from.perception_obstacle_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + error_code_ = from.error_code_; + // @@protoc_insertion_point(copy_constructor:apollo.perception.PerceptionObstacles) +} + +void PerceptionObstacles::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&error_code_) - + reinterpret_cast(&header_)) + sizeof(error_code_)); +} + +PerceptionObstacles::~PerceptionObstacles() { + // @@protoc_insertion_point(destructor:apollo.perception.PerceptionObstacles) + SharedDtor(); +} + +void PerceptionObstacles::SharedDtor() { + if (this != internal_default_instance()) delete header_; +} + +void PerceptionObstacles::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* PerceptionObstacles::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const PerceptionObstacles& PerceptionObstacles::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::scc_info_PerceptionObstacles.base); + return *internal_default_instance(); +} + + +void PerceptionObstacles::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.perception.PerceptionObstacles) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + perception_obstacle_.Clear(); + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + error_code_ = 0; + _internal_metadata_.Clear(); +} + +bool PerceptionObstacles::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.perception.PerceptionObstacles) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // repeated .apollo.perception.PerceptionObstacle perception_obstacle = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_perception_obstacle())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Header header = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.perception.PerceptionErrorCode error_code = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_error_code(static_cast< ::apollo::perception::PerceptionErrorCode >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.perception.PerceptionObstacles) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.perception.PerceptionObstacles) + return false; +#undef DO_ +} + +void PerceptionObstacles::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.perception.PerceptionObstacles) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.perception.PerceptionObstacle perception_obstacle = 1; + for (unsigned int i = 0, + n = static_cast(this->perception_obstacle_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, + this->perception_obstacle(static_cast(i)), + output); + } + + // .apollo.common.Header header = 2; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_header(), output); + } + + // .apollo.perception.PerceptionErrorCode error_code = 3; + if (this->error_code() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 3, this->error_code(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.perception.PerceptionObstacles) +} + +::google::protobuf::uint8* PerceptionObstacles::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.perception.PerceptionObstacles) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.perception.PerceptionObstacle perception_obstacle = 1; + for (unsigned int i = 0, + n = static_cast(this->perception_obstacle_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->perception_obstacle(static_cast(i)), deterministic, target); + } + + // .apollo.common.Header header = 2; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_header(), deterministic, target); + } + + // .apollo.perception.PerceptionErrorCode error_code = 3; + if (this->error_code() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 3, this->error_code(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.perception.PerceptionObstacles) + return target; +} + +size_t PerceptionObstacles::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.perception.PerceptionObstacles) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.perception.PerceptionObstacle perception_obstacle = 1; + { + unsigned int count = static_cast(this->perception_obstacle_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->perception_obstacle(static_cast(i))); + } + } + + // .apollo.common.Header header = 2; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.perception.PerceptionErrorCode error_code = 3; + if (this->error_code() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->error_code()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void PerceptionObstacles::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.perception.PerceptionObstacles) + GOOGLE_DCHECK_NE(&from, this); + const PerceptionObstacles* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.perception.PerceptionObstacles) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.perception.PerceptionObstacles) + MergeFrom(*source); + } +} + +void PerceptionObstacles::MergeFrom(const PerceptionObstacles& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.perception.PerceptionObstacles) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + perception_obstacle_.MergeFrom(from.perception_obstacle_); + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.error_code() != 0) { + set_error_code(from.error_code()); + } +} + +void PerceptionObstacles::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.perception.PerceptionObstacles) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PerceptionObstacles::CopyFrom(const PerceptionObstacles& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.perception.PerceptionObstacles) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PerceptionObstacles::IsInitialized() const { + return true; +} + +void PerceptionObstacles::Swap(PerceptionObstacles* other) { + if (other == this) return; + InternalSwap(other); +} +void PerceptionObstacles::InternalSwap(PerceptionObstacles* other) { + using std::swap; + CastToBase(&perception_obstacle_)->InternalSwap(CastToBase(&other->perception_obstacle_)); + swap(header_, other->header_); + swap(error_code_, other->error_code_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata PerceptionObstacles::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace perception +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::perception::Point* Arena::CreateMaybeMessage< ::apollo::perception::Point >(Arena* arena) { + return Arena::CreateInternal< ::apollo::perception::Point >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::perception::PerceptionObstacle* Arena::CreateMaybeMessage< ::apollo::perception::PerceptionObstacle >(Arena* arena) { + return Arena::CreateInternal< ::apollo::perception::PerceptionObstacle >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::perception::PerceptionObstacles* Arena::CreateMaybeMessage< ::apollo::perception::PerceptionObstacles >(Arena* arena) { + return Arena::CreateInternal< ::apollo::perception::PerceptionObstacles >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/perception/perception_obstacle.pb.h b/apollo_msgs/include/apollo_msgs/proto/perception/perception_obstacle.pb.h new file mode 100644 index 0000000..ecc41a3 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/perception/perception_obstacle.pb.h @@ -0,0 +1,1071 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/perception/perception_obstacle.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "apollo_msgs/proto/common/header.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[3]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto +namespace apollo { +namespace perception { +class PerceptionObstacle; +class PerceptionObstacleDefaultTypeInternal; +extern PerceptionObstacleDefaultTypeInternal _PerceptionObstacle_default_instance_; +class PerceptionObstacles; +class PerceptionObstaclesDefaultTypeInternal; +extern PerceptionObstaclesDefaultTypeInternal _PerceptionObstacles_default_instance_; +class Point; +class PointDefaultTypeInternal; +extern PointDefaultTypeInternal _Point_default_instance_; +} // namespace perception +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::perception::PerceptionObstacle* Arena::CreateMaybeMessage<::apollo::perception::PerceptionObstacle>(Arena*); +template<> ::apollo::perception::PerceptionObstacles* Arena::CreateMaybeMessage<::apollo::perception::PerceptionObstacles>(Arena*); +template<> ::apollo::perception::Point* Arena::CreateMaybeMessage<::apollo::perception::Point>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace perception { + +enum PerceptionObstacle_Type { + PerceptionObstacle_Type_UNKNOWN = 0, + PerceptionObstacle_Type_UNKNOWN_MOVABLE = 1, + PerceptionObstacle_Type_UNKNOWN_UNMOVABLE = 2, + PerceptionObstacle_Type_PEDESTRIAN = 3, + PerceptionObstacle_Type_BICYCLE = 4, + PerceptionObstacle_Type_VEHICLE = 5, + PerceptionObstacle_Type_PerceptionObstacle_Type_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + PerceptionObstacle_Type_PerceptionObstacle_Type_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool PerceptionObstacle_Type_IsValid(int value); +const PerceptionObstacle_Type PerceptionObstacle_Type_Type_MIN = PerceptionObstacle_Type_UNKNOWN; +const PerceptionObstacle_Type PerceptionObstacle_Type_Type_MAX = PerceptionObstacle_Type_VEHICLE; +const int PerceptionObstacle_Type_Type_ARRAYSIZE = PerceptionObstacle_Type_Type_MAX + 1; + +const ::google::protobuf::EnumDescriptor* PerceptionObstacle_Type_descriptor(); +inline const ::std::string& PerceptionObstacle_Type_Name(PerceptionObstacle_Type value) { + return ::google::protobuf::internal::NameOfEnum( + PerceptionObstacle_Type_descriptor(), value); +} +inline bool PerceptionObstacle_Type_Parse( + const ::std::string& name, PerceptionObstacle_Type* value) { + return ::google::protobuf::internal::ParseNamedEnum( + PerceptionObstacle_Type_descriptor(), name, value); +} +enum PerceptionErrorCode { + ERROR_NONE = 0, + ERROR_TF = 1, + ERROR_PROCESS = 2, + ERROR_UNKNOWN = 3, + PerceptionErrorCode_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + PerceptionErrorCode_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool PerceptionErrorCode_IsValid(int value); +const PerceptionErrorCode PerceptionErrorCode_MIN = ERROR_NONE; +const PerceptionErrorCode PerceptionErrorCode_MAX = ERROR_UNKNOWN; +const int PerceptionErrorCode_ARRAYSIZE = PerceptionErrorCode_MAX + 1; + +const ::google::protobuf::EnumDescriptor* PerceptionErrorCode_descriptor(); +inline const ::std::string& PerceptionErrorCode_Name(PerceptionErrorCode value) { + return ::google::protobuf::internal::NameOfEnum( + PerceptionErrorCode_descriptor(), value); +} +inline bool PerceptionErrorCode_Parse( + const ::std::string& name, PerceptionErrorCode* value) { + return ::google::protobuf::internal::ParseNamedEnum( + PerceptionErrorCode_descriptor(), name, value); +} +// =================================================================== + +class Point : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.perception.Point) */ { + public: + Point(); + virtual ~Point(); + + Point(const Point& from); + + inline Point& operator=(const Point& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Point(Point&& from) noexcept + : Point() { + *this = ::std::move(from); + } + + inline Point& operator=(Point&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Point& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Point* internal_default_instance() { + return reinterpret_cast( + &_Point_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(Point* other); + friend void swap(Point& a, Point& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Point* New() const final { + return CreateMaybeMessage(NULL); + } + + Point* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Point& from); + void MergeFrom(const Point& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Point* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double x = 1; + void clear_x(); + static const int kXFieldNumber = 1; + double x() const; + void set_x(double value); + + // double y = 2; + void clear_y(); + static const int kYFieldNumber = 2; + double y() const; + void set_y(double value); + + // double z = 3; + void clear_z(); + static const int kZFieldNumber = 3; + double z() const; + void set_z(double value); + + // @@protoc_insertion_point(class_scope:apollo.perception.Point) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double x_; + double y_; + double z_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class PerceptionObstacle : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.perception.PerceptionObstacle) */ { + public: + PerceptionObstacle(); + virtual ~PerceptionObstacle(); + + PerceptionObstacle(const PerceptionObstacle& from); + + inline PerceptionObstacle& operator=(const PerceptionObstacle& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + PerceptionObstacle(PerceptionObstacle&& from) noexcept + : PerceptionObstacle() { + *this = ::std::move(from); + } + + inline PerceptionObstacle& operator=(PerceptionObstacle&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const PerceptionObstacle& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const PerceptionObstacle* internal_default_instance() { + return reinterpret_cast( + &_PerceptionObstacle_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(PerceptionObstacle* other); + friend void swap(PerceptionObstacle& a, PerceptionObstacle& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline PerceptionObstacle* New() const final { + return CreateMaybeMessage(NULL); + } + + PerceptionObstacle* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const PerceptionObstacle& from); + void MergeFrom(const PerceptionObstacle& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(PerceptionObstacle* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef PerceptionObstacle_Type Type; + static const Type UNKNOWN = + PerceptionObstacle_Type_UNKNOWN; + static const Type UNKNOWN_MOVABLE = + PerceptionObstacle_Type_UNKNOWN_MOVABLE; + static const Type UNKNOWN_UNMOVABLE = + PerceptionObstacle_Type_UNKNOWN_UNMOVABLE; + static const Type PEDESTRIAN = + PerceptionObstacle_Type_PEDESTRIAN; + static const Type BICYCLE = + PerceptionObstacle_Type_BICYCLE; + static const Type VEHICLE = + PerceptionObstacle_Type_VEHICLE; + static inline bool Type_IsValid(int value) { + return PerceptionObstacle_Type_IsValid(value); + } + static const Type Type_MIN = + PerceptionObstacle_Type_Type_MIN; + static const Type Type_MAX = + PerceptionObstacle_Type_Type_MAX; + static const int Type_ARRAYSIZE = + PerceptionObstacle_Type_Type_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Type_descriptor() { + return PerceptionObstacle_Type_descriptor(); + } + static inline const ::std::string& Type_Name(Type value) { + return PerceptionObstacle_Type_Name(value); + } + static inline bool Type_Parse(const ::std::string& name, + Type* value) { + return PerceptionObstacle_Type_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // repeated .apollo.perception.Point polygon_point = 8; + int polygon_point_size() const; + void clear_polygon_point(); + static const int kPolygonPointFieldNumber = 8; + ::apollo::perception::Point* mutable_polygon_point(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::perception::Point >* + mutable_polygon_point(); + const ::apollo::perception::Point& polygon_point(int index) const; + ::apollo::perception::Point* add_polygon_point(); + const ::google::protobuf::RepeatedPtrField< ::apollo::perception::Point >& + polygon_point() const; + + // repeated double point_cloud = 12; + int point_cloud_size() const; + void clear_point_cloud(); + static const int kPointCloudFieldNumber = 12; + double point_cloud(int index) const; + void set_point_cloud(int index, double value); + void add_point_cloud(double value); + const ::google::protobuf::RepeatedField< double >& + point_cloud() const; + ::google::protobuf::RepeatedField< double >* + mutable_point_cloud(); + + // .apollo.perception.Point position = 2; + bool has_position() const; + void clear_position(); + static const int kPositionFieldNumber = 2; + private: + const ::apollo::perception::Point& _internal_position() const; + public: + const ::apollo::perception::Point& position() const; + ::apollo::perception::Point* release_position(); + ::apollo::perception::Point* mutable_position(); + void set_allocated_position(::apollo::perception::Point* position); + + // .apollo.perception.Point velocity = 4; + bool has_velocity() const; + void clear_velocity(); + static const int kVelocityFieldNumber = 4; + private: + const ::apollo::perception::Point& _internal_velocity() const; + public: + const ::apollo::perception::Point& velocity() const; + ::apollo::perception::Point* release_velocity(); + ::apollo::perception::Point* mutable_velocity(); + void set_allocated_velocity(::apollo::perception::Point* velocity); + + // double theta = 3; + void clear_theta(); + static const int kThetaFieldNumber = 3; + double theta() const; + void set_theta(double value); + + // double length = 5; + void clear_length(); + static const int kLengthFieldNumber = 5; + double length() const; + void set_length(double value); + + // int32 id = 1; + void clear_id(); + static const int kIdFieldNumber = 1; + ::google::protobuf::int32 id() const; + void set_id(::google::protobuf::int32 value); + + // .apollo.perception.PerceptionObstacle.Type type = 10; + void clear_type(); + static const int kTypeFieldNumber = 10; + ::apollo::perception::PerceptionObstacle_Type type() const; + void set_type(::apollo::perception::PerceptionObstacle_Type value); + + // double width = 6; + void clear_width(); + static const int kWidthFieldNumber = 6; + double width() const; + void set_width(double value); + + // double height = 7; + void clear_height(); + static const int kHeightFieldNumber = 7; + double height() const; + void set_height(double value); + + // double tracking_time = 9; + void clear_tracking_time(); + static const int kTrackingTimeFieldNumber = 9; + double tracking_time() const; + void set_tracking_time(double value); + + // double timestamp = 11; + void clear_timestamp(); + static const int kTimestampFieldNumber = 11; + double timestamp() const; + void set_timestamp(double value); + + // @@protoc_insertion_point(class_scope:apollo.perception.PerceptionObstacle) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::perception::Point > polygon_point_; + ::google::protobuf::RepeatedField< double > point_cloud_; + mutable int _point_cloud_cached_byte_size_; + ::apollo::perception::Point* position_; + ::apollo::perception::Point* velocity_; + double theta_; + double length_; + ::google::protobuf::int32 id_; + int type_; + double width_; + double height_; + double tracking_time_; + double timestamp_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class PerceptionObstacles : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.perception.PerceptionObstacles) */ { + public: + PerceptionObstacles(); + virtual ~PerceptionObstacles(); + + PerceptionObstacles(const PerceptionObstacles& from); + + inline PerceptionObstacles& operator=(const PerceptionObstacles& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + PerceptionObstacles(PerceptionObstacles&& from) noexcept + : PerceptionObstacles() { + *this = ::std::move(from); + } + + inline PerceptionObstacles& operator=(PerceptionObstacles&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const PerceptionObstacles& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const PerceptionObstacles* internal_default_instance() { + return reinterpret_cast( + &_PerceptionObstacles_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + void Swap(PerceptionObstacles* other); + friend void swap(PerceptionObstacles& a, PerceptionObstacles& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline PerceptionObstacles* New() const final { + return CreateMaybeMessage(NULL); + } + + PerceptionObstacles* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const PerceptionObstacles& from); + void MergeFrom(const PerceptionObstacles& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(PerceptionObstacles* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.perception.PerceptionObstacle perception_obstacle = 1; + int perception_obstacle_size() const; + void clear_perception_obstacle(); + static const int kPerceptionObstacleFieldNumber = 1; + ::apollo::perception::PerceptionObstacle* mutable_perception_obstacle(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::perception::PerceptionObstacle >* + mutable_perception_obstacle(); + const ::apollo::perception::PerceptionObstacle& perception_obstacle(int index) const; + ::apollo::perception::PerceptionObstacle* add_perception_obstacle(); + const ::google::protobuf::RepeatedPtrField< ::apollo::perception::PerceptionObstacle >& + perception_obstacle() const; + + // .apollo.common.Header header = 2; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 2; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.perception.PerceptionErrorCode error_code = 3; + void clear_error_code(); + static const int kErrorCodeFieldNumber = 3; + ::apollo::perception::PerceptionErrorCode error_code() const; + void set_error_code(::apollo::perception::PerceptionErrorCode value); + + // @@protoc_insertion_point(class_scope:apollo.perception.PerceptionObstacles) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::perception::PerceptionObstacle > perception_obstacle_; + ::apollo::common::Header* header_; + int error_code_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// Point + +// double x = 1; +inline void Point::clear_x() { + x_ = 0; +} +inline double Point::x() const { + // @@protoc_insertion_point(field_get:apollo.perception.Point.x) + return x_; +} +inline void Point::set_x(double value) { + + x_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.Point.x) +} + +// double y = 2; +inline void Point::clear_y() { + y_ = 0; +} +inline double Point::y() const { + // @@protoc_insertion_point(field_get:apollo.perception.Point.y) + return y_; +} +inline void Point::set_y(double value) { + + y_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.Point.y) +} + +// double z = 3; +inline void Point::clear_z() { + z_ = 0; +} +inline double Point::z() const { + // @@protoc_insertion_point(field_get:apollo.perception.Point.z) + return z_; +} +inline void Point::set_z(double value) { + + z_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.Point.z) +} + +// ------------------------------------------------------------------- + +// PerceptionObstacle + +// int32 id = 1; +inline void PerceptionObstacle::clear_id() { + id_ = 0; +} +inline ::google::protobuf::int32 PerceptionObstacle::id() const { + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacle.id) + return id_; +} +inline void PerceptionObstacle::set_id(::google::protobuf::int32 value) { + + id_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.PerceptionObstacle.id) +} + +// .apollo.perception.Point position = 2; +inline bool PerceptionObstacle::has_position() const { + return this != internal_default_instance() && position_ != NULL; +} +inline void PerceptionObstacle::clear_position() { + if (GetArenaNoVirtual() == NULL && position_ != NULL) { + delete position_; + } + position_ = NULL; +} +inline const ::apollo::perception::Point& PerceptionObstacle::_internal_position() const { + return *position_; +} +inline const ::apollo::perception::Point& PerceptionObstacle::position() const { + const ::apollo::perception::Point* p = position_; + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacle.position) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::perception::_Point_default_instance_); +} +inline ::apollo::perception::Point* PerceptionObstacle::release_position() { + // @@protoc_insertion_point(field_release:apollo.perception.PerceptionObstacle.position) + + ::apollo::perception::Point* temp = position_; + position_ = NULL; + return temp; +} +inline ::apollo::perception::Point* PerceptionObstacle::mutable_position() { + + if (position_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::perception::Point>(GetArenaNoVirtual()); + position_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.perception.PerceptionObstacle.position) + return position_; +} +inline void PerceptionObstacle::set_allocated_position(::apollo::perception::Point* position) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete position_; + } + if (position) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + position = ::google::protobuf::internal::GetOwnedMessage( + message_arena, position, submessage_arena); + } + + } else { + + } + position_ = position; + // @@protoc_insertion_point(field_set_allocated:apollo.perception.PerceptionObstacle.position) +} + +// double theta = 3; +inline void PerceptionObstacle::clear_theta() { + theta_ = 0; +} +inline double PerceptionObstacle::theta() const { + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacle.theta) + return theta_; +} +inline void PerceptionObstacle::set_theta(double value) { + + theta_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.PerceptionObstacle.theta) +} + +// .apollo.perception.Point velocity = 4; +inline bool PerceptionObstacle::has_velocity() const { + return this != internal_default_instance() && velocity_ != NULL; +} +inline void PerceptionObstacle::clear_velocity() { + if (GetArenaNoVirtual() == NULL && velocity_ != NULL) { + delete velocity_; + } + velocity_ = NULL; +} +inline const ::apollo::perception::Point& PerceptionObstacle::_internal_velocity() const { + return *velocity_; +} +inline const ::apollo::perception::Point& PerceptionObstacle::velocity() const { + const ::apollo::perception::Point* p = velocity_; + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacle.velocity) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::perception::_Point_default_instance_); +} +inline ::apollo::perception::Point* PerceptionObstacle::release_velocity() { + // @@protoc_insertion_point(field_release:apollo.perception.PerceptionObstacle.velocity) + + ::apollo::perception::Point* temp = velocity_; + velocity_ = NULL; + return temp; +} +inline ::apollo::perception::Point* PerceptionObstacle::mutable_velocity() { + + if (velocity_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::perception::Point>(GetArenaNoVirtual()); + velocity_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.perception.PerceptionObstacle.velocity) + return velocity_; +} +inline void PerceptionObstacle::set_allocated_velocity(::apollo::perception::Point* velocity) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete velocity_; + } + if (velocity) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + velocity = ::google::protobuf::internal::GetOwnedMessage( + message_arena, velocity, submessage_arena); + } + + } else { + + } + velocity_ = velocity; + // @@protoc_insertion_point(field_set_allocated:apollo.perception.PerceptionObstacle.velocity) +} + +// double length = 5; +inline void PerceptionObstacle::clear_length() { + length_ = 0; +} +inline double PerceptionObstacle::length() const { + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacle.length) + return length_; +} +inline void PerceptionObstacle::set_length(double value) { + + length_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.PerceptionObstacle.length) +} + +// double width = 6; +inline void PerceptionObstacle::clear_width() { + width_ = 0; +} +inline double PerceptionObstacle::width() const { + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacle.width) + return width_; +} +inline void PerceptionObstacle::set_width(double value) { + + width_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.PerceptionObstacle.width) +} + +// double height = 7; +inline void PerceptionObstacle::clear_height() { + height_ = 0; +} +inline double PerceptionObstacle::height() const { + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacle.height) + return height_; +} +inline void PerceptionObstacle::set_height(double value) { + + height_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.PerceptionObstacle.height) +} + +// repeated .apollo.perception.Point polygon_point = 8; +inline int PerceptionObstacle::polygon_point_size() const { + return polygon_point_.size(); +} +inline void PerceptionObstacle::clear_polygon_point() { + polygon_point_.Clear(); +} +inline ::apollo::perception::Point* PerceptionObstacle::mutable_polygon_point(int index) { + // @@protoc_insertion_point(field_mutable:apollo.perception.PerceptionObstacle.polygon_point) + return polygon_point_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::perception::Point >* +PerceptionObstacle::mutable_polygon_point() { + // @@protoc_insertion_point(field_mutable_list:apollo.perception.PerceptionObstacle.polygon_point) + return &polygon_point_; +} +inline const ::apollo::perception::Point& PerceptionObstacle::polygon_point(int index) const { + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacle.polygon_point) + return polygon_point_.Get(index); +} +inline ::apollo::perception::Point* PerceptionObstacle::add_polygon_point() { + // @@protoc_insertion_point(field_add:apollo.perception.PerceptionObstacle.polygon_point) + return polygon_point_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::perception::Point >& +PerceptionObstacle::polygon_point() const { + // @@protoc_insertion_point(field_list:apollo.perception.PerceptionObstacle.polygon_point) + return polygon_point_; +} + +// double tracking_time = 9; +inline void PerceptionObstacle::clear_tracking_time() { + tracking_time_ = 0; +} +inline double PerceptionObstacle::tracking_time() const { + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacle.tracking_time) + return tracking_time_; +} +inline void PerceptionObstacle::set_tracking_time(double value) { + + tracking_time_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.PerceptionObstacle.tracking_time) +} + +// .apollo.perception.PerceptionObstacle.Type type = 10; +inline void PerceptionObstacle::clear_type() { + type_ = 0; +} +inline ::apollo::perception::PerceptionObstacle_Type PerceptionObstacle::type() const { + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacle.type) + return static_cast< ::apollo::perception::PerceptionObstacle_Type >(type_); +} +inline void PerceptionObstacle::set_type(::apollo::perception::PerceptionObstacle_Type value) { + + type_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.PerceptionObstacle.type) +} + +// double timestamp = 11; +inline void PerceptionObstacle::clear_timestamp() { + timestamp_ = 0; +} +inline double PerceptionObstacle::timestamp() const { + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacle.timestamp) + return timestamp_; +} +inline void PerceptionObstacle::set_timestamp(double value) { + + timestamp_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.PerceptionObstacle.timestamp) +} + +// repeated double point_cloud = 12; +inline int PerceptionObstacle::point_cloud_size() const { + return point_cloud_.size(); +} +inline void PerceptionObstacle::clear_point_cloud() { + point_cloud_.Clear(); +} +inline double PerceptionObstacle::point_cloud(int index) const { + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacle.point_cloud) + return point_cloud_.Get(index); +} +inline void PerceptionObstacle::set_point_cloud(int index, double value) { + point_cloud_.Set(index, value); + // @@protoc_insertion_point(field_set:apollo.perception.PerceptionObstacle.point_cloud) +} +inline void PerceptionObstacle::add_point_cloud(double value) { + point_cloud_.Add(value); + // @@protoc_insertion_point(field_add:apollo.perception.PerceptionObstacle.point_cloud) +} +inline const ::google::protobuf::RepeatedField< double >& +PerceptionObstacle::point_cloud() const { + // @@protoc_insertion_point(field_list:apollo.perception.PerceptionObstacle.point_cloud) + return point_cloud_; +} +inline ::google::protobuf::RepeatedField< double >* +PerceptionObstacle::mutable_point_cloud() { + // @@protoc_insertion_point(field_mutable_list:apollo.perception.PerceptionObstacle.point_cloud) + return &point_cloud_; +} + +// ------------------------------------------------------------------- + +// PerceptionObstacles + +// repeated .apollo.perception.PerceptionObstacle perception_obstacle = 1; +inline int PerceptionObstacles::perception_obstacle_size() const { + return perception_obstacle_.size(); +} +inline void PerceptionObstacles::clear_perception_obstacle() { + perception_obstacle_.Clear(); +} +inline ::apollo::perception::PerceptionObstacle* PerceptionObstacles::mutable_perception_obstacle(int index) { + // @@protoc_insertion_point(field_mutable:apollo.perception.PerceptionObstacles.perception_obstacle) + return perception_obstacle_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::perception::PerceptionObstacle >* +PerceptionObstacles::mutable_perception_obstacle() { + // @@protoc_insertion_point(field_mutable_list:apollo.perception.PerceptionObstacles.perception_obstacle) + return &perception_obstacle_; +} +inline const ::apollo::perception::PerceptionObstacle& PerceptionObstacles::perception_obstacle(int index) const { + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacles.perception_obstacle) + return perception_obstacle_.Get(index); +} +inline ::apollo::perception::PerceptionObstacle* PerceptionObstacles::add_perception_obstacle() { + // @@protoc_insertion_point(field_add:apollo.perception.PerceptionObstacles.perception_obstacle) + return perception_obstacle_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::perception::PerceptionObstacle >& +PerceptionObstacles::perception_obstacle() const { + // @@protoc_insertion_point(field_list:apollo.perception.PerceptionObstacles.perception_obstacle) + return perception_obstacle_; +} + +// .apollo.common.Header header = 2; +inline bool PerceptionObstacles::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& PerceptionObstacles::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& PerceptionObstacles::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacles.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* PerceptionObstacles::release_header() { + // @@protoc_insertion_point(field_release:apollo.perception.PerceptionObstacles.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* PerceptionObstacles::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.perception.PerceptionObstacles.header) + return header_; +} +inline void PerceptionObstacles::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.perception.PerceptionObstacles.header) +} + +// .apollo.perception.PerceptionErrorCode error_code = 3; +inline void PerceptionObstacles::clear_error_code() { + error_code_ = 0; +} +inline ::apollo::perception::PerceptionErrorCode PerceptionObstacles::error_code() const { + // @@protoc_insertion_point(field_get:apollo.perception.PerceptionObstacles.error_code) + return static_cast< ::apollo::perception::PerceptionErrorCode >(error_code_); +} +inline void PerceptionObstacles::set_error_code(::apollo::perception::PerceptionErrorCode value) { + + error_code_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.PerceptionObstacles.error_code) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace perception +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::perception::PerceptionObstacle_Type> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::perception::PerceptionObstacle_Type>() { + return ::apollo::perception::PerceptionObstacle_Type_descriptor(); +} +template <> struct is_proto_enum< ::apollo::perception::PerceptionErrorCode> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::perception::PerceptionErrorCode>() { + return ::apollo::perception::PerceptionErrorCode_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/perception/traffic_light_detection.pb.cc b/apollo_msgs/include/apollo_msgs/proto/perception/traffic_light_detection.pb.cc new file mode 100644 index 0000000..2862093 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/perception/traffic_light_detection.pb.cc @@ -0,0 +1,844 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/perception/traffic_light_detection.proto + +#include "apollo_msgs/proto/perception/traffic_light_detection.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_TrafficLight; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto +namespace apollo { +namespace perception { +class TrafficLightDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _TrafficLight_default_instance_; +class TrafficLightDetectionDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _TrafficLightDetection_default_instance_; +} // namespace perception +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto { +static void InitDefaultsTrafficLight() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::perception::_TrafficLight_default_instance_; + new (ptr) ::apollo::perception::TrafficLight(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::perception::TrafficLight::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_TrafficLight = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsTrafficLight}, {}}; + +static void InitDefaultsTrafficLightDetection() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::perception::_TrafficLightDetection_default_instance_; + new (ptr) ::apollo::perception::TrafficLightDetection(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::perception::TrafficLightDetection::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_TrafficLightDetection = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsTrafficLightDetection}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base, + &protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::scc_info_TrafficLight.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_TrafficLight.base); + ::google::protobuf::internal::InitSCC(&scc_info_TrafficLightDetection.base); +} + +::google::protobuf::Metadata file_level_metadata[2]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::TrafficLight, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::TrafficLight, color_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::TrafficLight, id_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::TrafficLight, confidence_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::TrafficLight, tracking_time_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::TrafficLightDetection, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::TrafficLightDetection, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::perception::TrafficLightDetection, traffic_light_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::perception::TrafficLight)}, + { 9, -1, sizeof(::apollo::perception::TrafficLightDetection)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::perception::_TrafficLight_default_instance_), + reinterpret_cast(&::apollo::perception::_TrafficLightDetection_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/perception/traffic_light_detection.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 2); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n:apollo_msgs/proto/perception/traffic_l" + "ight_detection.proto\022\021apollo.perception\032" + "%apollo_msgs/proto/common/header.proto\"\261" + "\001\n\014TrafficLight\0224\n\005color\030\001 \001(\0162%.apollo." + "perception.TrafficLight.Color\022\n\n\002id\030\002 \001(" + "\t\022\022\n\nconfidence\030\003 \001(\001\022\025\n\rtracking_time\030\004" + " \001(\001\"4\n\005Color\022\013\n\007UNKNOWN\020\000\022\007\n\003RED\020\001\022\n\n\006Y" + "ELLOW\020\002\022\t\n\005GREEN\020\003\"v\n\025TrafficLightDetect" + "ion\022%\n\006header\030\002 \001(\0132\025.apollo.common.Head" + "er\0226\n\rtraffic_light\030\001 \003(\0132\037.apollo.perce" + "ption.TrafficLightb\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 426); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/perception/traffic_light_detection.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto +namespace apollo { +namespace perception { +const ::google::protobuf::EnumDescriptor* TrafficLight_Color_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::file_level_enum_descriptors[0]; +} +bool TrafficLight_Color_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const TrafficLight_Color TrafficLight::UNKNOWN; +const TrafficLight_Color TrafficLight::RED; +const TrafficLight_Color TrafficLight::YELLOW; +const TrafficLight_Color TrafficLight::GREEN; +const TrafficLight_Color TrafficLight::Color_MIN; +const TrafficLight_Color TrafficLight::Color_MAX; +const int TrafficLight::Color_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +// =================================================================== + +void TrafficLight::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int TrafficLight::kColorFieldNumber; +const int TrafficLight::kIdFieldNumber; +const int TrafficLight::kConfidenceFieldNumber; +const int TrafficLight::kTrackingTimeFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +TrafficLight::TrafficLight() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::scc_info_TrafficLight.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.perception.TrafficLight) +} +TrafficLight::TrafficLight(const TrafficLight& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.id().size() > 0) { + id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.id_); + } + ::memcpy(&confidence_, &from.confidence_, + static_cast(reinterpret_cast(&color_) - + reinterpret_cast(&confidence_)) + sizeof(color_)); + // @@protoc_insertion_point(copy_constructor:apollo.perception.TrafficLight) +} + +void TrafficLight::SharedCtor() { + id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&confidence_, 0, static_cast( + reinterpret_cast(&color_) - + reinterpret_cast(&confidence_)) + sizeof(color_)); +} + +TrafficLight::~TrafficLight() { + // @@protoc_insertion_point(destructor:apollo.perception.TrafficLight) + SharedDtor(); +} + +void TrafficLight::SharedDtor() { + id_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} + +void TrafficLight::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* TrafficLight::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const TrafficLight& TrafficLight::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::scc_info_TrafficLight.base); + return *internal_default_instance(); +} + + +void TrafficLight::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.perception.TrafficLight) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&confidence_, 0, static_cast( + reinterpret_cast(&color_) - + reinterpret_cast(&confidence_)) + sizeof(color_)); + _internal_metadata_.Clear(); +} + +bool TrafficLight::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.perception.TrafficLight) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.perception.TrafficLight.Color color = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_color(static_cast< ::apollo::perception::TrafficLight_Color >(value)); + } else { + goto handle_unusual; + } + break; + } + + // string id = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_id())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->id().data(), static_cast(this->id().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.perception.TrafficLight.id")); + } else { + goto handle_unusual; + } + break; + } + + // double confidence = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &confidence_))); + } else { + goto handle_unusual; + } + break; + } + + // double tracking_time = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &tracking_time_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.perception.TrafficLight) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.perception.TrafficLight) + return false; +#undef DO_ +} + +void TrafficLight::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.perception.TrafficLight) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.perception.TrafficLight.Color color = 1; + if (this->color() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->color(), output); + } + + // string id = 2; + if (this->id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->id().data(), static_cast(this->id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.perception.TrafficLight.id"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 2, this->id(), output); + } + + // double confidence = 3; + if (this->confidence() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->confidence(), output); + } + + // double tracking_time = 4; + if (this->tracking_time() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->tracking_time(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.perception.TrafficLight) +} + +::google::protobuf::uint8* TrafficLight::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.perception.TrafficLight) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.perception.TrafficLight.Color color = 1; + if (this->color() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->color(), target); + } + + // string id = 2; + if (this->id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->id().data(), static_cast(this->id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.perception.TrafficLight.id"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 2, this->id(), target); + } + + // double confidence = 3; + if (this->confidence() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->confidence(), target); + } + + // double tracking_time = 4; + if (this->tracking_time() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->tracking_time(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.perception.TrafficLight) + return target; +} + +size_t TrafficLight::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.perception.TrafficLight) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // string id = 2; + if (this->id().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->id()); + } + + // double confidence = 3; + if (this->confidence() != 0) { + total_size += 1 + 8; + } + + // double tracking_time = 4; + if (this->tracking_time() != 0) { + total_size += 1 + 8; + } + + // .apollo.perception.TrafficLight.Color color = 1; + if (this->color() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->color()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void TrafficLight::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.perception.TrafficLight) + GOOGLE_DCHECK_NE(&from, this); + const TrafficLight* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.perception.TrafficLight) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.perception.TrafficLight) + MergeFrom(*source); + } +} + +void TrafficLight::MergeFrom(const TrafficLight& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.perception.TrafficLight) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.id().size() > 0) { + + id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.id_); + } + if (from.confidence() != 0) { + set_confidence(from.confidence()); + } + if (from.tracking_time() != 0) { + set_tracking_time(from.tracking_time()); + } + if (from.color() != 0) { + set_color(from.color()); + } +} + +void TrafficLight::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.perception.TrafficLight) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void TrafficLight::CopyFrom(const TrafficLight& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.perception.TrafficLight) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool TrafficLight::IsInitialized() const { + return true; +} + +void TrafficLight::Swap(TrafficLight* other) { + if (other == this) return; + InternalSwap(other); +} +void TrafficLight::InternalSwap(TrafficLight* other) { + using std::swap; + id_.Swap(&other->id_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(confidence_, other->confidence_); + swap(tracking_time_, other->tracking_time_); + swap(color_, other->color_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata TrafficLight::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void TrafficLightDetection::InitAsDefaultInstance() { + ::apollo::perception::_TrafficLightDetection_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); +} +void TrafficLightDetection::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int TrafficLightDetection::kHeaderFieldNumber; +const int TrafficLightDetection::kTrafficLightFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +TrafficLightDetection::TrafficLightDetection() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::scc_info_TrafficLightDetection.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.perception.TrafficLightDetection) +} +TrafficLightDetection::TrafficLightDetection(const TrafficLightDetection& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + traffic_light_(from.traffic_light_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.perception.TrafficLightDetection) +} + +void TrafficLightDetection::SharedCtor() { + header_ = NULL; +} + +TrafficLightDetection::~TrafficLightDetection() { + // @@protoc_insertion_point(destructor:apollo.perception.TrafficLightDetection) + SharedDtor(); +} + +void TrafficLightDetection::SharedDtor() { + if (this != internal_default_instance()) delete header_; +} + +void TrafficLightDetection::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* TrafficLightDetection::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const TrafficLightDetection& TrafficLightDetection::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::scc_info_TrafficLightDetection.base); + return *internal_default_instance(); +} + + +void TrafficLightDetection::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.perception.TrafficLightDetection) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + traffic_light_.Clear(); + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + _internal_metadata_.Clear(); +} + +bool TrafficLightDetection::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.perception.TrafficLightDetection) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // repeated .apollo.perception.TrafficLight traffic_light = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_traffic_light())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.common.Header header = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.perception.TrafficLightDetection) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.perception.TrafficLightDetection) + return false; +#undef DO_ +} + +void TrafficLightDetection::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.perception.TrafficLightDetection) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.perception.TrafficLight traffic_light = 1; + for (unsigned int i = 0, + n = static_cast(this->traffic_light_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, + this->traffic_light(static_cast(i)), + output); + } + + // .apollo.common.Header header = 2; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_header(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.perception.TrafficLightDetection) +} + +::google::protobuf::uint8* TrafficLightDetection::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.perception.TrafficLightDetection) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.perception.TrafficLight traffic_light = 1; + for (unsigned int i = 0, + n = static_cast(this->traffic_light_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->traffic_light(static_cast(i)), deterministic, target); + } + + // .apollo.common.Header header = 2; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_header(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.perception.TrafficLightDetection) + return target; +} + +size_t TrafficLightDetection::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.perception.TrafficLightDetection) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.perception.TrafficLight traffic_light = 1; + { + unsigned int count = static_cast(this->traffic_light_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->traffic_light(static_cast(i))); + } + } + + // .apollo.common.Header header = 2; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void TrafficLightDetection::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.perception.TrafficLightDetection) + GOOGLE_DCHECK_NE(&from, this); + const TrafficLightDetection* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.perception.TrafficLightDetection) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.perception.TrafficLightDetection) + MergeFrom(*source); + } +} + +void TrafficLightDetection::MergeFrom(const TrafficLightDetection& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.perception.TrafficLightDetection) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + traffic_light_.MergeFrom(from.traffic_light_); + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } +} + +void TrafficLightDetection::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.perception.TrafficLightDetection) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void TrafficLightDetection::CopyFrom(const TrafficLightDetection& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.perception.TrafficLightDetection) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool TrafficLightDetection::IsInitialized() const { + return true; +} + +void TrafficLightDetection::Swap(TrafficLightDetection* other) { + if (other == this) return; + InternalSwap(other); +} +void TrafficLightDetection::InternalSwap(TrafficLightDetection* other) { + using std::swap; + CastToBase(&traffic_light_)->InternalSwap(CastToBase(&other->traffic_light_)); + swap(header_, other->header_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata TrafficLightDetection::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace perception +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::perception::TrafficLight* Arena::CreateMaybeMessage< ::apollo::perception::TrafficLight >(Arena* arena) { + return Arena::CreateInternal< ::apollo::perception::TrafficLight >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::perception::TrafficLightDetection* Arena::CreateMaybeMessage< ::apollo::perception::TrafficLightDetection >(Arena* arena) { + return Arena::CreateInternal< ::apollo::perception::TrafficLightDetection >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/perception/traffic_light_detection.pb.h b/apollo_msgs/include/apollo_msgs/proto/perception/traffic_light_detection.pb.h new file mode 100644 index 0000000..5d1cb4e --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/perception/traffic_light_detection.pb.h @@ -0,0 +1,589 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/perception/traffic_light_detection.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "apollo_msgs/proto/common/header.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[2]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto +namespace apollo { +namespace perception { +class TrafficLight; +class TrafficLightDefaultTypeInternal; +extern TrafficLightDefaultTypeInternal _TrafficLight_default_instance_; +class TrafficLightDetection; +class TrafficLightDetectionDefaultTypeInternal; +extern TrafficLightDetectionDefaultTypeInternal _TrafficLightDetection_default_instance_; +} // namespace perception +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::perception::TrafficLight* Arena::CreateMaybeMessage<::apollo::perception::TrafficLight>(Arena*); +template<> ::apollo::perception::TrafficLightDetection* Arena::CreateMaybeMessage<::apollo::perception::TrafficLightDetection>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace perception { + +enum TrafficLight_Color { + TrafficLight_Color_UNKNOWN = 0, + TrafficLight_Color_RED = 1, + TrafficLight_Color_YELLOW = 2, + TrafficLight_Color_GREEN = 3, + TrafficLight_Color_TrafficLight_Color_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + TrafficLight_Color_TrafficLight_Color_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool TrafficLight_Color_IsValid(int value); +const TrafficLight_Color TrafficLight_Color_Color_MIN = TrafficLight_Color_UNKNOWN; +const TrafficLight_Color TrafficLight_Color_Color_MAX = TrafficLight_Color_GREEN; +const int TrafficLight_Color_Color_ARRAYSIZE = TrafficLight_Color_Color_MAX + 1; + +const ::google::protobuf::EnumDescriptor* TrafficLight_Color_descriptor(); +inline const ::std::string& TrafficLight_Color_Name(TrafficLight_Color value) { + return ::google::protobuf::internal::NameOfEnum( + TrafficLight_Color_descriptor(), value); +} +inline bool TrafficLight_Color_Parse( + const ::std::string& name, TrafficLight_Color* value) { + return ::google::protobuf::internal::ParseNamedEnum( + TrafficLight_Color_descriptor(), name, value); +} +// =================================================================== + +class TrafficLight : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.perception.TrafficLight) */ { + public: + TrafficLight(); + virtual ~TrafficLight(); + + TrafficLight(const TrafficLight& from); + + inline TrafficLight& operator=(const TrafficLight& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + TrafficLight(TrafficLight&& from) noexcept + : TrafficLight() { + *this = ::std::move(from); + } + + inline TrafficLight& operator=(TrafficLight&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const TrafficLight& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const TrafficLight* internal_default_instance() { + return reinterpret_cast( + &_TrafficLight_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(TrafficLight* other); + friend void swap(TrafficLight& a, TrafficLight& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline TrafficLight* New() const final { + return CreateMaybeMessage(NULL); + } + + TrafficLight* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const TrafficLight& from); + void MergeFrom(const TrafficLight& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(TrafficLight* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef TrafficLight_Color Color; + static const Color UNKNOWN = + TrafficLight_Color_UNKNOWN; + static const Color RED = + TrafficLight_Color_RED; + static const Color YELLOW = + TrafficLight_Color_YELLOW; + static const Color GREEN = + TrafficLight_Color_GREEN; + static inline bool Color_IsValid(int value) { + return TrafficLight_Color_IsValid(value); + } + static const Color Color_MIN = + TrafficLight_Color_Color_MIN; + static const Color Color_MAX = + TrafficLight_Color_Color_MAX; + static const int Color_ARRAYSIZE = + TrafficLight_Color_Color_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + Color_descriptor() { + return TrafficLight_Color_descriptor(); + } + static inline const ::std::string& Color_Name(Color value) { + return TrafficLight_Color_Name(value); + } + static inline bool Color_Parse(const ::std::string& name, + Color* value) { + return TrafficLight_Color_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // string id = 2; + void clear_id(); + static const int kIdFieldNumber = 2; + const ::std::string& id() const; + void set_id(const ::std::string& value); + #if LANG_CXX11 + void set_id(::std::string&& value); + #endif + void set_id(const char* value); + void set_id(const char* value, size_t size); + ::std::string* mutable_id(); + ::std::string* release_id(); + void set_allocated_id(::std::string* id); + + // double confidence = 3; + void clear_confidence(); + static const int kConfidenceFieldNumber = 3; + double confidence() const; + void set_confidence(double value); + + // double tracking_time = 4; + void clear_tracking_time(); + static const int kTrackingTimeFieldNumber = 4; + double tracking_time() const; + void set_tracking_time(double value); + + // .apollo.perception.TrafficLight.Color color = 1; + void clear_color(); + static const int kColorFieldNumber = 1; + ::apollo::perception::TrafficLight_Color color() const; + void set_color(::apollo::perception::TrafficLight_Color value); + + // @@protoc_insertion_point(class_scope:apollo.perception.TrafficLight) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr id_; + double confidence_; + double tracking_time_; + int color_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class TrafficLightDetection : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.perception.TrafficLightDetection) */ { + public: + TrafficLightDetection(); + virtual ~TrafficLightDetection(); + + TrafficLightDetection(const TrafficLightDetection& from); + + inline TrafficLightDetection& operator=(const TrafficLightDetection& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + TrafficLightDetection(TrafficLightDetection&& from) noexcept + : TrafficLightDetection() { + *this = ::std::move(from); + } + + inline TrafficLightDetection& operator=(TrafficLightDetection&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const TrafficLightDetection& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const TrafficLightDetection* internal_default_instance() { + return reinterpret_cast( + &_TrafficLightDetection_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(TrafficLightDetection* other); + friend void swap(TrafficLightDetection& a, TrafficLightDetection& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline TrafficLightDetection* New() const final { + return CreateMaybeMessage(NULL); + } + + TrafficLightDetection* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const TrafficLightDetection& from); + void MergeFrom(const TrafficLightDetection& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(TrafficLightDetection* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.perception.TrafficLight traffic_light = 1; + int traffic_light_size() const; + void clear_traffic_light(); + static const int kTrafficLightFieldNumber = 1; + ::apollo::perception::TrafficLight* mutable_traffic_light(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::perception::TrafficLight >* + mutable_traffic_light(); + const ::apollo::perception::TrafficLight& traffic_light(int index) const; + ::apollo::perception::TrafficLight* add_traffic_light(); + const ::google::protobuf::RepeatedPtrField< ::apollo::perception::TrafficLight >& + traffic_light() const; + + // .apollo.common.Header header = 2; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 2; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // @@protoc_insertion_point(class_scope:apollo.perception.TrafficLightDetection) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::perception::TrafficLight > traffic_light_; + ::apollo::common::Header* header_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// TrafficLight + +// .apollo.perception.TrafficLight.Color color = 1; +inline void TrafficLight::clear_color() { + color_ = 0; +} +inline ::apollo::perception::TrafficLight_Color TrafficLight::color() const { + // @@protoc_insertion_point(field_get:apollo.perception.TrafficLight.color) + return static_cast< ::apollo::perception::TrafficLight_Color >(color_); +} +inline void TrafficLight::set_color(::apollo::perception::TrafficLight_Color value) { + + color_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.TrafficLight.color) +} + +// string id = 2; +inline void TrafficLight::clear_id() { + id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& TrafficLight::id() const { + // @@protoc_insertion_point(field_get:apollo.perception.TrafficLight.id) + return id_.GetNoArena(); +} +inline void TrafficLight::set_id(const ::std::string& value) { + + id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.perception.TrafficLight.id) +} +#if LANG_CXX11 +inline void TrafficLight::set_id(::std::string&& value) { + + id_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.perception.TrafficLight.id) +} +#endif +inline void TrafficLight::set_id(const char* value) { + GOOGLE_DCHECK(value != NULL); + + id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.perception.TrafficLight.id) +} +inline void TrafficLight::set_id(const char* value, size_t size) { + + id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.perception.TrafficLight.id) +} +inline ::std::string* TrafficLight::mutable_id() { + + // @@protoc_insertion_point(field_mutable:apollo.perception.TrafficLight.id) + return id_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* TrafficLight::release_id() { + // @@protoc_insertion_point(field_release:apollo.perception.TrafficLight.id) + + return id_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void TrafficLight::set_allocated_id(::std::string* id) { + if (id != NULL) { + + } else { + + } + id_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), id); + // @@protoc_insertion_point(field_set_allocated:apollo.perception.TrafficLight.id) +} + +// double confidence = 3; +inline void TrafficLight::clear_confidence() { + confidence_ = 0; +} +inline double TrafficLight::confidence() const { + // @@protoc_insertion_point(field_get:apollo.perception.TrafficLight.confidence) + return confidence_; +} +inline void TrafficLight::set_confidence(double value) { + + confidence_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.TrafficLight.confidence) +} + +// double tracking_time = 4; +inline void TrafficLight::clear_tracking_time() { + tracking_time_ = 0; +} +inline double TrafficLight::tracking_time() const { + // @@protoc_insertion_point(field_get:apollo.perception.TrafficLight.tracking_time) + return tracking_time_; +} +inline void TrafficLight::set_tracking_time(double value) { + + tracking_time_ = value; + // @@protoc_insertion_point(field_set:apollo.perception.TrafficLight.tracking_time) +} + +// ------------------------------------------------------------------- + +// TrafficLightDetection + +// .apollo.common.Header header = 2; +inline bool TrafficLightDetection::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& TrafficLightDetection::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& TrafficLightDetection::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.perception.TrafficLightDetection.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* TrafficLightDetection::release_header() { + // @@protoc_insertion_point(field_release:apollo.perception.TrafficLightDetection.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* TrafficLightDetection::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.perception.TrafficLightDetection.header) + return header_; +} +inline void TrafficLightDetection::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.perception.TrafficLightDetection.header) +} + +// repeated .apollo.perception.TrafficLight traffic_light = 1; +inline int TrafficLightDetection::traffic_light_size() const { + return traffic_light_.size(); +} +inline void TrafficLightDetection::clear_traffic_light() { + traffic_light_.Clear(); +} +inline ::apollo::perception::TrafficLight* TrafficLightDetection::mutable_traffic_light(int index) { + // @@protoc_insertion_point(field_mutable:apollo.perception.TrafficLightDetection.traffic_light) + return traffic_light_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::perception::TrafficLight >* +TrafficLightDetection::mutable_traffic_light() { + // @@protoc_insertion_point(field_mutable_list:apollo.perception.TrafficLightDetection.traffic_light) + return &traffic_light_; +} +inline const ::apollo::perception::TrafficLight& TrafficLightDetection::traffic_light(int index) const { + // @@protoc_insertion_point(field_get:apollo.perception.TrafficLightDetection.traffic_light) + return traffic_light_.Get(index); +} +inline ::apollo::perception::TrafficLight* TrafficLightDetection::add_traffic_light() { + // @@protoc_insertion_point(field_add:apollo.perception.TrafficLightDetection.traffic_light) + return traffic_light_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::perception::TrafficLight >& +TrafficLightDetection::traffic_light() const { + // @@protoc_insertion_point(field_list:apollo.perception.TrafficLightDetection.traffic_light) + return traffic_light_; +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace perception +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::perception::TrafficLight_Color> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::perception::TrafficLight_Color>() { + return ::apollo::perception::TrafficLight_Color_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fperception_2ftraffic_5flight_5fdetection_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/planning/planning.pb.cc b/apollo_msgs/include/apollo_msgs/proto/planning/planning.pb.cc new file mode 100644 index 0000000..f00a8cd --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/planning/planning.pb.cc @@ -0,0 +1,2490 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/planning/planning.proto + +#include "apollo_msgs/proto/planning/planning.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Signal; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_ADCPathPoint; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_ADCSignals; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_ADCTrajectoryPoint; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_EStop; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_Debug; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto +namespace apollo { +namespace planning { +class ADCTrajectoryPointDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ADCTrajectoryPoint_default_instance_; +class ADCSignalsDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ADCSignals_default_instance_; +class EStopDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _EStop_default_instance_; +class ADCPathPointDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ADCPathPoint_default_instance_; +class ADCTrajectoryDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _ADCTrajectory_default_instance_; +} // namespace planning +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto { +static void InitDefaultsADCTrajectoryPoint() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::planning::_ADCTrajectoryPoint_default_instance_; + new (ptr) ::apollo::planning::ADCTrajectoryPoint(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::planning::ADCTrajectoryPoint::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_ADCTrajectoryPoint = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsADCTrajectoryPoint}, {}}; + +static void InitDefaultsADCSignals() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::planning::_ADCSignals_default_instance_; + new (ptr) ::apollo::planning::ADCSignals(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::planning::ADCSignals::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_ADCSignals = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsADCSignals}, {}}; + +static void InitDefaultsEStop() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::planning::_EStop_default_instance_; + new (ptr) ::apollo::planning::EStop(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::planning::EStop::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_EStop = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsEStop}, {}}; + +static void InitDefaultsADCPathPoint() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::planning::_ADCPathPoint_default_instance_; + new (ptr) ::apollo::planning::ADCPathPoint(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::planning::ADCPathPoint::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_ADCPathPoint = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsADCPathPoint}, {}}; + +static void InitDefaultsADCTrajectory() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::planning::_ADCTrajectory_default_instance_; + new (ptr) ::apollo::planning::ADCTrajectory(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::planning::ADCTrajectory::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<7> scc_info_ADCTrajectory = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 7, InitDefaultsADCTrajectory}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base, + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_ADCTrajectoryPoint.base, + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_EStop.base, + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_ADCPathPoint.base, + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::scc_info_Debug.base, + &protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::scc_info_Signal.base, + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_ADCSignals.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_ADCTrajectoryPoint.base); + ::google::protobuf::internal::InitSCC(&scc_info_ADCSignals.base); + ::google::protobuf::internal::InitSCC(&scc_info_EStop.base); + ::google::protobuf::internal::InitSCC(&scc_info_ADCPathPoint.base); + ::google::protobuf::internal::InitSCC(&scc_info_ADCTrajectory.base); +} + +::google::protobuf::Metadata file_level_metadata[5]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectoryPoint, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectoryPoint, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectoryPoint, y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectoryPoint, z_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectoryPoint, speed_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectoryPoint, acceleration_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectoryPoint, curvature_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectoryPoint, curvature_change_rate_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectoryPoint, relative_time_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectoryPoint, theta_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectoryPoint, accumulated_s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectoryPoint, s_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectoryPoint, l_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCSignals, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCSignals, signal_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::EStop, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::EStop, is_estop_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCPathPoint, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCPathPoint, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCPathPoint, y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCPathPoint, z_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCPathPoint, curvature_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCPathPoint, heading_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectory, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectory, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectory, total_path_length_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectory, total_path_time_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectory, adc_trajectory_point_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectory, estop_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectory, adc_path_point_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectory, is_replan_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectory, gear_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectory, debug_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectory, signal_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning::ADCTrajectory, signals_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::planning::ADCTrajectoryPoint)}, + { 17, -1, sizeof(::apollo::planning::ADCSignals)}, + { 23, -1, sizeof(::apollo::planning::EStop)}, + { 29, -1, sizeof(::apollo::planning::ADCPathPoint)}, + { 39, -1, sizeof(::apollo::planning::ADCTrajectory)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::planning::_ADCTrajectoryPoint_default_instance_), + reinterpret_cast(&::apollo::planning::_ADCSignals_default_instance_), + reinterpret_cast(&::apollo::planning::_EStop_default_instance_), + reinterpret_cast(&::apollo::planning::_ADCPathPoint_default_instance_), + reinterpret_cast(&::apollo::planning::_ADCTrajectory_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/planning/planning.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 5); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n)apollo_msgs/proto/planning/planning.pr" + "oto\022\017apollo.planning\032%apollo_msgs/proto/" + "common/header.proto\032&apollo_msgs/proto/c" + "anbus/chassis.proto\0322apollo_msgs/proto/p" + "lanning/planning_internal.proto\"\341\001\n\022ADCT" + "rajectoryPoint\022\t\n\001x\030\001 \001(\001\022\t\n\001y\030\002 \001(\001\022\t\n\001" + "z\030\003 \001(\001\022\r\n\005speed\030\006 \001(\001\022\026\n\016acceleration_s" + "\030\007 \001(\001\022\021\n\tcurvature\030\010 \001(\001\022\035\n\025curvature_c" + "hange_rate\030\t \001(\001\022\025\n\rrelative_time\030\n \001(\001\022" + "\r\n\005theta\030\013 \001(\001\022\025\n\raccumulated_s\030\014 \001(\001\022\t\n" + "\001s\030\004 \001(\001\022\t\n\001l\030\005 \001(\001\"\276\001\n\nADCSignals\0226\n\006si" + "gnal\030\001 \003(\0162&.apollo.planning.ADCSignals." + "SignalType\"x\n\nSignalType\022\r\n\tLEFT_TURN\020\000\022" + "\016\n\nRIGHT_TURN\020\001\022\022\n\016LOW_BEAM_LIGHT\020\002\022\023\n\017H" + "IGH_BEAM_LIGHT\020\003\022\r\n\tFOG_LIGHT\020\004\022\023\n\017EMERG" + "ENCY_LIGHT\020\005\"\031\n\005EStop\022\020\n\010is_estop\030\001 \001(\010\"" + "S\n\014ADCPathPoint\022\t\n\001x\030\001 \001(\001\022\t\n\001y\030\002 \001(\001\022\t\n" + "\001z\030\003 \001(\001\022\021\n\tcurvature\030\004 \001(\001\022\017\n\007heading\030\005" + " \001(\001\"\326\003\n\rADCTrajectory\022%\n\006header\030\001 \001(\0132\025" + ".apollo.common.Header\022\031\n\021total_path_leng" + "th\030\002 \001(\001\022\027\n\017total_path_time\030\003 \001(\001\022A\n\024adc" + "_trajectory_point\030\004 \003(\0132#.apollo.plannin" + "g.ADCTrajectoryPoint\022%\n\005estop\030\006 \001(\0132\026.ap" + "ollo.planning.EStop\0225\n\016adc_path_point\030\007 " + "\003(\0132\035.apollo.planning.ADCPathPoint\022\021\n\tis" + "_replan\030\t \001(\010\0221\n\004gear\030\n \001(\0162#.apollo.can" + "bus.Chassis.GearPosition\022.\n\005debug\030\010 \001(\0132" + "\037.apollo.planning_internal.Debug\022%\n\006sign" + "al\030\013 \001(\0132\025.apollo.canbus.Signal\022,\n\007signa" + "ls\030\005 \001(\0132\033.apollo.planning.ADCSignalsb\006p" + "roto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 1205); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/planning/planning.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fcanbus_2fchassis_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto +namespace apollo { +namespace planning { +const ::google::protobuf::EnumDescriptor* ADCSignals_SignalType_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::file_level_enum_descriptors[0]; +} +bool ADCSignals_SignalType_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const ADCSignals_SignalType ADCSignals::LEFT_TURN; +const ADCSignals_SignalType ADCSignals::RIGHT_TURN; +const ADCSignals_SignalType ADCSignals::LOW_BEAM_LIGHT; +const ADCSignals_SignalType ADCSignals::HIGH_BEAM_LIGHT; +const ADCSignals_SignalType ADCSignals::FOG_LIGHT; +const ADCSignals_SignalType ADCSignals::EMERGENCY_LIGHT; +const ADCSignals_SignalType ADCSignals::SignalType_MIN; +const ADCSignals_SignalType ADCSignals::SignalType_MAX; +const int ADCSignals::SignalType_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +// =================================================================== + +void ADCTrajectoryPoint::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ADCTrajectoryPoint::kXFieldNumber; +const int ADCTrajectoryPoint::kYFieldNumber; +const int ADCTrajectoryPoint::kZFieldNumber; +const int ADCTrajectoryPoint::kSpeedFieldNumber; +const int ADCTrajectoryPoint::kAccelerationSFieldNumber; +const int ADCTrajectoryPoint::kCurvatureFieldNumber; +const int ADCTrajectoryPoint::kCurvatureChangeRateFieldNumber; +const int ADCTrajectoryPoint::kRelativeTimeFieldNumber; +const int ADCTrajectoryPoint::kThetaFieldNumber; +const int ADCTrajectoryPoint::kAccumulatedSFieldNumber; +const int ADCTrajectoryPoint::kSFieldNumber; +const int ADCTrajectoryPoint::kLFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ADCTrajectoryPoint::ADCTrajectoryPoint() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_ADCTrajectoryPoint.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.planning.ADCTrajectoryPoint) +} +ADCTrajectoryPoint::ADCTrajectoryPoint(const ADCTrajectoryPoint& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&x_, &from.x_, + static_cast(reinterpret_cast(&accumulated_s_) - + reinterpret_cast(&x_)) + sizeof(accumulated_s_)); + // @@protoc_insertion_point(copy_constructor:apollo.planning.ADCTrajectoryPoint) +} + +void ADCTrajectoryPoint::SharedCtor() { + ::memset(&x_, 0, static_cast( + reinterpret_cast(&accumulated_s_) - + reinterpret_cast(&x_)) + sizeof(accumulated_s_)); +} + +ADCTrajectoryPoint::~ADCTrajectoryPoint() { + // @@protoc_insertion_point(destructor:apollo.planning.ADCTrajectoryPoint) + SharedDtor(); +} + +void ADCTrajectoryPoint::SharedDtor() { +} + +void ADCTrajectoryPoint::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ADCTrajectoryPoint::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ADCTrajectoryPoint& ADCTrajectoryPoint::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_ADCTrajectoryPoint.base); + return *internal_default_instance(); +} + + +void ADCTrajectoryPoint::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.planning.ADCTrajectoryPoint) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&x_, 0, static_cast( + reinterpret_cast(&accumulated_s_) - + reinterpret_cast(&x_)) + sizeof(accumulated_s_)); + _internal_metadata_.Clear(); +} + +bool ADCTrajectoryPoint::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.planning.ADCTrajectoryPoint) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double x = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &x_))); + } else { + goto handle_unusual; + } + break; + } + + // double y = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &y_))); + } else { + goto handle_unusual; + } + break; + } + + // double z = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &z_))); + } else { + goto handle_unusual; + } + break; + } + + // double s = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &s_))); + } else { + goto handle_unusual; + } + break; + } + + // double l = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &l_))); + } else { + goto handle_unusual; + } + break; + } + + // double speed = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &speed_))); + } else { + goto handle_unusual; + } + break; + } + + // double acceleration_s = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &acceleration_s_))); + } else { + goto handle_unusual; + } + break; + } + + // double curvature = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(65u /* 65 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &curvature_))); + } else { + goto handle_unusual; + } + break; + } + + // double curvature_change_rate = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(73u /* 73 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &curvature_change_rate_))); + } else { + goto handle_unusual; + } + break; + } + + // double relative_time = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(81u /* 81 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &relative_time_))); + } else { + goto handle_unusual; + } + break; + } + + // double theta = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(89u /* 89 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &theta_))); + } else { + goto handle_unusual; + } + break; + } + + // double accumulated_s = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(97u /* 97 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &accumulated_s_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.planning.ADCTrajectoryPoint) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.planning.ADCTrajectoryPoint) + return false; +#undef DO_ +} + +void ADCTrajectoryPoint::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.planning.ADCTrajectoryPoint) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output); + } + + // double y = 2; + if (this->y() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output); + } + + // double z = 3; + if (this->z() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->z(), output); + } + + // double s = 4; + if (this->s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->s(), output); + } + + // double l = 5; + if (this->l() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->l(), output); + } + + // double speed = 6; + if (this->speed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->speed(), output); + } + + // double acceleration_s = 7; + if (this->acceleration_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->acceleration_s(), output); + } + + // double curvature = 8; + if (this->curvature() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(8, this->curvature(), output); + } + + // double curvature_change_rate = 9; + if (this->curvature_change_rate() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->curvature_change_rate(), output); + } + + // double relative_time = 10; + if (this->relative_time() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(10, this->relative_time(), output); + } + + // double theta = 11; + if (this->theta() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(11, this->theta(), output); + } + + // double accumulated_s = 12; + if (this->accumulated_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(12, this->accumulated_s(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.planning.ADCTrajectoryPoint) +} + +::google::protobuf::uint8* ADCTrajectoryPoint::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.planning.ADCTrajectoryPoint) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target); + } + + // double y = 2; + if (this->y() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target); + } + + // double z = 3; + if (this->z() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->z(), target); + } + + // double s = 4; + if (this->s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->s(), target); + } + + // double l = 5; + if (this->l() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->l(), target); + } + + // double speed = 6; + if (this->speed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->speed(), target); + } + + // double acceleration_s = 7; + if (this->acceleration_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->acceleration_s(), target); + } + + // double curvature = 8; + if (this->curvature() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(8, this->curvature(), target); + } + + // double curvature_change_rate = 9; + if (this->curvature_change_rate() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->curvature_change_rate(), target); + } + + // double relative_time = 10; + if (this->relative_time() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(10, this->relative_time(), target); + } + + // double theta = 11; + if (this->theta() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(11, this->theta(), target); + } + + // double accumulated_s = 12; + if (this->accumulated_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(12, this->accumulated_s(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.planning.ADCTrajectoryPoint) + return target; +} + +size_t ADCTrajectoryPoint::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.planning.ADCTrajectoryPoint) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double x = 1; + if (this->x() != 0) { + total_size += 1 + 8; + } + + // double y = 2; + if (this->y() != 0) { + total_size += 1 + 8; + } + + // double z = 3; + if (this->z() != 0) { + total_size += 1 + 8; + } + + // double s = 4; + if (this->s() != 0) { + total_size += 1 + 8; + } + + // double l = 5; + if (this->l() != 0) { + total_size += 1 + 8; + } + + // double speed = 6; + if (this->speed() != 0) { + total_size += 1 + 8; + } + + // double acceleration_s = 7; + if (this->acceleration_s() != 0) { + total_size += 1 + 8; + } + + // double curvature = 8; + if (this->curvature() != 0) { + total_size += 1 + 8; + } + + // double curvature_change_rate = 9; + if (this->curvature_change_rate() != 0) { + total_size += 1 + 8; + } + + // double relative_time = 10; + if (this->relative_time() != 0) { + total_size += 1 + 8; + } + + // double theta = 11; + if (this->theta() != 0) { + total_size += 1 + 8; + } + + // double accumulated_s = 12; + if (this->accumulated_s() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ADCTrajectoryPoint::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.planning.ADCTrajectoryPoint) + GOOGLE_DCHECK_NE(&from, this); + const ADCTrajectoryPoint* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.planning.ADCTrajectoryPoint) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.planning.ADCTrajectoryPoint) + MergeFrom(*source); + } +} + +void ADCTrajectoryPoint::MergeFrom(const ADCTrajectoryPoint& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.planning.ADCTrajectoryPoint) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.x() != 0) { + set_x(from.x()); + } + if (from.y() != 0) { + set_y(from.y()); + } + if (from.z() != 0) { + set_z(from.z()); + } + if (from.s() != 0) { + set_s(from.s()); + } + if (from.l() != 0) { + set_l(from.l()); + } + if (from.speed() != 0) { + set_speed(from.speed()); + } + if (from.acceleration_s() != 0) { + set_acceleration_s(from.acceleration_s()); + } + if (from.curvature() != 0) { + set_curvature(from.curvature()); + } + if (from.curvature_change_rate() != 0) { + set_curvature_change_rate(from.curvature_change_rate()); + } + if (from.relative_time() != 0) { + set_relative_time(from.relative_time()); + } + if (from.theta() != 0) { + set_theta(from.theta()); + } + if (from.accumulated_s() != 0) { + set_accumulated_s(from.accumulated_s()); + } +} + +void ADCTrajectoryPoint::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.planning.ADCTrajectoryPoint) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ADCTrajectoryPoint::CopyFrom(const ADCTrajectoryPoint& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.planning.ADCTrajectoryPoint) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ADCTrajectoryPoint::IsInitialized() const { + return true; +} + +void ADCTrajectoryPoint::Swap(ADCTrajectoryPoint* other) { + if (other == this) return; + InternalSwap(other); +} +void ADCTrajectoryPoint::InternalSwap(ADCTrajectoryPoint* other) { + using std::swap; + swap(x_, other->x_); + swap(y_, other->y_); + swap(z_, other->z_); + swap(s_, other->s_); + swap(l_, other->l_); + swap(speed_, other->speed_); + swap(acceleration_s_, other->acceleration_s_); + swap(curvature_, other->curvature_); + swap(curvature_change_rate_, other->curvature_change_rate_); + swap(relative_time_, other->relative_time_); + swap(theta_, other->theta_); + swap(accumulated_s_, other->accumulated_s_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ADCTrajectoryPoint::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ADCSignals::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ADCSignals::kSignalFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ADCSignals::ADCSignals() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_ADCSignals.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.planning.ADCSignals) +} +ADCSignals::ADCSignals(const ADCSignals& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + signal_(from.signal_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + // @@protoc_insertion_point(copy_constructor:apollo.planning.ADCSignals) +} + +void ADCSignals::SharedCtor() { +} + +ADCSignals::~ADCSignals() { + // @@protoc_insertion_point(destructor:apollo.planning.ADCSignals) + SharedDtor(); +} + +void ADCSignals::SharedDtor() { +} + +void ADCSignals::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ADCSignals::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ADCSignals& ADCSignals::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_ADCSignals.base); + return *internal_default_instance(); +} + + +void ADCSignals::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.planning.ADCSignals) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + signal_.Clear(); + _internal_metadata_.Clear(); +} + +bool ADCSignals::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.planning.ADCSignals) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // repeated .apollo.planning.ADCSignals.SignalType signal = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + ::google::protobuf::uint32 length; + DO_(input->ReadVarint32(&length)); + ::google::protobuf::io::CodedInputStream::Limit limit = input->PushLimit(static_cast(length)); + while (input->BytesUntilLimit() > 0) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + add_signal(static_cast< ::apollo::planning::ADCSignals_SignalType >(value)); + } + input->PopLimit(limit); + } else if ( + static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + add_signal(static_cast< ::apollo::planning::ADCSignals_SignalType >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.planning.ADCSignals) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.planning.ADCSignals) + return false; +#undef DO_ +} + +void ADCSignals::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.planning.ADCSignals) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.planning.ADCSignals.SignalType signal = 1; + if (this->signal_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag( + 1, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + output); + output->WriteVarint32( + static_cast< ::google::protobuf::uint32>(_signal_cached_byte_size_)); + } + for (int i = 0, n = this->signal_size(); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteEnumNoTag( + this->signal(i), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.planning.ADCSignals) +} + +::google::protobuf::uint8* ADCSignals::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.planning.ADCSignals) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // repeated .apollo.planning.ADCSignals.SignalType signal = 1; + if (this->signal_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 1, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( static_cast< ::google::protobuf::uint32>( + _signal_cached_byte_size_), target); + target = ::google::protobuf::internal::WireFormatLite::WriteEnumNoTagToArray( + this->signal_, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.planning.ADCSignals) + return target; +} + +size_t ADCSignals::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.planning.ADCSignals) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.planning.ADCSignals.SignalType signal = 1; + { + size_t data_size = 0; + unsigned int count = static_cast(this->signal_size());for (unsigned int i = 0; i < count; i++) { + data_size += ::google::protobuf::internal::WireFormatLite::EnumSize( + this->signal(static_cast(i))); + } + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + static_cast< ::google::protobuf::int32>(data_size)); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); + _signal_cached_byte_size_ = cached_size; + GOOGLE_SAFE_CONCURRENT_WRITES_END(); + total_size += data_size; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ADCSignals::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.planning.ADCSignals) + GOOGLE_DCHECK_NE(&from, this); + const ADCSignals* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.planning.ADCSignals) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.planning.ADCSignals) + MergeFrom(*source); + } +} + +void ADCSignals::MergeFrom(const ADCSignals& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.planning.ADCSignals) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + signal_.MergeFrom(from.signal_); +} + +void ADCSignals::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.planning.ADCSignals) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ADCSignals::CopyFrom(const ADCSignals& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.planning.ADCSignals) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ADCSignals::IsInitialized() const { + return true; +} + +void ADCSignals::Swap(ADCSignals* other) { + if (other == this) return; + InternalSwap(other); +} +void ADCSignals::InternalSwap(ADCSignals* other) { + using std::swap; + signal_.InternalSwap(&other->signal_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ADCSignals::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void EStop::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int EStop::kIsEstopFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +EStop::EStop() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_EStop.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.planning.EStop) +} +EStop::EStop(const EStop& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + is_estop_ = from.is_estop_; + // @@protoc_insertion_point(copy_constructor:apollo.planning.EStop) +} + +void EStop::SharedCtor() { + is_estop_ = false; +} + +EStop::~EStop() { + // @@protoc_insertion_point(destructor:apollo.planning.EStop) + SharedDtor(); +} + +void EStop::SharedDtor() { +} + +void EStop::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* EStop::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const EStop& EStop::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_EStop.base); + return *internal_default_instance(); +} + + +void EStop::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.planning.EStop) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + is_estop_ = false; + _internal_metadata_.Clear(); +} + +bool EStop::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.planning.EStop) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_estop = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_estop_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.planning.EStop) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.planning.EStop) + return false; +#undef DO_ +} + +void EStop::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.planning.EStop) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_estop = 1; + if (this->is_estop() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_estop(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.planning.EStop) +} + +::google::protobuf::uint8* EStop::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.planning.EStop) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_estop = 1; + if (this->is_estop() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_estop(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.planning.EStop) + return target; +} + +size_t EStop::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.planning.EStop) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // bool is_estop = 1; + if (this->is_estop() != 0) { + total_size += 1 + 1; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void EStop::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.planning.EStop) + GOOGLE_DCHECK_NE(&from, this); + const EStop* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.planning.EStop) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.planning.EStop) + MergeFrom(*source); + } +} + +void EStop::MergeFrom(const EStop& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.planning.EStop) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.is_estop() != 0) { + set_is_estop(from.is_estop()); + } +} + +void EStop::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.planning.EStop) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void EStop::CopyFrom(const EStop& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.planning.EStop) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool EStop::IsInitialized() const { + return true; +} + +void EStop::Swap(EStop* other) { + if (other == this) return; + InternalSwap(other); +} +void EStop::InternalSwap(EStop* other) { + using std::swap; + swap(is_estop_, other->is_estop_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata EStop::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ADCPathPoint::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ADCPathPoint::kXFieldNumber; +const int ADCPathPoint::kYFieldNumber; +const int ADCPathPoint::kZFieldNumber; +const int ADCPathPoint::kCurvatureFieldNumber; +const int ADCPathPoint::kHeadingFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ADCPathPoint::ADCPathPoint() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_ADCPathPoint.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.planning.ADCPathPoint) +} +ADCPathPoint::ADCPathPoint(const ADCPathPoint& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&x_, &from.x_, + static_cast(reinterpret_cast(&heading_) - + reinterpret_cast(&x_)) + sizeof(heading_)); + // @@protoc_insertion_point(copy_constructor:apollo.planning.ADCPathPoint) +} + +void ADCPathPoint::SharedCtor() { + ::memset(&x_, 0, static_cast( + reinterpret_cast(&heading_) - + reinterpret_cast(&x_)) + sizeof(heading_)); +} + +ADCPathPoint::~ADCPathPoint() { + // @@protoc_insertion_point(destructor:apollo.planning.ADCPathPoint) + SharedDtor(); +} + +void ADCPathPoint::SharedDtor() { +} + +void ADCPathPoint::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ADCPathPoint::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ADCPathPoint& ADCPathPoint::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_ADCPathPoint.base); + return *internal_default_instance(); +} + + +void ADCPathPoint::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.planning.ADCPathPoint) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&x_, 0, static_cast( + reinterpret_cast(&heading_) - + reinterpret_cast(&x_)) + sizeof(heading_)); + _internal_metadata_.Clear(); +} + +bool ADCPathPoint::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.planning.ADCPathPoint) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double x = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &x_))); + } else { + goto handle_unusual; + } + break; + } + + // double y = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &y_))); + } else { + goto handle_unusual; + } + break; + } + + // double z = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &z_))); + } else { + goto handle_unusual; + } + break; + } + + // double curvature = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &curvature_))); + } else { + goto handle_unusual; + } + break; + } + + // double heading = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &heading_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.planning.ADCPathPoint) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.planning.ADCPathPoint) + return false; +#undef DO_ +} + +void ADCPathPoint::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.planning.ADCPathPoint) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output); + } + + // double y = 2; + if (this->y() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output); + } + + // double z = 3; + if (this->z() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->z(), output); + } + + // double curvature = 4; + if (this->curvature() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->curvature(), output); + } + + // double heading = 5; + if (this->heading() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->heading(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.planning.ADCPathPoint) +} + +::google::protobuf::uint8* ADCPathPoint::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.planning.ADCPathPoint) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target); + } + + // double y = 2; + if (this->y() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target); + } + + // double z = 3; + if (this->z() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->z(), target); + } + + // double curvature = 4; + if (this->curvature() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->curvature(), target); + } + + // double heading = 5; + if (this->heading() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->heading(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.planning.ADCPathPoint) + return target; +} + +size_t ADCPathPoint::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.planning.ADCPathPoint) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double x = 1; + if (this->x() != 0) { + total_size += 1 + 8; + } + + // double y = 2; + if (this->y() != 0) { + total_size += 1 + 8; + } + + // double z = 3; + if (this->z() != 0) { + total_size += 1 + 8; + } + + // double curvature = 4; + if (this->curvature() != 0) { + total_size += 1 + 8; + } + + // double heading = 5; + if (this->heading() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ADCPathPoint::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.planning.ADCPathPoint) + GOOGLE_DCHECK_NE(&from, this); + const ADCPathPoint* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.planning.ADCPathPoint) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.planning.ADCPathPoint) + MergeFrom(*source); + } +} + +void ADCPathPoint::MergeFrom(const ADCPathPoint& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.planning.ADCPathPoint) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.x() != 0) { + set_x(from.x()); + } + if (from.y() != 0) { + set_y(from.y()); + } + if (from.z() != 0) { + set_z(from.z()); + } + if (from.curvature() != 0) { + set_curvature(from.curvature()); + } + if (from.heading() != 0) { + set_heading(from.heading()); + } +} + +void ADCPathPoint::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.planning.ADCPathPoint) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ADCPathPoint::CopyFrom(const ADCPathPoint& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.planning.ADCPathPoint) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ADCPathPoint::IsInitialized() const { + return true; +} + +void ADCPathPoint::Swap(ADCPathPoint* other) { + if (other == this) return; + InternalSwap(other); +} +void ADCPathPoint::InternalSwap(ADCPathPoint* other) { + using std::swap; + swap(x_, other->x_); + swap(y_, other->y_); + swap(z_, other->z_); + swap(curvature_, other->curvature_); + swap(heading_, other->heading_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ADCPathPoint::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void ADCTrajectory::InitAsDefaultInstance() { + ::apollo::planning::_ADCTrajectory_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); + ::apollo::planning::_ADCTrajectory_default_instance_._instance.get_mutable()->estop_ = const_cast< ::apollo::planning::EStop*>( + ::apollo::planning::EStop::internal_default_instance()); + ::apollo::planning::_ADCTrajectory_default_instance_._instance.get_mutable()->debug_ = const_cast< ::apollo::planning_internal::Debug*>( + ::apollo::planning_internal::Debug::internal_default_instance()); + ::apollo::planning::_ADCTrajectory_default_instance_._instance.get_mutable()->signal_ = const_cast< ::apollo::canbus::Signal*>( + ::apollo::canbus::Signal::internal_default_instance()); + ::apollo::planning::_ADCTrajectory_default_instance_._instance.get_mutable()->signals_ = const_cast< ::apollo::planning::ADCSignals*>( + ::apollo::planning::ADCSignals::internal_default_instance()); +} +void ADCTrajectory::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +void ADCTrajectory::clear_debug() { + if (GetArenaNoVirtual() == NULL && debug_ != NULL) { + delete debug_; + } + debug_ = NULL; +} +void ADCTrajectory::clear_signal() { + if (GetArenaNoVirtual() == NULL && signal_ != NULL) { + delete signal_; + } + signal_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ADCTrajectory::kHeaderFieldNumber; +const int ADCTrajectory::kTotalPathLengthFieldNumber; +const int ADCTrajectory::kTotalPathTimeFieldNumber; +const int ADCTrajectory::kAdcTrajectoryPointFieldNumber; +const int ADCTrajectory::kEstopFieldNumber; +const int ADCTrajectory::kAdcPathPointFieldNumber; +const int ADCTrajectory::kIsReplanFieldNumber; +const int ADCTrajectory::kGearFieldNumber; +const int ADCTrajectory::kDebugFieldNumber; +const int ADCTrajectory::kSignalFieldNumber; +const int ADCTrajectory::kSignalsFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ADCTrajectory::ADCTrajectory() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_ADCTrajectory.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.planning.ADCTrajectory) +} +ADCTrajectory::ADCTrajectory(const ADCTrajectory& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + adc_trajectory_point_(from.adc_trajectory_point_), + adc_path_point_(from.adc_path_point_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + if (from.has_signals()) { + signals_ = new ::apollo::planning::ADCSignals(*from.signals_); + } else { + signals_ = NULL; + } + if (from.has_estop()) { + estop_ = new ::apollo::planning::EStop(*from.estop_); + } else { + estop_ = NULL; + } + if (from.has_debug()) { + debug_ = new ::apollo::planning_internal::Debug(*from.debug_); + } else { + debug_ = NULL; + } + if (from.has_signal()) { + signal_ = new ::apollo::canbus::Signal(*from.signal_); + } else { + signal_ = NULL; + } + ::memcpy(&total_path_length_, &from.total_path_length_, + static_cast(reinterpret_cast(&gear_) - + reinterpret_cast(&total_path_length_)) + sizeof(gear_)); + // @@protoc_insertion_point(copy_constructor:apollo.planning.ADCTrajectory) +} + +void ADCTrajectory::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&gear_) - + reinterpret_cast(&header_)) + sizeof(gear_)); +} + +ADCTrajectory::~ADCTrajectory() { + // @@protoc_insertion_point(destructor:apollo.planning.ADCTrajectory) + SharedDtor(); +} + +void ADCTrajectory::SharedDtor() { + if (this != internal_default_instance()) delete header_; + if (this != internal_default_instance()) delete signals_; + if (this != internal_default_instance()) delete estop_; + if (this != internal_default_instance()) delete debug_; + if (this != internal_default_instance()) delete signal_; +} + +void ADCTrajectory::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* ADCTrajectory::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const ADCTrajectory& ADCTrajectory::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::scc_info_ADCTrajectory.base); + return *internal_default_instance(); +} + + +void ADCTrajectory::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.planning.ADCTrajectory) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + adc_trajectory_point_.Clear(); + adc_path_point_.Clear(); + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + if (GetArenaNoVirtual() == NULL && signals_ != NULL) { + delete signals_; + } + signals_ = NULL; + if (GetArenaNoVirtual() == NULL && estop_ != NULL) { + delete estop_; + } + estop_ = NULL; + if (GetArenaNoVirtual() == NULL && debug_ != NULL) { + delete debug_; + } + debug_ = NULL; + if (GetArenaNoVirtual() == NULL && signal_ != NULL) { + delete signal_; + } + signal_ = NULL; + ::memset(&total_path_length_, 0, static_cast( + reinterpret_cast(&gear_) - + reinterpret_cast(&total_path_length_)) + sizeof(gear_)); + _internal_metadata_.Clear(); +} + +bool ADCTrajectory::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.planning.ADCTrajectory) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // double total_path_length = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &total_path_length_))); + } else { + goto handle_unusual; + } + break; + } + + // double total_path_time = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &total_path_time_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.planning.ADCTrajectoryPoint adc_trajectory_point = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_adc_trajectory_point())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.planning.ADCSignals signals = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_signals())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.planning.EStop estop = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(50u /* 50 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_estop())); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.planning.ADCPathPoint adc_path_point = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(58u /* 58 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_adc_path_point())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.planning_internal.Debug debug = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(66u /* 66 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_debug())); + } else { + goto handle_unusual; + } + break; + } + + // bool is_replan = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(72u /* 72 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_replan_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Chassis.GearPosition gear = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(80u /* 80 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_gear(static_cast< ::apollo::canbus::Chassis_GearPosition >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.canbus.Signal signal = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(90u /* 90 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_signal())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.planning.ADCTrajectory) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.planning.ADCTrajectory) + return false; +#undef DO_ +} + +void ADCTrajectory::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.planning.ADCTrajectory) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // double total_path_length = 2; + if (this->total_path_length() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->total_path_length(), output); + } + + // double total_path_time = 3; + if (this->total_path_time() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->total_path_time(), output); + } + + // repeated .apollo.planning.ADCTrajectoryPoint adc_trajectory_point = 4; + for (unsigned int i = 0, + n = static_cast(this->adc_trajectory_point_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, + this->adc_trajectory_point(static_cast(i)), + output); + } + + // .apollo.planning.ADCSignals signals = 5; + if (this->has_signals()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, this->_internal_signals(), output); + } + + // .apollo.planning.EStop estop = 6; + if (this->has_estop()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 6, this->_internal_estop(), output); + } + + // repeated .apollo.planning.ADCPathPoint adc_path_point = 7; + for (unsigned int i = 0, + n = static_cast(this->adc_path_point_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 7, + this->adc_path_point(static_cast(i)), + output); + } + + // .apollo.planning_internal.Debug debug = 8; + if (this->has_debug()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 8, this->_internal_debug(), output); + } + + // bool is_replan = 9; + if (this->is_replan() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(9, this->is_replan(), output); + } + + // .apollo.canbus.Chassis.GearPosition gear = 10; + if (this->gear() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 10, this->gear(), output); + } + + // .apollo.canbus.Signal signal = 11; + if (this->has_signal()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 11, this->_internal_signal(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.planning.ADCTrajectory) +} + +::google::protobuf::uint8* ADCTrajectory::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.planning.ADCTrajectory) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // double total_path_length = 2; + if (this->total_path_length() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->total_path_length(), target); + } + + // double total_path_time = 3; + if (this->total_path_time() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->total_path_time(), target); + } + + // repeated .apollo.planning.ADCTrajectoryPoint adc_trajectory_point = 4; + for (unsigned int i = 0, + n = static_cast(this->adc_trajectory_point_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->adc_trajectory_point(static_cast(i)), deterministic, target); + } + + // .apollo.planning.ADCSignals signals = 5; + if (this->has_signals()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 5, this->_internal_signals(), deterministic, target); + } + + // .apollo.planning.EStop estop = 6; + if (this->has_estop()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 6, this->_internal_estop(), deterministic, target); + } + + // repeated .apollo.planning.ADCPathPoint adc_path_point = 7; + for (unsigned int i = 0, + n = static_cast(this->adc_path_point_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 7, this->adc_path_point(static_cast(i)), deterministic, target); + } + + // .apollo.planning_internal.Debug debug = 8; + if (this->has_debug()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 8, this->_internal_debug(), deterministic, target); + } + + // bool is_replan = 9; + if (this->is_replan() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(9, this->is_replan(), target); + } + + // .apollo.canbus.Chassis.GearPosition gear = 10; + if (this->gear() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 10, this->gear(), target); + } + + // .apollo.canbus.Signal signal = 11; + if (this->has_signal()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 11, this->_internal_signal(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.planning.ADCTrajectory) + return target; +} + +size_t ADCTrajectory::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.planning.ADCTrajectory) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.planning.ADCTrajectoryPoint adc_trajectory_point = 4; + { + unsigned int count = static_cast(this->adc_trajectory_point_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->adc_trajectory_point(static_cast(i))); + } + } + + // repeated .apollo.planning.ADCPathPoint adc_path_point = 7; + { + unsigned int count = static_cast(this->adc_path_point_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->adc_path_point(static_cast(i))); + } + } + + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.planning.ADCSignals signals = 5; + if (this->has_signals()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *signals_); + } + + // .apollo.planning.EStop estop = 6; + if (this->has_estop()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *estop_); + } + + // .apollo.planning_internal.Debug debug = 8; + if (this->has_debug()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *debug_); + } + + // .apollo.canbus.Signal signal = 11; + if (this->has_signal()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *signal_); + } + + // double total_path_length = 2; + if (this->total_path_length() != 0) { + total_size += 1 + 8; + } + + // double total_path_time = 3; + if (this->total_path_time() != 0) { + total_size += 1 + 8; + } + + // bool is_replan = 9; + if (this->is_replan() != 0) { + total_size += 1 + 1; + } + + // .apollo.canbus.Chassis.GearPosition gear = 10; + if (this->gear() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->gear()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ADCTrajectory::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.planning.ADCTrajectory) + GOOGLE_DCHECK_NE(&from, this); + const ADCTrajectory* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.planning.ADCTrajectory) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.planning.ADCTrajectory) + MergeFrom(*source); + } +} + +void ADCTrajectory::MergeFrom(const ADCTrajectory& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.planning.ADCTrajectory) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + adc_trajectory_point_.MergeFrom(from.adc_trajectory_point_); + adc_path_point_.MergeFrom(from.adc_path_point_); + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.has_signals()) { + mutable_signals()->::apollo::planning::ADCSignals::MergeFrom(from.signals()); + } + if (from.has_estop()) { + mutable_estop()->::apollo::planning::EStop::MergeFrom(from.estop()); + } + if (from.has_debug()) { + mutable_debug()->::apollo::planning_internal::Debug::MergeFrom(from.debug()); + } + if (from.has_signal()) { + mutable_signal()->::apollo::canbus::Signal::MergeFrom(from.signal()); + } + if (from.total_path_length() != 0) { + set_total_path_length(from.total_path_length()); + } + if (from.total_path_time() != 0) { + set_total_path_time(from.total_path_time()); + } + if (from.is_replan() != 0) { + set_is_replan(from.is_replan()); + } + if (from.gear() != 0) { + set_gear(from.gear()); + } +} + +void ADCTrajectory::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.planning.ADCTrajectory) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ADCTrajectory::CopyFrom(const ADCTrajectory& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.planning.ADCTrajectory) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ADCTrajectory::IsInitialized() const { + return true; +} + +void ADCTrajectory::Swap(ADCTrajectory* other) { + if (other == this) return; + InternalSwap(other); +} +void ADCTrajectory::InternalSwap(ADCTrajectory* other) { + using std::swap; + CastToBase(&adc_trajectory_point_)->InternalSwap(CastToBase(&other->adc_trajectory_point_)); + CastToBase(&adc_path_point_)->InternalSwap(CastToBase(&other->adc_path_point_)); + swap(header_, other->header_); + swap(signals_, other->signals_); + swap(estop_, other->estop_); + swap(debug_, other->debug_); + swap(signal_, other->signal_); + swap(total_path_length_, other->total_path_length_); + swap(total_path_time_, other->total_path_time_); + swap(is_replan_, other->is_replan_); + swap(gear_, other->gear_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata ADCTrajectory::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace planning +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::planning::ADCTrajectoryPoint* Arena::CreateMaybeMessage< ::apollo::planning::ADCTrajectoryPoint >(Arena* arena) { + return Arena::CreateInternal< ::apollo::planning::ADCTrajectoryPoint >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::planning::ADCSignals* Arena::CreateMaybeMessage< ::apollo::planning::ADCSignals >(Arena* arena) { + return Arena::CreateInternal< ::apollo::planning::ADCSignals >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::planning::EStop* Arena::CreateMaybeMessage< ::apollo::planning::EStop >(Arena* arena) { + return Arena::CreateInternal< ::apollo::planning::EStop >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::planning::ADCPathPoint* Arena::CreateMaybeMessage< ::apollo::planning::ADCPathPoint >(Arena* arena) { + return Arena::CreateInternal< ::apollo::planning::ADCPathPoint >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::planning::ADCTrajectory* Arena::CreateMaybeMessage< ::apollo::planning::ADCTrajectory >(Arena* arena) { + return Arena::CreateInternal< ::apollo::planning::ADCTrajectory >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/planning/planning.pb.h b/apollo_msgs/include/apollo_msgs/proto/planning/planning.pb.h new file mode 100644 index 0000000..804ae66 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/planning/planning.pb.h @@ -0,0 +1,1587 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/planning/planning.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "apollo_msgs/proto/common/header.pb.h" +#include "apollo_msgs/proto/canbus/chassis.pb.h" +#include "apollo_msgs/proto/planning/planning_internal.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[5]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto +namespace apollo { +namespace planning { +class ADCPathPoint; +class ADCPathPointDefaultTypeInternal; +extern ADCPathPointDefaultTypeInternal _ADCPathPoint_default_instance_; +class ADCSignals; +class ADCSignalsDefaultTypeInternal; +extern ADCSignalsDefaultTypeInternal _ADCSignals_default_instance_; +class ADCTrajectory; +class ADCTrajectoryDefaultTypeInternal; +extern ADCTrajectoryDefaultTypeInternal _ADCTrajectory_default_instance_; +class ADCTrajectoryPoint; +class ADCTrajectoryPointDefaultTypeInternal; +extern ADCTrajectoryPointDefaultTypeInternal _ADCTrajectoryPoint_default_instance_; +class EStop; +class EStopDefaultTypeInternal; +extern EStopDefaultTypeInternal _EStop_default_instance_; +} // namespace planning +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::planning::ADCPathPoint* Arena::CreateMaybeMessage<::apollo::planning::ADCPathPoint>(Arena*); +template<> ::apollo::planning::ADCSignals* Arena::CreateMaybeMessage<::apollo::planning::ADCSignals>(Arena*); +template<> ::apollo::planning::ADCTrajectory* Arena::CreateMaybeMessage<::apollo::planning::ADCTrajectory>(Arena*); +template<> ::apollo::planning::ADCTrajectoryPoint* Arena::CreateMaybeMessage<::apollo::planning::ADCTrajectoryPoint>(Arena*); +template<> ::apollo::planning::EStop* Arena::CreateMaybeMessage<::apollo::planning::EStop>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace planning { + +enum ADCSignals_SignalType { + ADCSignals_SignalType_LEFT_TURN = 0, + ADCSignals_SignalType_RIGHT_TURN = 1, + ADCSignals_SignalType_LOW_BEAM_LIGHT = 2, + ADCSignals_SignalType_HIGH_BEAM_LIGHT = 3, + ADCSignals_SignalType_FOG_LIGHT = 4, + ADCSignals_SignalType_EMERGENCY_LIGHT = 5, + ADCSignals_SignalType_ADCSignals_SignalType_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + ADCSignals_SignalType_ADCSignals_SignalType_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool ADCSignals_SignalType_IsValid(int value); +const ADCSignals_SignalType ADCSignals_SignalType_SignalType_MIN = ADCSignals_SignalType_LEFT_TURN; +const ADCSignals_SignalType ADCSignals_SignalType_SignalType_MAX = ADCSignals_SignalType_EMERGENCY_LIGHT; +const int ADCSignals_SignalType_SignalType_ARRAYSIZE = ADCSignals_SignalType_SignalType_MAX + 1; + +const ::google::protobuf::EnumDescriptor* ADCSignals_SignalType_descriptor(); +inline const ::std::string& ADCSignals_SignalType_Name(ADCSignals_SignalType value) { + return ::google::protobuf::internal::NameOfEnum( + ADCSignals_SignalType_descriptor(), value); +} +inline bool ADCSignals_SignalType_Parse( + const ::std::string& name, ADCSignals_SignalType* value) { + return ::google::protobuf::internal::ParseNamedEnum( + ADCSignals_SignalType_descriptor(), name, value); +} +// =================================================================== + +class ADCTrajectoryPoint : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.planning.ADCTrajectoryPoint) */ { + public: + ADCTrajectoryPoint(); + virtual ~ADCTrajectoryPoint(); + + ADCTrajectoryPoint(const ADCTrajectoryPoint& from); + + inline ADCTrajectoryPoint& operator=(const ADCTrajectoryPoint& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ADCTrajectoryPoint(ADCTrajectoryPoint&& from) noexcept + : ADCTrajectoryPoint() { + *this = ::std::move(from); + } + + inline ADCTrajectoryPoint& operator=(ADCTrajectoryPoint&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ADCTrajectoryPoint& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ADCTrajectoryPoint* internal_default_instance() { + return reinterpret_cast( + &_ADCTrajectoryPoint_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(ADCTrajectoryPoint* other); + friend void swap(ADCTrajectoryPoint& a, ADCTrajectoryPoint& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ADCTrajectoryPoint* New() const final { + return CreateMaybeMessage(NULL); + } + + ADCTrajectoryPoint* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ADCTrajectoryPoint& from); + void MergeFrom(const ADCTrajectoryPoint& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ADCTrajectoryPoint* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double x = 1; + void clear_x(); + static const int kXFieldNumber = 1; + double x() const; + void set_x(double value); + + // double y = 2; + void clear_y(); + static const int kYFieldNumber = 2; + double y() const; + void set_y(double value); + + // double z = 3; + void clear_z(); + static const int kZFieldNumber = 3; + double z() const; + void set_z(double value); + + // double s = 4; + void clear_s(); + static const int kSFieldNumber = 4; + double s() const; + void set_s(double value); + + // double l = 5; + void clear_l(); + static const int kLFieldNumber = 5; + double l() const; + void set_l(double value); + + // double speed = 6; + void clear_speed(); + static const int kSpeedFieldNumber = 6; + double speed() const; + void set_speed(double value); + + // double acceleration_s = 7; + void clear_acceleration_s(); + static const int kAccelerationSFieldNumber = 7; + double acceleration_s() const; + void set_acceleration_s(double value); + + // double curvature = 8; + void clear_curvature(); + static const int kCurvatureFieldNumber = 8; + double curvature() const; + void set_curvature(double value); + + // double curvature_change_rate = 9; + void clear_curvature_change_rate(); + static const int kCurvatureChangeRateFieldNumber = 9; + double curvature_change_rate() const; + void set_curvature_change_rate(double value); + + // double relative_time = 10; + void clear_relative_time(); + static const int kRelativeTimeFieldNumber = 10; + double relative_time() const; + void set_relative_time(double value); + + // double theta = 11; + void clear_theta(); + static const int kThetaFieldNumber = 11; + double theta() const; + void set_theta(double value); + + // double accumulated_s = 12; + void clear_accumulated_s(); + static const int kAccumulatedSFieldNumber = 12; + double accumulated_s() const; + void set_accumulated_s(double value); + + // @@protoc_insertion_point(class_scope:apollo.planning.ADCTrajectoryPoint) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double x_; + double y_; + double z_; + double s_; + double l_; + double speed_; + double acceleration_s_; + double curvature_; + double curvature_change_rate_; + double relative_time_; + double theta_; + double accumulated_s_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ADCSignals : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.planning.ADCSignals) */ { + public: + ADCSignals(); + virtual ~ADCSignals(); + + ADCSignals(const ADCSignals& from); + + inline ADCSignals& operator=(const ADCSignals& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ADCSignals(ADCSignals&& from) noexcept + : ADCSignals() { + *this = ::std::move(from); + } + + inline ADCSignals& operator=(ADCSignals&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ADCSignals& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ADCSignals* internal_default_instance() { + return reinterpret_cast( + &_ADCSignals_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(ADCSignals* other); + friend void swap(ADCSignals& a, ADCSignals& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ADCSignals* New() const final { + return CreateMaybeMessage(NULL); + } + + ADCSignals* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ADCSignals& from); + void MergeFrom(const ADCSignals& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ADCSignals* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef ADCSignals_SignalType SignalType; + static const SignalType LEFT_TURN = + ADCSignals_SignalType_LEFT_TURN; + static const SignalType RIGHT_TURN = + ADCSignals_SignalType_RIGHT_TURN; + static const SignalType LOW_BEAM_LIGHT = + ADCSignals_SignalType_LOW_BEAM_LIGHT; + static const SignalType HIGH_BEAM_LIGHT = + ADCSignals_SignalType_HIGH_BEAM_LIGHT; + static const SignalType FOG_LIGHT = + ADCSignals_SignalType_FOG_LIGHT; + static const SignalType EMERGENCY_LIGHT = + ADCSignals_SignalType_EMERGENCY_LIGHT; + static inline bool SignalType_IsValid(int value) { + return ADCSignals_SignalType_IsValid(value); + } + static const SignalType SignalType_MIN = + ADCSignals_SignalType_SignalType_MIN; + static const SignalType SignalType_MAX = + ADCSignals_SignalType_SignalType_MAX; + static const int SignalType_ARRAYSIZE = + ADCSignals_SignalType_SignalType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + SignalType_descriptor() { + return ADCSignals_SignalType_descriptor(); + } + static inline const ::std::string& SignalType_Name(SignalType value) { + return ADCSignals_SignalType_Name(value); + } + static inline bool SignalType_Parse(const ::std::string& name, + SignalType* value) { + return ADCSignals_SignalType_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // repeated .apollo.planning.ADCSignals.SignalType signal = 1; + int signal_size() const; + void clear_signal(); + static const int kSignalFieldNumber = 1; + ::apollo::planning::ADCSignals_SignalType signal(int index) const; + void set_signal(int index, ::apollo::planning::ADCSignals_SignalType value); + void add_signal(::apollo::planning::ADCSignals_SignalType value); + const ::google::protobuf::RepeatedField& signal() const; + ::google::protobuf::RepeatedField* mutable_signal(); + + // @@protoc_insertion_point(class_scope:apollo.planning.ADCSignals) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedField signal_; + mutable int _signal_cached_byte_size_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class EStop : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.planning.EStop) */ { + public: + EStop(); + virtual ~EStop(); + + EStop(const EStop& from); + + inline EStop& operator=(const EStop& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + EStop(EStop&& from) noexcept + : EStop() { + *this = ::std::move(from); + } + + inline EStop& operator=(EStop&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const EStop& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const EStop* internal_default_instance() { + return reinterpret_cast( + &_EStop_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + void Swap(EStop* other); + friend void swap(EStop& a, EStop& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline EStop* New() const final { + return CreateMaybeMessage(NULL); + } + + EStop* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const EStop& from); + void MergeFrom(const EStop& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(EStop* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // bool is_estop = 1; + void clear_is_estop(); + static const int kIsEstopFieldNumber = 1; + bool is_estop() const; + void set_is_estop(bool value); + + // @@protoc_insertion_point(class_scope:apollo.planning.EStop) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + bool is_estop_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ADCPathPoint : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.planning.ADCPathPoint) */ { + public: + ADCPathPoint(); + virtual ~ADCPathPoint(); + + ADCPathPoint(const ADCPathPoint& from); + + inline ADCPathPoint& operator=(const ADCPathPoint& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ADCPathPoint(ADCPathPoint&& from) noexcept + : ADCPathPoint() { + *this = ::std::move(from); + } + + inline ADCPathPoint& operator=(ADCPathPoint&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ADCPathPoint& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ADCPathPoint* internal_default_instance() { + return reinterpret_cast( + &_ADCPathPoint_default_instance_); + } + static constexpr int kIndexInFileMessages = + 3; + + void Swap(ADCPathPoint* other); + friend void swap(ADCPathPoint& a, ADCPathPoint& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ADCPathPoint* New() const final { + return CreateMaybeMessage(NULL); + } + + ADCPathPoint* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ADCPathPoint& from); + void MergeFrom(const ADCPathPoint& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ADCPathPoint* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double x = 1; + void clear_x(); + static const int kXFieldNumber = 1; + double x() const; + void set_x(double value); + + // double y = 2; + void clear_y(); + static const int kYFieldNumber = 2; + double y() const; + void set_y(double value); + + // double z = 3; + void clear_z(); + static const int kZFieldNumber = 3; + double z() const; + void set_z(double value); + + // double curvature = 4; + void clear_curvature(); + static const int kCurvatureFieldNumber = 4; + double curvature() const; + void set_curvature(double value); + + // double heading = 5; + void clear_heading(); + static const int kHeadingFieldNumber = 5; + double heading() const; + void set_heading(double value); + + // @@protoc_insertion_point(class_scope:apollo.planning.ADCPathPoint) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double x_; + double y_; + double z_; + double curvature_; + double heading_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class ADCTrajectory : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.planning.ADCTrajectory) */ { + public: + ADCTrajectory(); + virtual ~ADCTrajectory(); + + ADCTrajectory(const ADCTrajectory& from); + + inline ADCTrajectory& operator=(const ADCTrajectory& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ADCTrajectory(ADCTrajectory&& from) noexcept + : ADCTrajectory() { + *this = ::std::move(from); + } + + inline ADCTrajectory& operator=(ADCTrajectory&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const ADCTrajectory& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ADCTrajectory* internal_default_instance() { + return reinterpret_cast( + &_ADCTrajectory_default_instance_); + } + static constexpr int kIndexInFileMessages = + 4; + + void Swap(ADCTrajectory* other); + friend void swap(ADCTrajectory& a, ADCTrajectory& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline ADCTrajectory* New() const final { + return CreateMaybeMessage(NULL); + } + + ADCTrajectory* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const ADCTrajectory& from); + void MergeFrom(const ADCTrajectory& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(ADCTrajectory* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.planning.ADCTrajectoryPoint adc_trajectory_point = 4; + int adc_trajectory_point_size() const; + void clear_adc_trajectory_point(); + static const int kAdcTrajectoryPointFieldNumber = 4; + ::apollo::planning::ADCTrajectoryPoint* mutable_adc_trajectory_point(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::planning::ADCTrajectoryPoint >* + mutable_adc_trajectory_point(); + const ::apollo::planning::ADCTrajectoryPoint& adc_trajectory_point(int index) const; + ::apollo::planning::ADCTrajectoryPoint* add_adc_trajectory_point(); + const ::google::protobuf::RepeatedPtrField< ::apollo::planning::ADCTrajectoryPoint >& + adc_trajectory_point() const; + + // repeated .apollo.planning.ADCPathPoint adc_path_point = 7; + int adc_path_point_size() const; + void clear_adc_path_point(); + static const int kAdcPathPointFieldNumber = 7; + ::apollo::planning::ADCPathPoint* mutable_adc_path_point(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::planning::ADCPathPoint >* + mutable_adc_path_point(); + const ::apollo::planning::ADCPathPoint& adc_path_point(int index) const; + ::apollo::planning::ADCPathPoint* add_adc_path_point(); + const ::google::protobuf::RepeatedPtrField< ::apollo::planning::ADCPathPoint >& + adc_path_point() const; + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.planning.ADCSignals signals = 5; + bool has_signals() const; + void clear_signals(); + static const int kSignalsFieldNumber = 5; + private: + const ::apollo::planning::ADCSignals& _internal_signals() const; + public: + const ::apollo::planning::ADCSignals& signals() const; + ::apollo::planning::ADCSignals* release_signals(); + ::apollo::planning::ADCSignals* mutable_signals(); + void set_allocated_signals(::apollo::planning::ADCSignals* signals); + + // .apollo.planning.EStop estop = 6; + bool has_estop() const; + void clear_estop(); + static const int kEstopFieldNumber = 6; + private: + const ::apollo::planning::EStop& _internal_estop() const; + public: + const ::apollo::planning::EStop& estop() const; + ::apollo::planning::EStop* release_estop(); + ::apollo::planning::EStop* mutable_estop(); + void set_allocated_estop(::apollo::planning::EStop* estop); + + // .apollo.planning_internal.Debug debug = 8; + bool has_debug() const; + void clear_debug(); + static const int kDebugFieldNumber = 8; + private: + const ::apollo::planning_internal::Debug& _internal_debug() const; + public: + const ::apollo::planning_internal::Debug& debug() const; + ::apollo::planning_internal::Debug* release_debug(); + ::apollo::planning_internal::Debug* mutable_debug(); + void set_allocated_debug(::apollo::planning_internal::Debug* debug); + + // .apollo.canbus.Signal signal = 11; + bool has_signal() const; + void clear_signal(); + static const int kSignalFieldNumber = 11; + private: + const ::apollo::canbus::Signal& _internal_signal() const; + public: + const ::apollo::canbus::Signal& signal() const; + ::apollo::canbus::Signal* release_signal(); + ::apollo::canbus::Signal* mutable_signal(); + void set_allocated_signal(::apollo::canbus::Signal* signal); + + // double total_path_length = 2; + void clear_total_path_length(); + static const int kTotalPathLengthFieldNumber = 2; + double total_path_length() const; + void set_total_path_length(double value); + + // double total_path_time = 3; + void clear_total_path_time(); + static const int kTotalPathTimeFieldNumber = 3; + double total_path_time() const; + void set_total_path_time(double value); + + // bool is_replan = 9; + void clear_is_replan(); + static const int kIsReplanFieldNumber = 9; + bool is_replan() const; + void set_is_replan(bool value); + + // .apollo.canbus.Chassis.GearPosition gear = 10; + void clear_gear(); + static const int kGearFieldNumber = 10; + ::apollo::canbus::Chassis_GearPosition gear() const; + void set_gear(::apollo::canbus::Chassis_GearPosition value); + + // @@protoc_insertion_point(class_scope:apollo.planning.ADCTrajectory) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::planning::ADCTrajectoryPoint > adc_trajectory_point_; + ::google::protobuf::RepeatedPtrField< ::apollo::planning::ADCPathPoint > adc_path_point_; + ::apollo::common::Header* header_; + ::apollo::planning::ADCSignals* signals_; + ::apollo::planning::EStop* estop_; + ::apollo::planning_internal::Debug* debug_; + ::apollo::canbus::Signal* signal_; + double total_path_length_; + double total_path_time_; + bool is_replan_; + int gear_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// ADCTrajectoryPoint + +// double x = 1; +inline void ADCTrajectoryPoint::clear_x() { + x_ = 0; +} +inline double ADCTrajectoryPoint::x() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectoryPoint.x) + return x_; +} +inline void ADCTrajectoryPoint::set_x(double value) { + + x_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectoryPoint.x) +} + +// double y = 2; +inline void ADCTrajectoryPoint::clear_y() { + y_ = 0; +} +inline double ADCTrajectoryPoint::y() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectoryPoint.y) + return y_; +} +inline void ADCTrajectoryPoint::set_y(double value) { + + y_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectoryPoint.y) +} + +// double z = 3; +inline void ADCTrajectoryPoint::clear_z() { + z_ = 0; +} +inline double ADCTrajectoryPoint::z() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectoryPoint.z) + return z_; +} +inline void ADCTrajectoryPoint::set_z(double value) { + + z_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectoryPoint.z) +} + +// double speed = 6; +inline void ADCTrajectoryPoint::clear_speed() { + speed_ = 0; +} +inline double ADCTrajectoryPoint::speed() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectoryPoint.speed) + return speed_; +} +inline void ADCTrajectoryPoint::set_speed(double value) { + + speed_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectoryPoint.speed) +} + +// double acceleration_s = 7; +inline void ADCTrajectoryPoint::clear_acceleration_s() { + acceleration_s_ = 0; +} +inline double ADCTrajectoryPoint::acceleration_s() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectoryPoint.acceleration_s) + return acceleration_s_; +} +inline void ADCTrajectoryPoint::set_acceleration_s(double value) { + + acceleration_s_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectoryPoint.acceleration_s) +} + +// double curvature = 8; +inline void ADCTrajectoryPoint::clear_curvature() { + curvature_ = 0; +} +inline double ADCTrajectoryPoint::curvature() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectoryPoint.curvature) + return curvature_; +} +inline void ADCTrajectoryPoint::set_curvature(double value) { + + curvature_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectoryPoint.curvature) +} + +// double curvature_change_rate = 9; +inline void ADCTrajectoryPoint::clear_curvature_change_rate() { + curvature_change_rate_ = 0; +} +inline double ADCTrajectoryPoint::curvature_change_rate() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectoryPoint.curvature_change_rate) + return curvature_change_rate_; +} +inline void ADCTrajectoryPoint::set_curvature_change_rate(double value) { + + curvature_change_rate_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectoryPoint.curvature_change_rate) +} + +// double relative_time = 10; +inline void ADCTrajectoryPoint::clear_relative_time() { + relative_time_ = 0; +} +inline double ADCTrajectoryPoint::relative_time() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectoryPoint.relative_time) + return relative_time_; +} +inline void ADCTrajectoryPoint::set_relative_time(double value) { + + relative_time_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectoryPoint.relative_time) +} + +// double theta = 11; +inline void ADCTrajectoryPoint::clear_theta() { + theta_ = 0; +} +inline double ADCTrajectoryPoint::theta() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectoryPoint.theta) + return theta_; +} +inline void ADCTrajectoryPoint::set_theta(double value) { + + theta_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectoryPoint.theta) +} + +// double accumulated_s = 12; +inline void ADCTrajectoryPoint::clear_accumulated_s() { + accumulated_s_ = 0; +} +inline double ADCTrajectoryPoint::accumulated_s() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectoryPoint.accumulated_s) + return accumulated_s_; +} +inline void ADCTrajectoryPoint::set_accumulated_s(double value) { + + accumulated_s_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectoryPoint.accumulated_s) +} + +// double s = 4; +inline void ADCTrajectoryPoint::clear_s() { + s_ = 0; +} +inline double ADCTrajectoryPoint::s() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectoryPoint.s) + return s_; +} +inline void ADCTrajectoryPoint::set_s(double value) { + + s_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectoryPoint.s) +} + +// double l = 5; +inline void ADCTrajectoryPoint::clear_l() { + l_ = 0; +} +inline double ADCTrajectoryPoint::l() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectoryPoint.l) + return l_; +} +inline void ADCTrajectoryPoint::set_l(double value) { + + l_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectoryPoint.l) +} + +// ------------------------------------------------------------------- + +// ADCSignals + +// repeated .apollo.planning.ADCSignals.SignalType signal = 1; +inline int ADCSignals::signal_size() const { + return signal_.size(); +} +inline void ADCSignals::clear_signal() { + signal_.Clear(); +} +inline ::apollo::planning::ADCSignals_SignalType ADCSignals::signal(int index) const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCSignals.signal) + return static_cast< ::apollo::planning::ADCSignals_SignalType >(signal_.Get(index)); +} +inline void ADCSignals::set_signal(int index, ::apollo::planning::ADCSignals_SignalType value) { + signal_.Set(index, value); + // @@protoc_insertion_point(field_set:apollo.planning.ADCSignals.signal) +} +inline void ADCSignals::add_signal(::apollo::planning::ADCSignals_SignalType value) { + signal_.Add(value); + // @@protoc_insertion_point(field_add:apollo.planning.ADCSignals.signal) +} +inline const ::google::protobuf::RepeatedField& +ADCSignals::signal() const { + // @@protoc_insertion_point(field_list:apollo.planning.ADCSignals.signal) + return signal_; +} +inline ::google::protobuf::RepeatedField* +ADCSignals::mutable_signal() { + // @@protoc_insertion_point(field_mutable_list:apollo.planning.ADCSignals.signal) + return &signal_; +} + +// ------------------------------------------------------------------- + +// EStop + +// bool is_estop = 1; +inline void EStop::clear_is_estop() { + is_estop_ = false; +} +inline bool EStop::is_estop() const { + // @@protoc_insertion_point(field_get:apollo.planning.EStop.is_estop) + return is_estop_; +} +inline void EStop::set_is_estop(bool value) { + + is_estop_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.EStop.is_estop) +} + +// ------------------------------------------------------------------- + +// ADCPathPoint + +// double x = 1; +inline void ADCPathPoint::clear_x() { + x_ = 0; +} +inline double ADCPathPoint::x() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCPathPoint.x) + return x_; +} +inline void ADCPathPoint::set_x(double value) { + + x_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCPathPoint.x) +} + +// double y = 2; +inline void ADCPathPoint::clear_y() { + y_ = 0; +} +inline double ADCPathPoint::y() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCPathPoint.y) + return y_; +} +inline void ADCPathPoint::set_y(double value) { + + y_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCPathPoint.y) +} + +// double z = 3; +inline void ADCPathPoint::clear_z() { + z_ = 0; +} +inline double ADCPathPoint::z() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCPathPoint.z) + return z_; +} +inline void ADCPathPoint::set_z(double value) { + + z_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCPathPoint.z) +} + +// double curvature = 4; +inline void ADCPathPoint::clear_curvature() { + curvature_ = 0; +} +inline double ADCPathPoint::curvature() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCPathPoint.curvature) + return curvature_; +} +inline void ADCPathPoint::set_curvature(double value) { + + curvature_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCPathPoint.curvature) +} + +// double heading = 5; +inline void ADCPathPoint::clear_heading() { + heading_ = 0; +} +inline double ADCPathPoint::heading() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCPathPoint.heading) + return heading_; +} +inline void ADCPathPoint::set_heading(double value) { + + heading_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCPathPoint.heading) +} + +// ------------------------------------------------------------------- + +// ADCTrajectory + +// .apollo.common.Header header = 1; +inline bool ADCTrajectory::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& ADCTrajectory::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& ADCTrajectory::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectory.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* ADCTrajectory::release_header() { + // @@protoc_insertion_point(field_release:apollo.planning.ADCTrajectory.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* ADCTrajectory::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.planning.ADCTrajectory.header) + return header_; +} +inline void ADCTrajectory::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.planning.ADCTrajectory.header) +} + +// double total_path_length = 2; +inline void ADCTrajectory::clear_total_path_length() { + total_path_length_ = 0; +} +inline double ADCTrajectory::total_path_length() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectory.total_path_length) + return total_path_length_; +} +inline void ADCTrajectory::set_total_path_length(double value) { + + total_path_length_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectory.total_path_length) +} + +// double total_path_time = 3; +inline void ADCTrajectory::clear_total_path_time() { + total_path_time_ = 0; +} +inline double ADCTrajectory::total_path_time() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectory.total_path_time) + return total_path_time_; +} +inline void ADCTrajectory::set_total_path_time(double value) { + + total_path_time_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectory.total_path_time) +} + +// repeated .apollo.planning.ADCTrajectoryPoint adc_trajectory_point = 4; +inline int ADCTrajectory::adc_trajectory_point_size() const { + return adc_trajectory_point_.size(); +} +inline void ADCTrajectory::clear_adc_trajectory_point() { + adc_trajectory_point_.Clear(); +} +inline ::apollo::planning::ADCTrajectoryPoint* ADCTrajectory::mutable_adc_trajectory_point(int index) { + // @@protoc_insertion_point(field_mutable:apollo.planning.ADCTrajectory.adc_trajectory_point) + return adc_trajectory_point_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::planning::ADCTrajectoryPoint >* +ADCTrajectory::mutable_adc_trajectory_point() { + // @@protoc_insertion_point(field_mutable_list:apollo.planning.ADCTrajectory.adc_trajectory_point) + return &adc_trajectory_point_; +} +inline const ::apollo::planning::ADCTrajectoryPoint& ADCTrajectory::adc_trajectory_point(int index) const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectory.adc_trajectory_point) + return adc_trajectory_point_.Get(index); +} +inline ::apollo::planning::ADCTrajectoryPoint* ADCTrajectory::add_adc_trajectory_point() { + // @@protoc_insertion_point(field_add:apollo.planning.ADCTrajectory.adc_trajectory_point) + return adc_trajectory_point_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::planning::ADCTrajectoryPoint >& +ADCTrajectory::adc_trajectory_point() const { + // @@protoc_insertion_point(field_list:apollo.planning.ADCTrajectory.adc_trajectory_point) + return adc_trajectory_point_; +} + +// .apollo.planning.EStop estop = 6; +inline bool ADCTrajectory::has_estop() const { + return this != internal_default_instance() && estop_ != NULL; +} +inline void ADCTrajectory::clear_estop() { + if (GetArenaNoVirtual() == NULL && estop_ != NULL) { + delete estop_; + } + estop_ = NULL; +} +inline const ::apollo::planning::EStop& ADCTrajectory::_internal_estop() const { + return *estop_; +} +inline const ::apollo::planning::EStop& ADCTrajectory::estop() const { + const ::apollo::planning::EStop* p = estop_; + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectory.estop) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::planning::_EStop_default_instance_); +} +inline ::apollo::planning::EStop* ADCTrajectory::release_estop() { + // @@protoc_insertion_point(field_release:apollo.planning.ADCTrajectory.estop) + + ::apollo::planning::EStop* temp = estop_; + estop_ = NULL; + return temp; +} +inline ::apollo::planning::EStop* ADCTrajectory::mutable_estop() { + + if (estop_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::planning::EStop>(GetArenaNoVirtual()); + estop_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.planning.ADCTrajectory.estop) + return estop_; +} +inline void ADCTrajectory::set_allocated_estop(::apollo::planning::EStop* estop) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete estop_; + } + if (estop) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + estop = ::google::protobuf::internal::GetOwnedMessage( + message_arena, estop, submessage_arena); + } + + } else { + + } + estop_ = estop; + // @@protoc_insertion_point(field_set_allocated:apollo.planning.ADCTrajectory.estop) +} + +// repeated .apollo.planning.ADCPathPoint adc_path_point = 7; +inline int ADCTrajectory::adc_path_point_size() const { + return adc_path_point_.size(); +} +inline void ADCTrajectory::clear_adc_path_point() { + adc_path_point_.Clear(); +} +inline ::apollo::planning::ADCPathPoint* ADCTrajectory::mutable_adc_path_point(int index) { + // @@protoc_insertion_point(field_mutable:apollo.planning.ADCTrajectory.adc_path_point) + return adc_path_point_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::planning::ADCPathPoint >* +ADCTrajectory::mutable_adc_path_point() { + // @@protoc_insertion_point(field_mutable_list:apollo.planning.ADCTrajectory.adc_path_point) + return &adc_path_point_; +} +inline const ::apollo::planning::ADCPathPoint& ADCTrajectory::adc_path_point(int index) const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectory.adc_path_point) + return adc_path_point_.Get(index); +} +inline ::apollo::planning::ADCPathPoint* ADCTrajectory::add_adc_path_point() { + // @@protoc_insertion_point(field_add:apollo.planning.ADCTrajectory.adc_path_point) + return adc_path_point_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::planning::ADCPathPoint >& +ADCTrajectory::adc_path_point() const { + // @@protoc_insertion_point(field_list:apollo.planning.ADCTrajectory.adc_path_point) + return adc_path_point_; +} + +// bool is_replan = 9; +inline void ADCTrajectory::clear_is_replan() { + is_replan_ = false; +} +inline bool ADCTrajectory::is_replan() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectory.is_replan) + return is_replan_; +} +inline void ADCTrajectory::set_is_replan(bool value) { + + is_replan_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectory.is_replan) +} + +// .apollo.canbus.Chassis.GearPosition gear = 10; +inline void ADCTrajectory::clear_gear() { + gear_ = 0; +} +inline ::apollo::canbus::Chassis_GearPosition ADCTrajectory::gear() const { + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectory.gear) + return static_cast< ::apollo::canbus::Chassis_GearPosition >(gear_); +} +inline void ADCTrajectory::set_gear(::apollo::canbus::Chassis_GearPosition value) { + + gear_ = value; + // @@protoc_insertion_point(field_set:apollo.planning.ADCTrajectory.gear) +} + +// .apollo.planning_internal.Debug debug = 8; +inline bool ADCTrajectory::has_debug() const { + return this != internal_default_instance() && debug_ != NULL; +} +inline const ::apollo::planning_internal::Debug& ADCTrajectory::_internal_debug() const { + return *debug_; +} +inline const ::apollo::planning_internal::Debug& ADCTrajectory::debug() const { + const ::apollo::planning_internal::Debug* p = debug_; + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectory.debug) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::planning_internal::_Debug_default_instance_); +} +inline ::apollo::planning_internal::Debug* ADCTrajectory::release_debug() { + // @@protoc_insertion_point(field_release:apollo.planning.ADCTrajectory.debug) + + ::apollo::planning_internal::Debug* temp = debug_; + debug_ = NULL; + return temp; +} +inline ::apollo::planning_internal::Debug* ADCTrajectory::mutable_debug() { + + if (debug_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::planning_internal::Debug>(GetArenaNoVirtual()); + debug_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.planning.ADCTrajectory.debug) + return debug_; +} +inline void ADCTrajectory::set_allocated_debug(::apollo::planning_internal::Debug* debug) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(debug_); + } + if (debug) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + debug = ::google::protobuf::internal::GetOwnedMessage( + message_arena, debug, submessage_arena); + } + + } else { + + } + debug_ = debug; + // @@protoc_insertion_point(field_set_allocated:apollo.planning.ADCTrajectory.debug) +} + +// .apollo.canbus.Signal signal = 11; +inline bool ADCTrajectory::has_signal() const { + return this != internal_default_instance() && signal_ != NULL; +} +inline const ::apollo::canbus::Signal& ADCTrajectory::_internal_signal() const { + return *signal_; +} +inline const ::apollo::canbus::Signal& ADCTrajectory::signal() const { + const ::apollo::canbus::Signal* p = signal_; + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectory.signal) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::canbus::_Signal_default_instance_); +} +inline ::apollo::canbus::Signal* ADCTrajectory::release_signal() { + // @@protoc_insertion_point(field_release:apollo.planning.ADCTrajectory.signal) + + ::apollo::canbus::Signal* temp = signal_; + signal_ = NULL; + return temp; +} +inline ::apollo::canbus::Signal* ADCTrajectory::mutable_signal() { + + if (signal_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::canbus::Signal>(GetArenaNoVirtual()); + signal_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.planning.ADCTrajectory.signal) + return signal_; +} +inline void ADCTrajectory::set_allocated_signal(::apollo::canbus::Signal* signal) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(signal_); + } + if (signal) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + signal = ::google::protobuf::internal::GetOwnedMessage( + message_arena, signal, submessage_arena); + } + + } else { + + } + signal_ = signal; + // @@protoc_insertion_point(field_set_allocated:apollo.planning.ADCTrajectory.signal) +} + +// .apollo.planning.ADCSignals signals = 5; +inline bool ADCTrajectory::has_signals() const { + return this != internal_default_instance() && signals_ != NULL; +} +inline void ADCTrajectory::clear_signals() { + if (GetArenaNoVirtual() == NULL && signals_ != NULL) { + delete signals_; + } + signals_ = NULL; +} +inline const ::apollo::planning::ADCSignals& ADCTrajectory::_internal_signals() const { + return *signals_; +} +inline const ::apollo::planning::ADCSignals& ADCTrajectory::signals() const { + const ::apollo::planning::ADCSignals* p = signals_; + // @@protoc_insertion_point(field_get:apollo.planning.ADCTrajectory.signals) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::planning::_ADCSignals_default_instance_); +} +inline ::apollo::planning::ADCSignals* ADCTrajectory::release_signals() { + // @@protoc_insertion_point(field_release:apollo.planning.ADCTrajectory.signals) + + ::apollo::planning::ADCSignals* temp = signals_; + signals_ = NULL; + return temp; +} +inline ::apollo::planning::ADCSignals* ADCTrajectory::mutable_signals() { + + if (signals_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::planning::ADCSignals>(GetArenaNoVirtual()); + signals_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.planning.ADCTrajectory.signals) + return signals_; +} +inline void ADCTrajectory::set_allocated_signals(::apollo::planning::ADCSignals* signals) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete signals_; + } + if (signals) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + signals = ::google::protobuf::internal::GetOwnedMessage( + message_arena, signals, submessage_arena); + } + + } else { + + } + signals_ = signals; + // @@protoc_insertion_point(field_set_allocated:apollo.planning.ADCTrajectory.signals) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace planning +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::planning::ADCSignals_SignalType> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::planning::ADCSignals_SignalType>() { + return ::apollo::planning::ADCSignals_SignalType_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fplanning_2fplanning_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/planning/planning_internal.pb.cc b/apollo_msgs/include/apollo_msgs/proto/planning/planning_internal.pb.cc new file mode 100644 index 0000000..c455704 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/planning/planning_internal.pb.cc @@ -0,0 +1,2680 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/planning/planning_internal.proto + +#include "apollo_msgs/proto/planning/planning_internal.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_LightSignal; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<8> scc_info_MainDecision; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto ::google::protobuf::internal::SCCInfo<8> scc_info_ObjectDecisionType; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto ::google::protobuf::internal::SCCInfo<3> scc_info_Pose; +} // namespace protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Point; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Debug_DebugMessage; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto ::google::protobuf::internal::SCCInfo<3> scc_info_PlanningObstacle; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto ::google::protobuf::internal::SCCInfo<5> scc_info_PlanningData; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Trajectory; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto +namespace apollo { +namespace planning_internal { +class PlanningObstacleDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _PlanningObstacle_default_instance_; +class Debug_DebugMessageDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; + ::google::protobuf::internal::ArenaStringPtr trace_; + ::google::protobuf::internal::ArenaStringPtr info_; + ::google::protobuf::internal::ArenaStringPtr warn_; + ::google::protobuf::internal::ArenaStringPtr error_; + ::google::protobuf::internal::ArenaStringPtr fatal_; +} _Debug_DebugMessage_default_instance_; +class DebugDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Debug_default_instance_; +class PlanningDataDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _PlanningData_default_instance_; +} // namespace planning_internal +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto { +static void InitDefaultsPlanningObstacle() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::planning_internal::_PlanningObstacle_default_instance_; + new (ptr) ::apollo::planning_internal::PlanningObstacle(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::planning_internal::PlanningObstacle::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<3> scc_info_PlanningObstacle = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 3, InitDefaultsPlanningObstacle}, { + &protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::scc_info_Point.base, + &protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::scc_info_Trajectory.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_ObjectDecisionType.base,}}; + +static void InitDefaultsDebug_DebugMessage() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::planning_internal::_Debug_DebugMessage_default_instance_; + new (ptr) ::apollo::planning_internal::Debug_DebugMessage(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::planning_internal::Debug_DebugMessage::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_Debug_DebugMessage = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsDebug_DebugMessage}, {}}; + +static void InitDefaultsDebug() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::planning_internal::_Debug_default_instance_; + new (ptr) ::apollo::planning_internal::Debug(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::planning_internal::Debug::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_Debug = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsDebug}, { + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::scc_info_PlanningData.base, + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::scc_info_Debug_DebugMessage.base,}}; + +static void InitDefaultsPlanningData() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::planning_internal::_PlanningData_default_instance_; + new (ptr) ::apollo::planning_internal::PlanningData(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::planning_internal::PlanningData::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<5> scc_info_PlanningData = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 5, InitDefaultsPlanningData}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base, + &protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::scc_info_Pose.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_MainDecision.base, + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::scc_info_PlanningObstacle.base, + &protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::scc_info_LightSignal.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_PlanningObstacle.base); + ::google::protobuf::internal::InitSCC(&scc_info_Debug_DebugMessage.base); + ::google::protobuf::internal::InitSCC(&scc_info_Debug.base); + ::google::protobuf::internal::InitSCC(&scc_info_PlanningData.base); +} + +::google::protobuf::Metadata file_level_metadata[4]; +const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[1]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, perception_id_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, decision_id_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, position_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, theta_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, velocity_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, speed_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, length_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, width_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, height_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, polygon_point_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, tracking_time_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, perception_timestamp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, perception_object_type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, prediction_timestamp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, prediction_trajectory_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, decision_object_type_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, object_decision_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningObstacle, planning_object_decision_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::Debug_DebugMessage, _internal_metadata_), + ~0u, // no _extensions_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::Debug_DebugMessage, _oneof_case_[0]), + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::Debug_DebugMessage, error_code_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::Debug_DebugMessage, id_), + offsetof(::apollo::planning_internal::Debug_DebugMessageDefaultTypeInternal, trace_), + offsetof(::apollo::planning_internal::Debug_DebugMessageDefaultTypeInternal, info_), + offsetof(::apollo::planning_internal::Debug_DebugMessageDefaultTypeInternal, warn_), + offsetof(::apollo::planning_internal::Debug_DebugMessageDefaultTypeInternal, error_), + offsetof(::apollo::planning_internal::Debug_DebugMessageDefaultTypeInternal, fatal_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::Debug_DebugMessage, debug_string_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::Debug, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::Debug, error_code_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::Debug, planning_data_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::Debug, debug_message_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningData, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningData, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningData, init_status_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningData, main_decision_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningData, planning_obstacle_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::planning_internal::PlanningData, light_signal_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::planning_internal::PlanningObstacle)}, + { 23, -1, sizeof(::apollo::planning_internal::Debug_DebugMessage)}, + { 36, -1, sizeof(::apollo::planning_internal::Debug)}, + { 44, -1, sizeof(::apollo::planning_internal::PlanningData)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::planning_internal::_PlanningObstacle_default_instance_), + reinterpret_cast(&::apollo::planning_internal::_Debug_DebugMessage_default_instance_), + reinterpret_cast(&::apollo::planning_internal::_Debug_default_instance_), + reinterpret_cast(&::apollo::planning_internal::_PlanningData_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/planning/planning_internal.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, file_level_enum_descriptors, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 4); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n2apollo_msgs/proto/planning/planning_in" + "ternal.proto\022\030apollo.planning_internal\032%" + "apollo_msgs/proto/common/header.proto\032)a" + "pollo_msgs/proto/decision/decision.proto" + "\0321apollo_msgs/proto/localization/localiz" + "ation.proto\032)apollo_msgs/proto/localizat" + "ion/pose.proto\0326apollo_msgs/proto/percep" + "tion/perception_obstacle.proto\0326apollo_m" + "sgs/proto/prediction/prediction_obstacle" + ".proto\"\300\005\n\020PlanningObstacle\022\025\n\rperceptio" + "n_id\030\001 \001(\005\022\023\n\013decision_id\030\002 \001(\t\022*\n\010posit" + "ion\030\003 \001(\0132\030.apollo.perception.Point\022\r\n\005t" + "heta\030\004 \001(\001\022*\n\010velocity\030\005 \001(\0132\030.apollo.pe" + "rception.Point\022\r\n\005speed\030\006 \001(\001\022\016\n\006length\030" + "\007 \001(\001\022\r\n\005width\030\010 \001(\001\022\016\n\006height\030\t \001(\001\022/\n\r" + "polygon_point\030\n \003(\0132\030.apollo.perception." + "Point\022\025\n\rtracking_time\030\013 \001(\001\022\034\n\024percepti" + "on_timestamp\030\014 \001(\001\022J\n\026perception_object_" + "type\030\r \001(\0162*.apollo.perception.Perceptio" + "nObstacle.Type\022\034\n\024prediction_timestamp\030\016" + " \001(\001\022<\n\025prediction_trajectory\030\017 \003(\0132\035.ap" + "ollo.prediction.Trajectory\022H\n\024decision_o" + "bject_type\030\020 \001(\0162*.apollo.decision.Objec" + "tDecision.ObjectType\022<\n\017object_decision\030" + "\021 \001(\0132#.apollo.decision.ObjectDecisionTy" + "pe\022E\n\030planning_object_decision\030\022 \003(\0132#.a" + "pollo.decision.ObjectDecisionType\"\232\004\n\005De" + "bug\022=\n\nerror_code\030\001 \001(\0162).apollo.plannin" + "g_internal.Debug.ErrorCode\022=\n\rplanning_d" + "ata\030\002 \001(\0132&.apollo.planning_internal.Pla" + "nningData\022C\n\rdebug_message\030\003 \003(\0132,.apoll" + "o.planning_internal.Debug.DebugMessage\032\274" + "\001\n\014DebugMessage\022=\n\nerror_code\030\001 \001(\0162).ap" + "ollo.planning_internal.Debug.ErrorCode\022\n" + "\n\002id\030\002 \001(\005\022\017\n\005trace\030\003 \001(\tH\000\022\016\n\004info\030\004 \001(" + "\tH\000\022\016\n\004warn\030\005 \001(\tH\000\022\017\n\005error\030\006 \001(\tH\000\022\017\n\005" + "fatal\030\007 \001(\tH\000B\016\n\014debug_string\"\216\001\n\tErrorC" + "ode\022\006\n\002OK\020\000\022\021\n\rERR_NOT_READY\020\001\022\r\n\tERR_ES" + "TOP\020\002\022\026\n\022ERR_PATH_OPTIMIZER\020\003\022\027\n\023ERR_SPE" + "ED_OPTIMIZER\020\004\022\020\n\014ERR_ST_GRAPH\020\005\022\024\n\020ERR_" + "SANITY_CHECK\020\006\"\226\002\n\014PlanningData\022%\n\006heade" + "r\030\001 \001(\0132\025.apollo.common.Header\022.\n\013init_s" + "tatus\030\002 \001(\0132\031.apollo.localization.Pose\0224" + "\n\rmain_decision\030\003 \001(\0132\035.apollo.decision." + "MainDecision\022E\n\021planning_obstacle\030\004 \003(\0132" + "*.apollo.planning_internal.PlanningObsta" + "cle\0222\n\014light_signal\030\005 \001(\0132\034.apollo.decis" + "ion.LightSignalb\006proto3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 1903); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/planning/planning_internal.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fdecision_2fdecision_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2flocalization_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2flocalization_2fpose_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto +namespace apollo { +namespace planning_internal { +const ::google::protobuf::EnumDescriptor* Debug_ErrorCode_descriptor() { + protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::protobuf_AssignDescriptorsOnce(); + return protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::file_level_enum_descriptors[0]; +} +bool Debug_ErrorCode_IsValid(int value) { + switch (value) { + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + case 6: + return true; + default: + return false; + } +} + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const Debug_ErrorCode Debug::OK; +const Debug_ErrorCode Debug::ERR_NOT_READY; +const Debug_ErrorCode Debug::ERR_ESTOP; +const Debug_ErrorCode Debug::ERR_PATH_OPTIMIZER; +const Debug_ErrorCode Debug::ERR_SPEED_OPTIMIZER; +const Debug_ErrorCode Debug::ERR_ST_GRAPH; +const Debug_ErrorCode Debug::ERR_SANITY_CHECK; +const Debug_ErrorCode Debug::ErrorCode_MIN; +const Debug_ErrorCode Debug::ErrorCode_MAX; +const int Debug::ErrorCode_ARRAYSIZE; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +// =================================================================== + +void PlanningObstacle::InitAsDefaultInstance() { + ::apollo::planning_internal::_PlanningObstacle_default_instance_._instance.get_mutable()->position_ = const_cast< ::apollo::perception::Point*>( + ::apollo::perception::Point::internal_default_instance()); + ::apollo::planning_internal::_PlanningObstacle_default_instance_._instance.get_mutable()->velocity_ = const_cast< ::apollo::perception::Point*>( + ::apollo::perception::Point::internal_default_instance()); + ::apollo::planning_internal::_PlanningObstacle_default_instance_._instance.get_mutable()->object_decision_ = const_cast< ::apollo::decision::ObjectDecisionType*>( + ::apollo::decision::ObjectDecisionType::internal_default_instance()); +} +void PlanningObstacle::clear_position() { + if (GetArenaNoVirtual() == NULL && position_ != NULL) { + delete position_; + } + position_ = NULL; +} +void PlanningObstacle::clear_velocity() { + if (GetArenaNoVirtual() == NULL && velocity_ != NULL) { + delete velocity_; + } + velocity_ = NULL; +} +void PlanningObstacle::clear_polygon_point() { + polygon_point_.Clear(); +} +void PlanningObstacle::clear_prediction_trajectory() { + prediction_trajectory_.Clear(); +} +void PlanningObstacle::clear_object_decision() { + if (GetArenaNoVirtual() == NULL && object_decision_ != NULL) { + delete object_decision_; + } + object_decision_ = NULL; +} +void PlanningObstacle::clear_planning_object_decision() { + planning_object_decision_.Clear(); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PlanningObstacle::kPerceptionIdFieldNumber; +const int PlanningObstacle::kDecisionIdFieldNumber; +const int PlanningObstacle::kPositionFieldNumber; +const int PlanningObstacle::kThetaFieldNumber; +const int PlanningObstacle::kVelocityFieldNumber; +const int PlanningObstacle::kSpeedFieldNumber; +const int PlanningObstacle::kLengthFieldNumber; +const int PlanningObstacle::kWidthFieldNumber; +const int PlanningObstacle::kHeightFieldNumber; +const int PlanningObstacle::kPolygonPointFieldNumber; +const int PlanningObstacle::kTrackingTimeFieldNumber; +const int PlanningObstacle::kPerceptionTimestampFieldNumber; +const int PlanningObstacle::kPerceptionObjectTypeFieldNumber; +const int PlanningObstacle::kPredictionTimestampFieldNumber; +const int PlanningObstacle::kPredictionTrajectoryFieldNumber; +const int PlanningObstacle::kDecisionObjectTypeFieldNumber; +const int PlanningObstacle::kObjectDecisionFieldNumber; +const int PlanningObstacle::kPlanningObjectDecisionFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PlanningObstacle::PlanningObstacle() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::scc_info_PlanningObstacle.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.planning_internal.PlanningObstacle) +} +PlanningObstacle::PlanningObstacle(const PlanningObstacle& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + polygon_point_(from.polygon_point_), + prediction_trajectory_(from.prediction_trajectory_), + planning_object_decision_(from.planning_object_decision_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + decision_id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.decision_id().size() > 0) { + decision_id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.decision_id_); + } + if (from.has_position()) { + position_ = new ::apollo::perception::Point(*from.position_); + } else { + position_ = NULL; + } + if (from.has_velocity()) { + velocity_ = new ::apollo::perception::Point(*from.velocity_); + } else { + velocity_ = NULL; + } + if (from.has_object_decision()) { + object_decision_ = new ::apollo::decision::ObjectDecisionType(*from.object_decision_); + } else { + object_decision_ = NULL; + } + ::memcpy(&theta_, &from.theta_, + static_cast(reinterpret_cast(&decision_object_type_) - + reinterpret_cast(&theta_)) + sizeof(decision_object_type_)); + // @@protoc_insertion_point(copy_constructor:apollo.planning_internal.PlanningObstacle) +} + +void PlanningObstacle::SharedCtor() { + decision_id_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::memset(&position_, 0, static_cast( + reinterpret_cast(&decision_object_type_) - + reinterpret_cast(&position_)) + sizeof(decision_object_type_)); +} + +PlanningObstacle::~PlanningObstacle() { + // @@protoc_insertion_point(destructor:apollo.planning_internal.PlanningObstacle) + SharedDtor(); +} + +void PlanningObstacle::SharedDtor() { + decision_id_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (this != internal_default_instance()) delete position_; + if (this != internal_default_instance()) delete velocity_; + if (this != internal_default_instance()) delete object_decision_; +} + +void PlanningObstacle::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* PlanningObstacle::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const PlanningObstacle& PlanningObstacle::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::scc_info_PlanningObstacle.base); + return *internal_default_instance(); +} + + +void PlanningObstacle::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.planning_internal.PlanningObstacle) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + polygon_point_.Clear(); + prediction_trajectory_.Clear(); + planning_object_decision_.Clear(); + decision_id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (GetArenaNoVirtual() == NULL && position_ != NULL) { + delete position_; + } + position_ = NULL; + if (GetArenaNoVirtual() == NULL && velocity_ != NULL) { + delete velocity_; + } + velocity_ = NULL; + if (GetArenaNoVirtual() == NULL && object_decision_ != NULL) { + delete object_decision_; + } + object_decision_ = NULL; + ::memset(&theta_, 0, static_cast( + reinterpret_cast(&decision_object_type_) - + reinterpret_cast(&theta_)) + sizeof(decision_object_type_)); + _internal_metadata_.Clear(); +} + +bool PlanningObstacle::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.planning_internal.PlanningObstacle) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(16383u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // int32 perception_id = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &perception_id_))); + } else { + goto handle_unusual; + } + break; + } + + // string decision_id = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_decision_id())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->decision_id().data(), static_cast(this->decision_id().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.planning_internal.PlanningObstacle.decision_id")); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.perception.Point position = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_position())); + } else { + goto handle_unusual; + } + break; + } + + // double theta = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &theta_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.perception.Point velocity = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_velocity())); + } else { + goto handle_unusual; + } + break; + } + + // double speed = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &speed_))); + } else { + goto handle_unusual; + } + break; + } + + // double length = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(57u /* 57 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &length_))); + } else { + goto handle_unusual; + } + break; + } + + // double width = 8; + case 8: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(65u /* 65 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &width_))); + } else { + goto handle_unusual; + } + break; + } + + // double height = 9; + case 9: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(73u /* 73 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &height_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.perception.Point polygon_point = 10; + case 10: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(82u /* 82 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_polygon_point())); + } else { + goto handle_unusual; + } + break; + } + + // double tracking_time = 11; + case 11: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(89u /* 89 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &tracking_time_))); + } else { + goto handle_unusual; + } + break; + } + + // double perception_timestamp = 12; + case 12: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(97u /* 97 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &perception_timestamp_))); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.perception.PerceptionObstacle.Type perception_object_type = 13; + case 13: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(104u /* 104 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_perception_object_type(static_cast< ::apollo::perception::PerceptionObstacle_Type >(value)); + } else { + goto handle_unusual; + } + break; + } + + // double prediction_timestamp = 14; + case 14: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(113u /* 113 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &prediction_timestamp_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.prediction.Trajectory prediction_trajectory = 15; + case 15: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(122u /* 122 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_prediction_trajectory())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectDecision.ObjectType decision_object_type = 16; + case 16: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(128u /* 128 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_decision_object_type(static_cast< ::apollo::decision::ObjectDecision_ObjectType >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.ObjectDecisionType object_decision = 17; + case 17: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(138u /* 138 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_object_decision())); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.decision.ObjectDecisionType planning_object_decision = 18; + case 18: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(146u /* 146 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_planning_object_decision())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.planning_internal.PlanningObstacle) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.planning_internal.PlanningObstacle) + return false; +#undef DO_ +} + +void PlanningObstacle::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.planning_internal.PlanningObstacle) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // int32 perception_id = 1; + if (this->perception_id() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->perception_id(), output); + } + + // string decision_id = 2; + if (this->decision_id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->decision_id().data(), static_cast(this->decision_id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.planning_internal.PlanningObstacle.decision_id"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 2, this->decision_id(), output); + } + + // .apollo.perception.Point position = 3; + if (this->has_position()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_position(), output); + } + + // double theta = 4; + if (this->theta() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->theta(), output); + } + + // .apollo.perception.Point velocity = 5; + if (this->has_velocity()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, this->_internal_velocity(), output); + } + + // double speed = 6; + if (this->speed() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->speed(), output); + } + + // double length = 7; + if (this->length() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(7, this->length(), output); + } + + // double width = 8; + if (this->width() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(8, this->width(), output); + } + + // double height = 9; + if (this->height() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(9, this->height(), output); + } + + // repeated .apollo.perception.Point polygon_point = 10; + for (unsigned int i = 0, + n = static_cast(this->polygon_point_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 10, + this->polygon_point(static_cast(i)), + output); + } + + // double tracking_time = 11; + if (this->tracking_time() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(11, this->tracking_time(), output); + } + + // double perception_timestamp = 12; + if (this->perception_timestamp() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(12, this->perception_timestamp(), output); + } + + // .apollo.perception.PerceptionObstacle.Type perception_object_type = 13; + if (this->perception_object_type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 13, this->perception_object_type(), output); + } + + // double prediction_timestamp = 14; + if (this->prediction_timestamp() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(14, this->prediction_timestamp(), output); + } + + // repeated .apollo.prediction.Trajectory prediction_trajectory = 15; + for (unsigned int i = 0, + n = static_cast(this->prediction_trajectory_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 15, + this->prediction_trajectory(static_cast(i)), + output); + } + + // .apollo.decision.ObjectDecision.ObjectType decision_object_type = 16; + if (this->decision_object_type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 16, this->decision_object_type(), output); + } + + // .apollo.decision.ObjectDecisionType object_decision = 17; + if (this->has_object_decision()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 17, this->_internal_object_decision(), output); + } + + // repeated .apollo.decision.ObjectDecisionType planning_object_decision = 18; + for (unsigned int i = 0, + n = static_cast(this->planning_object_decision_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 18, + this->planning_object_decision(static_cast(i)), + output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.planning_internal.PlanningObstacle) +} + +::google::protobuf::uint8* PlanningObstacle::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.planning_internal.PlanningObstacle) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // int32 perception_id = 1; + if (this->perception_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->perception_id(), target); + } + + // string decision_id = 2; + if (this->decision_id().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->decision_id().data(), static_cast(this->decision_id().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.planning_internal.PlanningObstacle.decision_id"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 2, this->decision_id(), target); + } + + // .apollo.perception.Point position = 3; + if (this->has_position()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_position(), deterministic, target); + } + + // double theta = 4; + if (this->theta() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->theta(), target); + } + + // .apollo.perception.Point velocity = 5; + if (this->has_velocity()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 5, this->_internal_velocity(), deterministic, target); + } + + // double speed = 6; + if (this->speed() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->speed(), target); + } + + // double length = 7; + if (this->length() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(7, this->length(), target); + } + + // double width = 8; + if (this->width() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(8, this->width(), target); + } + + // double height = 9; + if (this->height() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(9, this->height(), target); + } + + // repeated .apollo.perception.Point polygon_point = 10; + for (unsigned int i = 0, + n = static_cast(this->polygon_point_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 10, this->polygon_point(static_cast(i)), deterministic, target); + } + + // double tracking_time = 11; + if (this->tracking_time() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(11, this->tracking_time(), target); + } + + // double perception_timestamp = 12; + if (this->perception_timestamp() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(12, this->perception_timestamp(), target); + } + + // .apollo.perception.PerceptionObstacle.Type perception_object_type = 13; + if (this->perception_object_type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 13, this->perception_object_type(), target); + } + + // double prediction_timestamp = 14; + if (this->prediction_timestamp() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(14, this->prediction_timestamp(), target); + } + + // repeated .apollo.prediction.Trajectory prediction_trajectory = 15; + for (unsigned int i = 0, + n = static_cast(this->prediction_trajectory_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 15, this->prediction_trajectory(static_cast(i)), deterministic, target); + } + + // .apollo.decision.ObjectDecision.ObjectType decision_object_type = 16; + if (this->decision_object_type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 16, this->decision_object_type(), target); + } + + // .apollo.decision.ObjectDecisionType object_decision = 17; + if (this->has_object_decision()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 17, this->_internal_object_decision(), deterministic, target); + } + + // repeated .apollo.decision.ObjectDecisionType planning_object_decision = 18; + for (unsigned int i = 0, + n = static_cast(this->planning_object_decision_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 18, this->planning_object_decision(static_cast(i)), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.planning_internal.PlanningObstacle) + return target; +} + +size_t PlanningObstacle::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.planning_internal.PlanningObstacle) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.perception.Point polygon_point = 10; + { + unsigned int count = static_cast(this->polygon_point_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->polygon_point(static_cast(i))); + } + } + + // repeated .apollo.prediction.Trajectory prediction_trajectory = 15; + { + unsigned int count = static_cast(this->prediction_trajectory_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->prediction_trajectory(static_cast(i))); + } + } + + // repeated .apollo.decision.ObjectDecisionType planning_object_decision = 18; + { + unsigned int count = static_cast(this->planning_object_decision_size()); + total_size += 2UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->planning_object_decision(static_cast(i))); + } + } + + // string decision_id = 2; + if (this->decision_id().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->decision_id()); + } + + // .apollo.perception.Point position = 3; + if (this->has_position()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *position_); + } + + // .apollo.perception.Point velocity = 5; + if (this->has_velocity()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *velocity_); + } + + // .apollo.decision.ObjectDecisionType object_decision = 17; + if (this->has_object_decision()) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *object_decision_); + } + + // double theta = 4; + if (this->theta() != 0) { + total_size += 1 + 8; + } + + // double speed = 6; + if (this->speed() != 0) { + total_size += 1 + 8; + } + + // double length = 7; + if (this->length() != 0) { + total_size += 1 + 8; + } + + // int32 perception_id = 1; + if (this->perception_id() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->perception_id()); + } + + // .apollo.perception.PerceptionObstacle.Type perception_object_type = 13; + if (this->perception_object_type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->perception_object_type()); + } + + // double width = 8; + if (this->width() != 0) { + total_size += 1 + 8; + } + + // double height = 9; + if (this->height() != 0) { + total_size += 1 + 8; + } + + // double tracking_time = 11; + if (this->tracking_time() != 0) { + total_size += 1 + 8; + } + + // double perception_timestamp = 12; + if (this->perception_timestamp() != 0) { + total_size += 1 + 8; + } + + // double prediction_timestamp = 14; + if (this->prediction_timestamp() != 0) { + total_size += 1 + 8; + } + + // .apollo.decision.ObjectDecision.ObjectType decision_object_type = 16; + if (this->decision_object_type() != 0) { + total_size += 2 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->decision_object_type()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void PlanningObstacle::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.planning_internal.PlanningObstacle) + GOOGLE_DCHECK_NE(&from, this); + const PlanningObstacle* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.planning_internal.PlanningObstacle) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.planning_internal.PlanningObstacle) + MergeFrom(*source); + } +} + +void PlanningObstacle::MergeFrom(const PlanningObstacle& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.planning_internal.PlanningObstacle) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + polygon_point_.MergeFrom(from.polygon_point_); + prediction_trajectory_.MergeFrom(from.prediction_trajectory_); + planning_object_decision_.MergeFrom(from.planning_object_decision_); + if (from.decision_id().size() > 0) { + + decision_id_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.decision_id_); + } + if (from.has_position()) { + mutable_position()->::apollo::perception::Point::MergeFrom(from.position()); + } + if (from.has_velocity()) { + mutable_velocity()->::apollo::perception::Point::MergeFrom(from.velocity()); + } + if (from.has_object_decision()) { + mutable_object_decision()->::apollo::decision::ObjectDecisionType::MergeFrom(from.object_decision()); + } + if (from.theta() != 0) { + set_theta(from.theta()); + } + if (from.speed() != 0) { + set_speed(from.speed()); + } + if (from.length() != 0) { + set_length(from.length()); + } + if (from.perception_id() != 0) { + set_perception_id(from.perception_id()); + } + if (from.perception_object_type() != 0) { + set_perception_object_type(from.perception_object_type()); + } + if (from.width() != 0) { + set_width(from.width()); + } + if (from.height() != 0) { + set_height(from.height()); + } + if (from.tracking_time() != 0) { + set_tracking_time(from.tracking_time()); + } + if (from.perception_timestamp() != 0) { + set_perception_timestamp(from.perception_timestamp()); + } + if (from.prediction_timestamp() != 0) { + set_prediction_timestamp(from.prediction_timestamp()); + } + if (from.decision_object_type() != 0) { + set_decision_object_type(from.decision_object_type()); + } +} + +void PlanningObstacle::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.planning_internal.PlanningObstacle) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PlanningObstacle::CopyFrom(const PlanningObstacle& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.planning_internal.PlanningObstacle) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PlanningObstacle::IsInitialized() const { + return true; +} + +void PlanningObstacle::Swap(PlanningObstacle* other) { + if (other == this) return; + InternalSwap(other); +} +void PlanningObstacle::InternalSwap(PlanningObstacle* other) { + using std::swap; + CastToBase(&polygon_point_)->InternalSwap(CastToBase(&other->polygon_point_)); + CastToBase(&prediction_trajectory_)->InternalSwap(CastToBase(&other->prediction_trajectory_)); + CastToBase(&planning_object_decision_)->InternalSwap(CastToBase(&other->planning_object_decision_)); + decision_id_.Swap(&other->decision_id_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(position_, other->position_); + swap(velocity_, other->velocity_); + swap(object_decision_, other->object_decision_); + swap(theta_, other->theta_); + swap(speed_, other->speed_); + swap(length_, other->length_); + swap(perception_id_, other->perception_id_); + swap(perception_object_type_, other->perception_object_type_); + swap(width_, other->width_); + swap(height_, other->height_); + swap(tracking_time_, other->tracking_time_); + swap(perception_timestamp_, other->perception_timestamp_); + swap(prediction_timestamp_, other->prediction_timestamp_); + swap(decision_object_type_, other->decision_object_type_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata PlanningObstacle::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Debug_DebugMessage::InitAsDefaultInstance() { + ::apollo::planning_internal::_Debug_DebugMessage_default_instance_.trace_.UnsafeSetDefault( + &::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::apollo::planning_internal::_Debug_DebugMessage_default_instance_.info_.UnsafeSetDefault( + &::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::apollo::planning_internal::_Debug_DebugMessage_default_instance_.warn_.UnsafeSetDefault( + &::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::apollo::planning_internal::_Debug_DebugMessage_default_instance_.error_.UnsafeSetDefault( + &::google::protobuf::internal::GetEmptyStringAlreadyInited()); + ::apollo::planning_internal::_Debug_DebugMessage_default_instance_.fatal_.UnsafeSetDefault( + &::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Debug_DebugMessage::kErrorCodeFieldNumber; +const int Debug_DebugMessage::kIdFieldNumber; +const int Debug_DebugMessage::kTraceFieldNumber; +const int Debug_DebugMessage::kInfoFieldNumber; +const int Debug_DebugMessage::kWarnFieldNumber; +const int Debug_DebugMessage::kErrorFieldNumber; +const int Debug_DebugMessage::kFatalFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Debug_DebugMessage::Debug_DebugMessage() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::scc_info_Debug_DebugMessage.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.planning_internal.Debug.DebugMessage) +} +Debug_DebugMessage::Debug_DebugMessage(const Debug_DebugMessage& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&error_code_, &from.error_code_, + static_cast(reinterpret_cast(&id_) - + reinterpret_cast(&error_code_)) + sizeof(id_)); + clear_has_debug_string(); + switch (from.debug_string_case()) { + case kTrace: { + set_trace(from.trace()); + break; + } + case kInfo: { + set_info(from.info()); + break; + } + case kWarn: { + set_warn(from.warn()); + break; + } + case kError: { + set_error(from.error()); + break; + } + case kFatal: { + set_fatal(from.fatal()); + break; + } + case DEBUG_STRING_NOT_SET: { + break; + } + } + // @@protoc_insertion_point(copy_constructor:apollo.planning_internal.Debug.DebugMessage) +} + +void Debug_DebugMessage::SharedCtor() { + ::memset(&error_code_, 0, static_cast( + reinterpret_cast(&id_) - + reinterpret_cast(&error_code_)) + sizeof(id_)); + clear_has_debug_string(); +} + +Debug_DebugMessage::~Debug_DebugMessage() { + // @@protoc_insertion_point(destructor:apollo.planning_internal.Debug.DebugMessage) + SharedDtor(); +} + +void Debug_DebugMessage::SharedDtor() { + if (has_debug_string()) { + clear_debug_string(); + } +} + +void Debug_DebugMessage::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Debug_DebugMessage::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Debug_DebugMessage& Debug_DebugMessage::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::scc_info_Debug_DebugMessage.base); + return *internal_default_instance(); +} + + +void Debug_DebugMessage::clear_debug_string() { +// @@protoc_insertion_point(one_of_clear_start:apollo.planning_internal.Debug.DebugMessage) + switch (debug_string_case()) { + case kTrace: { + debug_string_.trace_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + break; + } + case kInfo: { + debug_string_.info_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + break; + } + case kWarn: { + debug_string_.warn_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + break; + } + case kError: { + debug_string_.error_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + break; + } + case kFatal: { + debug_string_.fatal_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + break; + } + case DEBUG_STRING_NOT_SET: { + break; + } + } + _oneof_case_[0] = DEBUG_STRING_NOT_SET; +} + + +void Debug_DebugMessage::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.planning_internal.Debug.DebugMessage) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&error_code_, 0, static_cast( + reinterpret_cast(&id_) - + reinterpret_cast(&error_code_)) + sizeof(id_)); + clear_debug_string(); + _internal_metadata_.Clear(); +} + +bool Debug_DebugMessage::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.planning_internal.Debug.DebugMessage) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.planning_internal.Debug.ErrorCode error_code = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_error_code(static_cast< ::apollo::planning_internal::Debug_ErrorCode >(value)); + } else { + goto handle_unusual; + } + break; + } + + // int32 id = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(16u /* 16 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &id_))); + } else { + goto handle_unusual; + } + break; + } + + // string trace = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_trace())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->trace().data(), static_cast(this->trace().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.planning_internal.Debug.DebugMessage.trace")); + } else { + goto handle_unusual; + } + break; + } + + // string info = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_info())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->info().data(), static_cast(this->info().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.planning_internal.Debug.DebugMessage.info")); + } else { + goto handle_unusual; + } + break; + } + + // string warn = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_warn())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->warn().data(), static_cast(this->warn().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.planning_internal.Debug.DebugMessage.warn")); + } else { + goto handle_unusual; + } + break; + } + + // string error = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(50u /* 50 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_error())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->error().data(), static_cast(this->error().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.planning_internal.Debug.DebugMessage.error")); + } else { + goto handle_unusual; + } + break; + } + + // string fatal = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(58u /* 58 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_fatal())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->fatal().data(), static_cast(this->fatal().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "apollo.planning_internal.Debug.DebugMessage.fatal")); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.planning_internal.Debug.DebugMessage) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.planning_internal.Debug.DebugMessage) + return false; +#undef DO_ +} + +void Debug_DebugMessage::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.planning_internal.Debug.DebugMessage) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.planning_internal.Debug.ErrorCode error_code = 1; + if (this->error_code() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->error_code(), output); + } + + // int32 id = 2; + if (this->id() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->id(), output); + } + + // string trace = 3; + if (has_trace()) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->trace().data(), static_cast(this->trace().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.planning_internal.Debug.DebugMessage.trace"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 3, this->trace(), output); + } + + // string info = 4; + if (has_info()) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->info().data(), static_cast(this->info().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.planning_internal.Debug.DebugMessage.info"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 4, this->info(), output); + } + + // string warn = 5; + if (has_warn()) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->warn().data(), static_cast(this->warn().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.planning_internal.Debug.DebugMessage.warn"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 5, this->warn(), output); + } + + // string error = 6; + if (has_error()) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->error().data(), static_cast(this->error().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.planning_internal.Debug.DebugMessage.error"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 6, this->error(), output); + } + + // string fatal = 7; + if (has_fatal()) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->fatal().data(), static_cast(this->fatal().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.planning_internal.Debug.DebugMessage.fatal"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 7, this->fatal(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.planning_internal.Debug.DebugMessage) +} + +::google::protobuf::uint8* Debug_DebugMessage::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.planning_internal.Debug.DebugMessage) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.planning_internal.Debug.ErrorCode error_code = 1; + if (this->error_code() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->error_code(), target); + } + + // int32 id = 2; + if (this->id() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->id(), target); + } + + // string trace = 3; + if (has_trace()) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->trace().data(), static_cast(this->trace().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.planning_internal.Debug.DebugMessage.trace"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 3, this->trace(), target); + } + + // string info = 4; + if (has_info()) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->info().data(), static_cast(this->info().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.planning_internal.Debug.DebugMessage.info"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 4, this->info(), target); + } + + // string warn = 5; + if (has_warn()) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->warn().data(), static_cast(this->warn().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.planning_internal.Debug.DebugMessage.warn"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 5, this->warn(), target); + } + + // string error = 6; + if (has_error()) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->error().data(), static_cast(this->error().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.planning_internal.Debug.DebugMessage.error"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 6, this->error(), target); + } + + // string fatal = 7; + if (has_fatal()) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->fatal().data(), static_cast(this->fatal().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "apollo.planning_internal.Debug.DebugMessage.fatal"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 7, this->fatal(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.planning_internal.Debug.DebugMessage) + return target; +} + +size_t Debug_DebugMessage::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.planning_internal.Debug.DebugMessage) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // .apollo.planning_internal.Debug.ErrorCode error_code = 1; + if (this->error_code() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->error_code()); + } + + // int32 id = 2; + if (this->id() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->id()); + } + + switch (debug_string_case()) { + // string trace = 3; + case kTrace: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->trace()); + break; + } + // string info = 4; + case kInfo: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->info()); + break; + } + // string warn = 5; + case kWarn: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->warn()); + break; + } + // string error = 6; + case kError: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->error()); + break; + } + // string fatal = 7; + case kFatal: { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->fatal()); + break; + } + case DEBUG_STRING_NOT_SET: { + break; + } + } + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Debug_DebugMessage::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.planning_internal.Debug.DebugMessage) + GOOGLE_DCHECK_NE(&from, this); + const Debug_DebugMessage* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.planning_internal.Debug.DebugMessage) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.planning_internal.Debug.DebugMessage) + MergeFrom(*source); + } +} + +void Debug_DebugMessage::MergeFrom(const Debug_DebugMessage& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.planning_internal.Debug.DebugMessage) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.error_code() != 0) { + set_error_code(from.error_code()); + } + if (from.id() != 0) { + set_id(from.id()); + } + switch (from.debug_string_case()) { + case kTrace: { + set_trace(from.trace()); + break; + } + case kInfo: { + set_info(from.info()); + break; + } + case kWarn: { + set_warn(from.warn()); + break; + } + case kError: { + set_error(from.error()); + break; + } + case kFatal: { + set_fatal(from.fatal()); + break; + } + case DEBUG_STRING_NOT_SET: { + break; + } + } +} + +void Debug_DebugMessage::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.planning_internal.Debug.DebugMessage) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Debug_DebugMessage::CopyFrom(const Debug_DebugMessage& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.planning_internal.Debug.DebugMessage) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Debug_DebugMessage::IsInitialized() const { + return true; +} + +void Debug_DebugMessage::Swap(Debug_DebugMessage* other) { + if (other == this) return; + InternalSwap(other); +} +void Debug_DebugMessage::InternalSwap(Debug_DebugMessage* other) { + using std::swap; + swap(error_code_, other->error_code_); + swap(id_, other->id_); + swap(debug_string_, other->debug_string_); + swap(_oneof_case_[0], other->_oneof_case_[0]); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Debug_DebugMessage::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Debug::InitAsDefaultInstance() { + ::apollo::planning_internal::_Debug_default_instance_._instance.get_mutable()->planning_data_ = const_cast< ::apollo::planning_internal::PlanningData*>( + ::apollo::planning_internal::PlanningData::internal_default_instance()); +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Debug::kErrorCodeFieldNumber; +const int Debug::kPlanningDataFieldNumber; +const int Debug::kDebugMessageFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Debug::Debug() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::scc_info_Debug.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.planning_internal.Debug) +} +Debug::Debug(const Debug& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + debug_message_(from.debug_message_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_planning_data()) { + planning_data_ = new ::apollo::planning_internal::PlanningData(*from.planning_data_); + } else { + planning_data_ = NULL; + } + error_code_ = from.error_code_; + // @@protoc_insertion_point(copy_constructor:apollo.planning_internal.Debug) +} + +void Debug::SharedCtor() { + ::memset(&planning_data_, 0, static_cast( + reinterpret_cast(&error_code_) - + reinterpret_cast(&planning_data_)) + sizeof(error_code_)); +} + +Debug::~Debug() { + // @@protoc_insertion_point(destructor:apollo.planning_internal.Debug) + SharedDtor(); +} + +void Debug::SharedDtor() { + if (this != internal_default_instance()) delete planning_data_; +} + +void Debug::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Debug::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Debug& Debug::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::scc_info_Debug.base); + return *internal_default_instance(); +} + + +void Debug::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.planning_internal.Debug) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + debug_message_.Clear(); + if (GetArenaNoVirtual() == NULL && planning_data_ != NULL) { + delete planning_data_; + } + planning_data_ = NULL; + error_code_ = 0; + _internal_metadata_.Clear(); +} + +bool Debug::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.planning_internal.Debug) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.planning_internal.Debug.ErrorCode error_code = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(8u /* 8 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_error_code(static_cast< ::apollo::planning_internal::Debug_ErrorCode >(value)); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.planning_internal.PlanningData planning_data = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_planning_data())); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.planning_internal.Debug.DebugMessage debug_message = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_debug_message())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.planning_internal.Debug) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.planning_internal.Debug) + return false; +#undef DO_ +} + +void Debug::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.planning_internal.Debug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.planning_internal.Debug.ErrorCode error_code = 1; + if (this->error_code() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->error_code(), output); + } + + // .apollo.planning_internal.PlanningData planning_data = 2; + if (this->has_planning_data()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_planning_data(), output); + } + + // repeated .apollo.planning_internal.Debug.DebugMessage debug_message = 3; + for (unsigned int i = 0, + n = static_cast(this->debug_message_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, + this->debug_message(static_cast(i)), + output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.planning_internal.Debug) +} + +::google::protobuf::uint8* Debug::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.planning_internal.Debug) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.planning_internal.Debug.ErrorCode error_code = 1; + if (this->error_code() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->error_code(), target); + } + + // .apollo.planning_internal.PlanningData planning_data = 2; + if (this->has_planning_data()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_planning_data(), deterministic, target); + } + + // repeated .apollo.planning_internal.Debug.DebugMessage debug_message = 3; + for (unsigned int i = 0, + n = static_cast(this->debug_message_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->debug_message(static_cast(i)), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.planning_internal.Debug) + return target; +} + +size_t Debug::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.planning_internal.Debug) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.planning_internal.Debug.DebugMessage debug_message = 3; + { + unsigned int count = static_cast(this->debug_message_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->debug_message(static_cast(i))); + } + } + + // .apollo.planning_internal.PlanningData planning_data = 2; + if (this->has_planning_data()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *planning_data_); + } + + // .apollo.planning_internal.Debug.ErrorCode error_code = 1; + if (this->error_code() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->error_code()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Debug::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.planning_internal.Debug) + GOOGLE_DCHECK_NE(&from, this); + const Debug* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.planning_internal.Debug) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.planning_internal.Debug) + MergeFrom(*source); + } +} + +void Debug::MergeFrom(const Debug& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.planning_internal.Debug) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + debug_message_.MergeFrom(from.debug_message_); + if (from.has_planning_data()) { + mutable_planning_data()->::apollo::planning_internal::PlanningData::MergeFrom(from.planning_data()); + } + if (from.error_code() != 0) { + set_error_code(from.error_code()); + } +} + +void Debug::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.planning_internal.Debug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Debug::CopyFrom(const Debug& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.planning_internal.Debug) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Debug::IsInitialized() const { + return true; +} + +void Debug::Swap(Debug* other) { + if (other == this) return; + InternalSwap(other); +} +void Debug::InternalSwap(Debug* other) { + using std::swap; + CastToBase(&debug_message_)->InternalSwap(CastToBase(&other->debug_message_)); + swap(planning_data_, other->planning_data_); + swap(error_code_, other->error_code_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Debug::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void PlanningData::InitAsDefaultInstance() { + ::apollo::planning_internal::_PlanningData_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); + ::apollo::planning_internal::_PlanningData_default_instance_._instance.get_mutable()->init_status_ = const_cast< ::apollo::localization::Pose*>( + ::apollo::localization::Pose::internal_default_instance()); + ::apollo::planning_internal::_PlanningData_default_instance_._instance.get_mutable()->main_decision_ = const_cast< ::apollo::decision::MainDecision*>( + ::apollo::decision::MainDecision::internal_default_instance()); + ::apollo::planning_internal::_PlanningData_default_instance_._instance.get_mutable()->light_signal_ = const_cast< ::apollo::decision::LightSignal*>( + ::apollo::decision::LightSignal::internal_default_instance()); +} +void PlanningData::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +void PlanningData::clear_init_status() { + if (GetArenaNoVirtual() == NULL && init_status_ != NULL) { + delete init_status_; + } + init_status_ = NULL; +} +void PlanningData::clear_main_decision() { + if (GetArenaNoVirtual() == NULL && main_decision_ != NULL) { + delete main_decision_; + } + main_decision_ = NULL; +} +void PlanningData::clear_light_signal() { + if (GetArenaNoVirtual() == NULL && light_signal_ != NULL) { + delete light_signal_; + } + light_signal_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PlanningData::kHeaderFieldNumber; +const int PlanningData::kInitStatusFieldNumber; +const int PlanningData::kMainDecisionFieldNumber; +const int PlanningData::kPlanningObstacleFieldNumber; +const int PlanningData::kLightSignalFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PlanningData::PlanningData() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::scc_info_PlanningData.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.planning_internal.PlanningData) +} +PlanningData::PlanningData(const PlanningData& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + planning_obstacle_(from.planning_obstacle_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + if (from.has_init_status()) { + init_status_ = new ::apollo::localization::Pose(*from.init_status_); + } else { + init_status_ = NULL; + } + if (from.has_main_decision()) { + main_decision_ = new ::apollo::decision::MainDecision(*from.main_decision_); + } else { + main_decision_ = NULL; + } + if (from.has_light_signal()) { + light_signal_ = new ::apollo::decision::LightSignal(*from.light_signal_); + } else { + light_signal_ = NULL; + } + // @@protoc_insertion_point(copy_constructor:apollo.planning_internal.PlanningData) +} + +void PlanningData::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&light_signal_) - + reinterpret_cast(&header_)) + sizeof(light_signal_)); +} + +PlanningData::~PlanningData() { + // @@protoc_insertion_point(destructor:apollo.planning_internal.PlanningData) + SharedDtor(); +} + +void PlanningData::SharedDtor() { + if (this != internal_default_instance()) delete header_; + if (this != internal_default_instance()) delete init_status_; + if (this != internal_default_instance()) delete main_decision_; + if (this != internal_default_instance()) delete light_signal_; +} + +void PlanningData::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* PlanningData::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const PlanningData& PlanningData::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::scc_info_PlanningData.base); + return *internal_default_instance(); +} + + +void PlanningData::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.planning_internal.PlanningData) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + planning_obstacle_.Clear(); + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + if (GetArenaNoVirtual() == NULL && init_status_ != NULL) { + delete init_status_; + } + init_status_ = NULL; + if (GetArenaNoVirtual() == NULL && main_decision_ != NULL) { + delete main_decision_; + } + main_decision_ = NULL; + if (GetArenaNoVirtual() == NULL && light_signal_ != NULL) { + delete light_signal_; + } + light_signal_ = NULL; + _internal_metadata_.Clear(); +} + +bool PlanningData::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.planning_internal.PlanningData) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.localization.Pose init_status = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_init_status())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.MainDecision main_decision = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(26u /* 26 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_main_decision())); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.planning_internal.PlanningObstacle planning_obstacle = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_planning_obstacle())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.decision.LightSignal light_signal = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(42u /* 42 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_light_signal())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.planning_internal.PlanningData) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.planning_internal.PlanningData) + return false; +#undef DO_ +} + +void PlanningData::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.planning_internal.PlanningData) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // .apollo.localization.Pose init_status = 2; + if (this->has_init_status()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, this->_internal_init_status(), output); + } + + // .apollo.decision.MainDecision main_decision = 3; + if (this->has_main_decision()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 3, this->_internal_main_decision(), output); + } + + // repeated .apollo.planning_internal.PlanningObstacle planning_obstacle = 4; + for (unsigned int i = 0, + n = static_cast(this->planning_obstacle_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, + this->planning_obstacle(static_cast(i)), + output); + } + + // .apollo.decision.LightSignal light_signal = 5; + if (this->has_light_signal()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 5, this->_internal_light_signal(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.planning_internal.PlanningData) +} + +::google::protobuf::uint8* PlanningData::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.planning_internal.PlanningData) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // .apollo.localization.Pose init_status = 2; + if (this->has_init_status()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->_internal_init_status(), deterministic, target); + } + + // .apollo.decision.MainDecision main_decision = 3; + if (this->has_main_decision()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 3, this->_internal_main_decision(), deterministic, target); + } + + // repeated .apollo.planning_internal.PlanningObstacle planning_obstacle = 4; + for (unsigned int i = 0, + n = static_cast(this->planning_obstacle_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->planning_obstacle(static_cast(i)), deterministic, target); + } + + // .apollo.decision.LightSignal light_signal = 5; + if (this->has_light_signal()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 5, this->_internal_light_signal(), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.planning_internal.PlanningData) + return target; +} + +size_t PlanningData::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.planning_internal.PlanningData) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.planning_internal.PlanningObstacle planning_obstacle = 4; + { + unsigned int count = static_cast(this->planning_obstacle_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->planning_obstacle(static_cast(i))); + } + } + + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.localization.Pose init_status = 2; + if (this->has_init_status()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *init_status_); + } + + // .apollo.decision.MainDecision main_decision = 3; + if (this->has_main_decision()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *main_decision_); + } + + // .apollo.decision.LightSignal light_signal = 5; + if (this->has_light_signal()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *light_signal_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void PlanningData::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.planning_internal.PlanningData) + GOOGLE_DCHECK_NE(&from, this); + const PlanningData* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.planning_internal.PlanningData) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.planning_internal.PlanningData) + MergeFrom(*source); + } +} + +void PlanningData::MergeFrom(const PlanningData& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.planning_internal.PlanningData) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + planning_obstacle_.MergeFrom(from.planning_obstacle_); + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.has_init_status()) { + mutable_init_status()->::apollo::localization::Pose::MergeFrom(from.init_status()); + } + if (from.has_main_decision()) { + mutable_main_decision()->::apollo::decision::MainDecision::MergeFrom(from.main_decision()); + } + if (from.has_light_signal()) { + mutable_light_signal()->::apollo::decision::LightSignal::MergeFrom(from.light_signal()); + } +} + +void PlanningData::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.planning_internal.PlanningData) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PlanningData::CopyFrom(const PlanningData& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.planning_internal.PlanningData) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PlanningData::IsInitialized() const { + return true; +} + +void PlanningData::Swap(PlanningData* other) { + if (other == this) return; + InternalSwap(other); +} +void PlanningData::InternalSwap(PlanningData* other) { + using std::swap; + CastToBase(&planning_obstacle_)->InternalSwap(CastToBase(&other->planning_obstacle_)); + swap(header_, other->header_); + swap(init_status_, other->init_status_); + swap(main_decision_, other->main_decision_); + swap(light_signal_, other->light_signal_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata PlanningData::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace planning_internal +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::planning_internal::PlanningObstacle* Arena::CreateMaybeMessage< ::apollo::planning_internal::PlanningObstacle >(Arena* arena) { + return Arena::CreateInternal< ::apollo::planning_internal::PlanningObstacle >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::planning_internal::Debug_DebugMessage* Arena::CreateMaybeMessage< ::apollo::planning_internal::Debug_DebugMessage >(Arena* arena) { + return Arena::CreateInternal< ::apollo::planning_internal::Debug_DebugMessage >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::planning_internal::Debug* Arena::CreateMaybeMessage< ::apollo::planning_internal::Debug >(Arena* arena) { + return Arena::CreateInternal< ::apollo::planning_internal::Debug >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::planning_internal::PlanningData* Arena::CreateMaybeMessage< ::apollo::planning_internal::PlanningData >(Arena* arena) { + return Arena::CreateInternal< ::apollo::planning_internal::PlanningData >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/planning/planning_internal.pb.h b/apollo_msgs/include/apollo_msgs/proto/planning/planning_internal.pb.h new file mode 100644 index 0000000..1c2f566 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/planning/planning_internal.pb.h @@ -0,0 +1,2232 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/planning/planning_internal.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include +#include "apollo_msgs/proto/common/header.pb.h" +#include "apollo_msgs/proto/decision/decision.pb.h" +#include "apollo_msgs/proto/localization/localization.pb.h" +#include "apollo_msgs/proto/localization/pose.pb.h" +#include "apollo_msgs/proto/perception/perception_obstacle.pb.h" +#include "apollo_msgs/proto/prediction/prediction_obstacle.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[4]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto +namespace apollo { +namespace planning_internal { +class Debug; +class DebugDefaultTypeInternal; +extern DebugDefaultTypeInternal _Debug_default_instance_; +class Debug_DebugMessage; +class Debug_DebugMessageDefaultTypeInternal; +extern Debug_DebugMessageDefaultTypeInternal _Debug_DebugMessage_default_instance_; +class PlanningData; +class PlanningDataDefaultTypeInternal; +extern PlanningDataDefaultTypeInternal _PlanningData_default_instance_; +class PlanningObstacle; +class PlanningObstacleDefaultTypeInternal; +extern PlanningObstacleDefaultTypeInternal _PlanningObstacle_default_instance_; +} // namespace planning_internal +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::planning_internal::Debug* Arena::CreateMaybeMessage<::apollo::planning_internal::Debug>(Arena*); +template<> ::apollo::planning_internal::Debug_DebugMessage* Arena::CreateMaybeMessage<::apollo::planning_internal::Debug_DebugMessage>(Arena*); +template<> ::apollo::planning_internal::PlanningData* Arena::CreateMaybeMessage<::apollo::planning_internal::PlanningData>(Arena*); +template<> ::apollo::planning_internal::PlanningObstacle* Arena::CreateMaybeMessage<::apollo::planning_internal::PlanningObstacle>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace planning_internal { + +enum Debug_ErrorCode { + Debug_ErrorCode_OK = 0, + Debug_ErrorCode_ERR_NOT_READY = 1, + Debug_ErrorCode_ERR_ESTOP = 2, + Debug_ErrorCode_ERR_PATH_OPTIMIZER = 3, + Debug_ErrorCode_ERR_SPEED_OPTIMIZER = 4, + Debug_ErrorCode_ERR_ST_GRAPH = 5, + Debug_ErrorCode_ERR_SANITY_CHECK = 6, + Debug_ErrorCode_Debug_ErrorCode_INT_MIN_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32min, + Debug_ErrorCode_Debug_ErrorCode_INT_MAX_SENTINEL_DO_NOT_USE_ = ::google::protobuf::kint32max +}; +bool Debug_ErrorCode_IsValid(int value); +const Debug_ErrorCode Debug_ErrorCode_ErrorCode_MIN = Debug_ErrorCode_OK; +const Debug_ErrorCode Debug_ErrorCode_ErrorCode_MAX = Debug_ErrorCode_ERR_SANITY_CHECK; +const int Debug_ErrorCode_ErrorCode_ARRAYSIZE = Debug_ErrorCode_ErrorCode_MAX + 1; + +const ::google::protobuf::EnumDescriptor* Debug_ErrorCode_descriptor(); +inline const ::std::string& Debug_ErrorCode_Name(Debug_ErrorCode value) { + return ::google::protobuf::internal::NameOfEnum( + Debug_ErrorCode_descriptor(), value); +} +inline bool Debug_ErrorCode_Parse( + const ::std::string& name, Debug_ErrorCode* value) { + return ::google::protobuf::internal::ParseNamedEnum( + Debug_ErrorCode_descriptor(), name, value); +} +// =================================================================== + +class PlanningObstacle : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.planning_internal.PlanningObstacle) */ { + public: + PlanningObstacle(); + virtual ~PlanningObstacle(); + + PlanningObstacle(const PlanningObstacle& from); + + inline PlanningObstacle& operator=(const PlanningObstacle& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + PlanningObstacle(PlanningObstacle&& from) noexcept + : PlanningObstacle() { + *this = ::std::move(from); + } + + inline PlanningObstacle& operator=(PlanningObstacle&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const PlanningObstacle& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const PlanningObstacle* internal_default_instance() { + return reinterpret_cast( + &_PlanningObstacle_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(PlanningObstacle* other); + friend void swap(PlanningObstacle& a, PlanningObstacle& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline PlanningObstacle* New() const final { + return CreateMaybeMessage(NULL); + } + + PlanningObstacle* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const PlanningObstacle& from); + void MergeFrom(const PlanningObstacle& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(PlanningObstacle* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.perception.Point polygon_point = 10; + int polygon_point_size() const; + void clear_polygon_point(); + static const int kPolygonPointFieldNumber = 10; + ::apollo::perception::Point* mutable_polygon_point(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::perception::Point >* + mutable_polygon_point(); + const ::apollo::perception::Point& polygon_point(int index) const; + ::apollo::perception::Point* add_polygon_point(); + const ::google::protobuf::RepeatedPtrField< ::apollo::perception::Point >& + polygon_point() const; + + // repeated .apollo.prediction.Trajectory prediction_trajectory = 15; + int prediction_trajectory_size() const; + void clear_prediction_trajectory(); + static const int kPredictionTrajectoryFieldNumber = 15; + ::apollo::prediction::Trajectory* mutable_prediction_trajectory(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::prediction::Trajectory >* + mutable_prediction_trajectory(); + const ::apollo::prediction::Trajectory& prediction_trajectory(int index) const; + ::apollo::prediction::Trajectory* add_prediction_trajectory(); + const ::google::protobuf::RepeatedPtrField< ::apollo::prediction::Trajectory >& + prediction_trajectory() const; + + // repeated .apollo.decision.ObjectDecisionType planning_object_decision = 18; + int planning_object_decision_size() const; + void clear_planning_object_decision(); + static const int kPlanningObjectDecisionFieldNumber = 18; + ::apollo::decision::ObjectDecisionType* mutable_planning_object_decision(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecisionType >* + mutable_planning_object_decision(); + const ::apollo::decision::ObjectDecisionType& planning_object_decision(int index) const; + ::apollo::decision::ObjectDecisionType* add_planning_object_decision(); + const ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecisionType >& + planning_object_decision() const; + + // string decision_id = 2; + void clear_decision_id(); + static const int kDecisionIdFieldNumber = 2; + const ::std::string& decision_id() const; + void set_decision_id(const ::std::string& value); + #if LANG_CXX11 + void set_decision_id(::std::string&& value); + #endif + void set_decision_id(const char* value); + void set_decision_id(const char* value, size_t size); + ::std::string* mutable_decision_id(); + ::std::string* release_decision_id(); + void set_allocated_decision_id(::std::string* decision_id); + + // .apollo.perception.Point position = 3; + bool has_position() const; + void clear_position(); + static const int kPositionFieldNumber = 3; + private: + const ::apollo::perception::Point& _internal_position() const; + public: + const ::apollo::perception::Point& position() const; + ::apollo::perception::Point* release_position(); + ::apollo::perception::Point* mutable_position(); + void set_allocated_position(::apollo::perception::Point* position); + + // .apollo.perception.Point velocity = 5; + bool has_velocity() const; + void clear_velocity(); + static const int kVelocityFieldNumber = 5; + private: + const ::apollo::perception::Point& _internal_velocity() const; + public: + const ::apollo::perception::Point& velocity() const; + ::apollo::perception::Point* release_velocity(); + ::apollo::perception::Point* mutable_velocity(); + void set_allocated_velocity(::apollo::perception::Point* velocity); + + // .apollo.decision.ObjectDecisionType object_decision = 17; + bool has_object_decision() const; + void clear_object_decision(); + static const int kObjectDecisionFieldNumber = 17; + private: + const ::apollo::decision::ObjectDecisionType& _internal_object_decision() const; + public: + const ::apollo::decision::ObjectDecisionType& object_decision() const; + ::apollo::decision::ObjectDecisionType* release_object_decision(); + ::apollo::decision::ObjectDecisionType* mutable_object_decision(); + void set_allocated_object_decision(::apollo::decision::ObjectDecisionType* object_decision); + + // double theta = 4; + void clear_theta(); + static const int kThetaFieldNumber = 4; + double theta() const; + void set_theta(double value); + + // double speed = 6; + void clear_speed(); + static const int kSpeedFieldNumber = 6; + double speed() const; + void set_speed(double value); + + // double length = 7; + void clear_length(); + static const int kLengthFieldNumber = 7; + double length() const; + void set_length(double value); + + // int32 perception_id = 1; + void clear_perception_id(); + static const int kPerceptionIdFieldNumber = 1; + ::google::protobuf::int32 perception_id() const; + void set_perception_id(::google::protobuf::int32 value); + + // .apollo.perception.PerceptionObstacle.Type perception_object_type = 13; + void clear_perception_object_type(); + static const int kPerceptionObjectTypeFieldNumber = 13; + ::apollo::perception::PerceptionObstacle_Type perception_object_type() const; + void set_perception_object_type(::apollo::perception::PerceptionObstacle_Type value); + + // double width = 8; + void clear_width(); + static const int kWidthFieldNumber = 8; + double width() const; + void set_width(double value); + + // double height = 9; + void clear_height(); + static const int kHeightFieldNumber = 9; + double height() const; + void set_height(double value); + + // double tracking_time = 11; + void clear_tracking_time(); + static const int kTrackingTimeFieldNumber = 11; + double tracking_time() const; + void set_tracking_time(double value); + + // double perception_timestamp = 12; + void clear_perception_timestamp(); + static const int kPerceptionTimestampFieldNumber = 12; + double perception_timestamp() const; + void set_perception_timestamp(double value); + + // double prediction_timestamp = 14; + void clear_prediction_timestamp(); + static const int kPredictionTimestampFieldNumber = 14; + double prediction_timestamp() const; + void set_prediction_timestamp(double value); + + // .apollo.decision.ObjectDecision.ObjectType decision_object_type = 16; + void clear_decision_object_type(); + static const int kDecisionObjectTypeFieldNumber = 16; + ::apollo::decision::ObjectDecision_ObjectType decision_object_type() const; + void set_decision_object_type(::apollo::decision::ObjectDecision_ObjectType value); + + // @@protoc_insertion_point(class_scope:apollo.planning_internal.PlanningObstacle) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::perception::Point > polygon_point_; + ::google::protobuf::RepeatedPtrField< ::apollo::prediction::Trajectory > prediction_trajectory_; + ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecisionType > planning_object_decision_; + ::google::protobuf::internal::ArenaStringPtr decision_id_; + ::apollo::perception::Point* position_; + ::apollo::perception::Point* velocity_; + ::apollo::decision::ObjectDecisionType* object_decision_; + double theta_; + double speed_; + double length_; + ::google::protobuf::int32 perception_id_; + int perception_object_type_; + double width_; + double height_; + double tracking_time_; + double perception_timestamp_; + double prediction_timestamp_; + int decision_object_type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Debug_DebugMessage : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.planning_internal.Debug.DebugMessage) */ { + public: + Debug_DebugMessage(); + virtual ~Debug_DebugMessage(); + + Debug_DebugMessage(const Debug_DebugMessage& from); + + inline Debug_DebugMessage& operator=(const Debug_DebugMessage& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Debug_DebugMessage(Debug_DebugMessage&& from) noexcept + : Debug_DebugMessage() { + *this = ::std::move(from); + } + + inline Debug_DebugMessage& operator=(Debug_DebugMessage&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Debug_DebugMessage& default_instance(); + + enum DebugStringCase { + kTrace = 3, + kInfo = 4, + kWarn = 5, + kError = 6, + kFatal = 7, + DEBUG_STRING_NOT_SET = 0, + }; + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Debug_DebugMessage* internal_default_instance() { + return reinterpret_cast( + &_Debug_DebugMessage_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(Debug_DebugMessage* other); + friend void swap(Debug_DebugMessage& a, Debug_DebugMessage& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Debug_DebugMessage* New() const final { + return CreateMaybeMessage(NULL); + } + + Debug_DebugMessage* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Debug_DebugMessage& from); + void MergeFrom(const Debug_DebugMessage& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Debug_DebugMessage* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .apollo.planning_internal.Debug.ErrorCode error_code = 1; + void clear_error_code(); + static const int kErrorCodeFieldNumber = 1; + ::apollo::planning_internal::Debug_ErrorCode error_code() const; + void set_error_code(::apollo::planning_internal::Debug_ErrorCode value); + + // int32 id = 2; + void clear_id(); + static const int kIdFieldNumber = 2; + ::google::protobuf::int32 id() const; + void set_id(::google::protobuf::int32 value); + + // string trace = 3; + private: + bool has_trace() const; + public: + void clear_trace(); + static const int kTraceFieldNumber = 3; + const ::std::string& trace() const; + void set_trace(const ::std::string& value); + #if LANG_CXX11 + void set_trace(::std::string&& value); + #endif + void set_trace(const char* value); + void set_trace(const char* value, size_t size); + ::std::string* mutable_trace(); + ::std::string* release_trace(); + void set_allocated_trace(::std::string* trace); + + // string info = 4; + private: + bool has_info() const; + public: + void clear_info(); + static const int kInfoFieldNumber = 4; + const ::std::string& info() const; + void set_info(const ::std::string& value); + #if LANG_CXX11 + void set_info(::std::string&& value); + #endif + void set_info(const char* value); + void set_info(const char* value, size_t size); + ::std::string* mutable_info(); + ::std::string* release_info(); + void set_allocated_info(::std::string* info); + + // string warn = 5; + private: + bool has_warn() const; + public: + void clear_warn(); + static const int kWarnFieldNumber = 5; + const ::std::string& warn() const; + void set_warn(const ::std::string& value); + #if LANG_CXX11 + void set_warn(::std::string&& value); + #endif + void set_warn(const char* value); + void set_warn(const char* value, size_t size); + ::std::string* mutable_warn(); + ::std::string* release_warn(); + void set_allocated_warn(::std::string* warn); + + // string error = 6; + private: + bool has_error() const; + public: + void clear_error(); + static const int kErrorFieldNumber = 6; + const ::std::string& error() const; + void set_error(const ::std::string& value); + #if LANG_CXX11 + void set_error(::std::string&& value); + #endif + void set_error(const char* value); + void set_error(const char* value, size_t size); + ::std::string* mutable_error(); + ::std::string* release_error(); + void set_allocated_error(::std::string* error); + + // string fatal = 7; + private: + bool has_fatal() const; + public: + void clear_fatal(); + static const int kFatalFieldNumber = 7; + const ::std::string& fatal() const; + void set_fatal(const ::std::string& value); + #if LANG_CXX11 + void set_fatal(::std::string&& value); + #endif + void set_fatal(const char* value); + void set_fatal(const char* value, size_t size); + ::std::string* mutable_fatal(); + ::std::string* release_fatal(); + void set_allocated_fatal(::std::string* fatal); + + void clear_debug_string(); + DebugStringCase debug_string_case() const; + // @@protoc_insertion_point(class_scope:apollo.planning_internal.Debug.DebugMessage) + private: + void set_has_trace(); + void set_has_info(); + void set_has_warn(); + void set_has_error(); + void set_has_fatal(); + + inline bool has_debug_string() const; + inline void clear_has_debug_string(); + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + int error_code_; + ::google::protobuf::int32 id_; + union DebugStringUnion { + DebugStringUnion() {} + ::google::protobuf::internal::ArenaStringPtr trace_; + ::google::protobuf::internal::ArenaStringPtr info_; + ::google::protobuf::internal::ArenaStringPtr warn_; + ::google::protobuf::internal::ArenaStringPtr error_; + ::google::protobuf::internal::ArenaStringPtr fatal_; + } debug_string_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::google::protobuf::uint32 _oneof_case_[1]; + + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Debug : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.planning_internal.Debug) */ { + public: + Debug(); + virtual ~Debug(); + + Debug(const Debug& from); + + inline Debug& operator=(const Debug& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Debug(Debug&& from) noexcept + : Debug() { + *this = ::std::move(from); + } + + inline Debug& operator=(Debug&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Debug& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Debug* internal_default_instance() { + return reinterpret_cast( + &_Debug_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + void Swap(Debug* other); + friend void swap(Debug& a, Debug& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Debug* New() const final { + return CreateMaybeMessage(NULL); + } + + Debug* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Debug& from); + void MergeFrom(const Debug& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Debug* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef Debug_DebugMessage DebugMessage; + + typedef Debug_ErrorCode ErrorCode; + static const ErrorCode OK = + Debug_ErrorCode_OK; + static const ErrorCode ERR_NOT_READY = + Debug_ErrorCode_ERR_NOT_READY; + static const ErrorCode ERR_ESTOP = + Debug_ErrorCode_ERR_ESTOP; + static const ErrorCode ERR_PATH_OPTIMIZER = + Debug_ErrorCode_ERR_PATH_OPTIMIZER; + static const ErrorCode ERR_SPEED_OPTIMIZER = + Debug_ErrorCode_ERR_SPEED_OPTIMIZER; + static const ErrorCode ERR_ST_GRAPH = + Debug_ErrorCode_ERR_ST_GRAPH; + static const ErrorCode ERR_SANITY_CHECK = + Debug_ErrorCode_ERR_SANITY_CHECK; + static inline bool ErrorCode_IsValid(int value) { + return Debug_ErrorCode_IsValid(value); + } + static const ErrorCode ErrorCode_MIN = + Debug_ErrorCode_ErrorCode_MIN; + static const ErrorCode ErrorCode_MAX = + Debug_ErrorCode_ErrorCode_MAX; + static const int ErrorCode_ARRAYSIZE = + Debug_ErrorCode_ErrorCode_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + ErrorCode_descriptor() { + return Debug_ErrorCode_descriptor(); + } + static inline const ::std::string& ErrorCode_Name(ErrorCode value) { + return Debug_ErrorCode_Name(value); + } + static inline bool ErrorCode_Parse(const ::std::string& name, + ErrorCode* value) { + return Debug_ErrorCode_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // repeated .apollo.planning_internal.Debug.DebugMessage debug_message = 3; + int debug_message_size() const; + void clear_debug_message(); + static const int kDebugMessageFieldNumber = 3; + ::apollo::planning_internal::Debug_DebugMessage* mutable_debug_message(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::planning_internal::Debug_DebugMessage >* + mutable_debug_message(); + const ::apollo::planning_internal::Debug_DebugMessage& debug_message(int index) const; + ::apollo::planning_internal::Debug_DebugMessage* add_debug_message(); + const ::google::protobuf::RepeatedPtrField< ::apollo::planning_internal::Debug_DebugMessage >& + debug_message() const; + + // .apollo.planning_internal.PlanningData planning_data = 2; + bool has_planning_data() const; + void clear_planning_data(); + static const int kPlanningDataFieldNumber = 2; + private: + const ::apollo::planning_internal::PlanningData& _internal_planning_data() const; + public: + const ::apollo::planning_internal::PlanningData& planning_data() const; + ::apollo::planning_internal::PlanningData* release_planning_data(); + ::apollo::planning_internal::PlanningData* mutable_planning_data(); + void set_allocated_planning_data(::apollo::planning_internal::PlanningData* planning_data); + + // .apollo.planning_internal.Debug.ErrorCode error_code = 1; + void clear_error_code(); + static const int kErrorCodeFieldNumber = 1; + ::apollo::planning_internal::Debug_ErrorCode error_code() const; + void set_error_code(::apollo::planning_internal::Debug_ErrorCode value); + + // @@protoc_insertion_point(class_scope:apollo.planning_internal.Debug) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::planning_internal::Debug_DebugMessage > debug_message_; + ::apollo::planning_internal::PlanningData* planning_data_; + int error_code_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class PlanningData : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.planning_internal.PlanningData) */ { + public: + PlanningData(); + virtual ~PlanningData(); + + PlanningData(const PlanningData& from); + + inline PlanningData& operator=(const PlanningData& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + PlanningData(PlanningData&& from) noexcept + : PlanningData() { + *this = ::std::move(from); + } + + inline PlanningData& operator=(PlanningData&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const PlanningData& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const PlanningData* internal_default_instance() { + return reinterpret_cast( + &_PlanningData_default_instance_); + } + static constexpr int kIndexInFileMessages = + 3; + + void Swap(PlanningData* other); + friend void swap(PlanningData& a, PlanningData& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline PlanningData* New() const final { + return CreateMaybeMessage(NULL); + } + + PlanningData* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const PlanningData& from); + void MergeFrom(const PlanningData& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(PlanningData* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.planning_internal.PlanningObstacle planning_obstacle = 4; + int planning_obstacle_size() const; + void clear_planning_obstacle(); + static const int kPlanningObstacleFieldNumber = 4; + ::apollo::planning_internal::PlanningObstacle* mutable_planning_obstacle(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::planning_internal::PlanningObstacle >* + mutable_planning_obstacle(); + const ::apollo::planning_internal::PlanningObstacle& planning_obstacle(int index) const; + ::apollo::planning_internal::PlanningObstacle* add_planning_obstacle(); + const ::google::protobuf::RepeatedPtrField< ::apollo::planning_internal::PlanningObstacle >& + planning_obstacle() const; + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.localization.Pose init_status = 2; + bool has_init_status() const; + void clear_init_status(); + static const int kInitStatusFieldNumber = 2; + private: + const ::apollo::localization::Pose& _internal_init_status() const; + public: + const ::apollo::localization::Pose& init_status() const; + ::apollo::localization::Pose* release_init_status(); + ::apollo::localization::Pose* mutable_init_status(); + void set_allocated_init_status(::apollo::localization::Pose* init_status); + + // .apollo.decision.MainDecision main_decision = 3; + bool has_main_decision() const; + void clear_main_decision(); + static const int kMainDecisionFieldNumber = 3; + private: + const ::apollo::decision::MainDecision& _internal_main_decision() const; + public: + const ::apollo::decision::MainDecision& main_decision() const; + ::apollo::decision::MainDecision* release_main_decision(); + ::apollo::decision::MainDecision* mutable_main_decision(); + void set_allocated_main_decision(::apollo::decision::MainDecision* main_decision); + + // .apollo.decision.LightSignal light_signal = 5; + bool has_light_signal() const; + void clear_light_signal(); + static const int kLightSignalFieldNumber = 5; + private: + const ::apollo::decision::LightSignal& _internal_light_signal() const; + public: + const ::apollo::decision::LightSignal& light_signal() const; + ::apollo::decision::LightSignal* release_light_signal(); + ::apollo::decision::LightSignal* mutable_light_signal(); + void set_allocated_light_signal(::apollo::decision::LightSignal* light_signal); + + // @@protoc_insertion_point(class_scope:apollo.planning_internal.PlanningData) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::planning_internal::PlanningObstacle > planning_obstacle_; + ::apollo::common::Header* header_; + ::apollo::localization::Pose* init_status_; + ::apollo::decision::MainDecision* main_decision_; + ::apollo::decision::LightSignal* light_signal_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// PlanningObstacle + +// int32 perception_id = 1; +inline void PlanningObstacle::clear_perception_id() { + perception_id_ = 0; +} +inline ::google::protobuf::int32 PlanningObstacle::perception_id() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.perception_id) + return perception_id_; +} +inline void PlanningObstacle::set_perception_id(::google::protobuf::int32 value) { + + perception_id_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.PlanningObstacle.perception_id) +} + +// string decision_id = 2; +inline void PlanningObstacle::clear_decision_id() { + decision_id_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline const ::std::string& PlanningObstacle::decision_id() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.decision_id) + return decision_id_.GetNoArena(); +} +inline void PlanningObstacle::set_decision_id(const ::std::string& value) { + + decision_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.planning_internal.PlanningObstacle.decision_id) +} +#if LANG_CXX11 +inline void PlanningObstacle::set_decision_id(::std::string&& value) { + + decision_id_.SetNoArena( + &::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.planning_internal.PlanningObstacle.decision_id) +} +#endif +inline void PlanningObstacle::set_decision_id(const char* value) { + GOOGLE_DCHECK(value != NULL); + + decision_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.planning_internal.PlanningObstacle.decision_id) +} +inline void PlanningObstacle::set_decision_id(const char* value, size_t size) { + + decision_id_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.planning_internal.PlanningObstacle.decision_id) +} +inline ::std::string* PlanningObstacle::mutable_decision_id() { + + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.PlanningObstacle.decision_id) + return decision_id_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* PlanningObstacle::release_decision_id() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.PlanningObstacle.decision_id) + + return decision_id_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline void PlanningObstacle::set_allocated_decision_id(::std::string* decision_id) { + if (decision_id != NULL) { + + } else { + + } + decision_id_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), decision_id); + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.PlanningObstacle.decision_id) +} + +// .apollo.perception.Point position = 3; +inline bool PlanningObstacle::has_position() const { + return this != internal_default_instance() && position_ != NULL; +} +inline const ::apollo::perception::Point& PlanningObstacle::_internal_position() const { + return *position_; +} +inline const ::apollo::perception::Point& PlanningObstacle::position() const { + const ::apollo::perception::Point* p = position_; + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.position) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::perception::_Point_default_instance_); +} +inline ::apollo::perception::Point* PlanningObstacle::release_position() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.PlanningObstacle.position) + + ::apollo::perception::Point* temp = position_; + position_ = NULL; + return temp; +} +inline ::apollo::perception::Point* PlanningObstacle::mutable_position() { + + if (position_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::perception::Point>(GetArenaNoVirtual()); + position_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.PlanningObstacle.position) + return position_; +} +inline void PlanningObstacle::set_allocated_position(::apollo::perception::Point* position) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(position_); + } + if (position) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + position = ::google::protobuf::internal::GetOwnedMessage( + message_arena, position, submessage_arena); + } + + } else { + + } + position_ = position; + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.PlanningObstacle.position) +} + +// double theta = 4; +inline void PlanningObstacle::clear_theta() { + theta_ = 0; +} +inline double PlanningObstacle::theta() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.theta) + return theta_; +} +inline void PlanningObstacle::set_theta(double value) { + + theta_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.PlanningObstacle.theta) +} + +// .apollo.perception.Point velocity = 5; +inline bool PlanningObstacle::has_velocity() const { + return this != internal_default_instance() && velocity_ != NULL; +} +inline const ::apollo::perception::Point& PlanningObstacle::_internal_velocity() const { + return *velocity_; +} +inline const ::apollo::perception::Point& PlanningObstacle::velocity() const { + const ::apollo::perception::Point* p = velocity_; + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.velocity) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::perception::_Point_default_instance_); +} +inline ::apollo::perception::Point* PlanningObstacle::release_velocity() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.PlanningObstacle.velocity) + + ::apollo::perception::Point* temp = velocity_; + velocity_ = NULL; + return temp; +} +inline ::apollo::perception::Point* PlanningObstacle::mutable_velocity() { + + if (velocity_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::perception::Point>(GetArenaNoVirtual()); + velocity_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.PlanningObstacle.velocity) + return velocity_; +} +inline void PlanningObstacle::set_allocated_velocity(::apollo::perception::Point* velocity) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(velocity_); + } + if (velocity) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + velocity = ::google::protobuf::internal::GetOwnedMessage( + message_arena, velocity, submessage_arena); + } + + } else { + + } + velocity_ = velocity; + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.PlanningObstacle.velocity) +} + +// double speed = 6; +inline void PlanningObstacle::clear_speed() { + speed_ = 0; +} +inline double PlanningObstacle::speed() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.speed) + return speed_; +} +inline void PlanningObstacle::set_speed(double value) { + + speed_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.PlanningObstacle.speed) +} + +// double length = 7; +inline void PlanningObstacle::clear_length() { + length_ = 0; +} +inline double PlanningObstacle::length() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.length) + return length_; +} +inline void PlanningObstacle::set_length(double value) { + + length_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.PlanningObstacle.length) +} + +// double width = 8; +inline void PlanningObstacle::clear_width() { + width_ = 0; +} +inline double PlanningObstacle::width() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.width) + return width_; +} +inline void PlanningObstacle::set_width(double value) { + + width_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.PlanningObstacle.width) +} + +// double height = 9; +inline void PlanningObstacle::clear_height() { + height_ = 0; +} +inline double PlanningObstacle::height() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.height) + return height_; +} +inline void PlanningObstacle::set_height(double value) { + + height_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.PlanningObstacle.height) +} + +// repeated .apollo.perception.Point polygon_point = 10; +inline int PlanningObstacle::polygon_point_size() const { + return polygon_point_.size(); +} +inline ::apollo::perception::Point* PlanningObstacle::mutable_polygon_point(int index) { + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.PlanningObstacle.polygon_point) + return polygon_point_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::perception::Point >* +PlanningObstacle::mutable_polygon_point() { + // @@protoc_insertion_point(field_mutable_list:apollo.planning_internal.PlanningObstacle.polygon_point) + return &polygon_point_; +} +inline const ::apollo::perception::Point& PlanningObstacle::polygon_point(int index) const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.polygon_point) + return polygon_point_.Get(index); +} +inline ::apollo::perception::Point* PlanningObstacle::add_polygon_point() { + // @@protoc_insertion_point(field_add:apollo.planning_internal.PlanningObstacle.polygon_point) + return polygon_point_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::perception::Point >& +PlanningObstacle::polygon_point() const { + // @@protoc_insertion_point(field_list:apollo.planning_internal.PlanningObstacle.polygon_point) + return polygon_point_; +} + +// double tracking_time = 11; +inline void PlanningObstacle::clear_tracking_time() { + tracking_time_ = 0; +} +inline double PlanningObstacle::tracking_time() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.tracking_time) + return tracking_time_; +} +inline void PlanningObstacle::set_tracking_time(double value) { + + tracking_time_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.PlanningObstacle.tracking_time) +} + +// double perception_timestamp = 12; +inline void PlanningObstacle::clear_perception_timestamp() { + perception_timestamp_ = 0; +} +inline double PlanningObstacle::perception_timestamp() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.perception_timestamp) + return perception_timestamp_; +} +inline void PlanningObstacle::set_perception_timestamp(double value) { + + perception_timestamp_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.PlanningObstacle.perception_timestamp) +} + +// .apollo.perception.PerceptionObstacle.Type perception_object_type = 13; +inline void PlanningObstacle::clear_perception_object_type() { + perception_object_type_ = 0; +} +inline ::apollo::perception::PerceptionObstacle_Type PlanningObstacle::perception_object_type() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.perception_object_type) + return static_cast< ::apollo::perception::PerceptionObstacle_Type >(perception_object_type_); +} +inline void PlanningObstacle::set_perception_object_type(::apollo::perception::PerceptionObstacle_Type value) { + + perception_object_type_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.PlanningObstacle.perception_object_type) +} + +// double prediction_timestamp = 14; +inline void PlanningObstacle::clear_prediction_timestamp() { + prediction_timestamp_ = 0; +} +inline double PlanningObstacle::prediction_timestamp() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.prediction_timestamp) + return prediction_timestamp_; +} +inline void PlanningObstacle::set_prediction_timestamp(double value) { + + prediction_timestamp_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.PlanningObstacle.prediction_timestamp) +} + +// repeated .apollo.prediction.Trajectory prediction_trajectory = 15; +inline int PlanningObstacle::prediction_trajectory_size() const { + return prediction_trajectory_.size(); +} +inline ::apollo::prediction::Trajectory* PlanningObstacle::mutable_prediction_trajectory(int index) { + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.PlanningObstacle.prediction_trajectory) + return prediction_trajectory_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::prediction::Trajectory >* +PlanningObstacle::mutable_prediction_trajectory() { + // @@protoc_insertion_point(field_mutable_list:apollo.planning_internal.PlanningObstacle.prediction_trajectory) + return &prediction_trajectory_; +} +inline const ::apollo::prediction::Trajectory& PlanningObstacle::prediction_trajectory(int index) const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.prediction_trajectory) + return prediction_trajectory_.Get(index); +} +inline ::apollo::prediction::Trajectory* PlanningObstacle::add_prediction_trajectory() { + // @@protoc_insertion_point(field_add:apollo.planning_internal.PlanningObstacle.prediction_trajectory) + return prediction_trajectory_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::prediction::Trajectory >& +PlanningObstacle::prediction_trajectory() const { + // @@protoc_insertion_point(field_list:apollo.planning_internal.PlanningObstacle.prediction_trajectory) + return prediction_trajectory_; +} + +// .apollo.decision.ObjectDecision.ObjectType decision_object_type = 16; +inline void PlanningObstacle::clear_decision_object_type() { + decision_object_type_ = 0; +} +inline ::apollo::decision::ObjectDecision_ObjectType PlanningObstacle::decision_object_type() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.decision_object_type) + return static_cast< ::apollo::decision::ObjectDecision_ObjectType >(decision_object_type_); +} +inline void PlanningObstacle::set_decision_object_type(::apollo::decision::ObjectDecision_ObjectType value) { + + decision_object_type_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.PlanningObstacle.decision_object_type) +} + +// .apollo.decision.ObjectDecisionType object_decision = 17; +inline bool PlanningObstacle::has_object_decision() const { + return this != internal_default_instance() && object_decision_ != NULL; +} +inline const ::apollo::decision::ObjectDecisionType& PlanningObstacle::_internal_object_decision() const { + return *object_decision_; +} +inline const ::apollo::decision::ObjectDecisionType& PlanningObstacle::object_decision() const { + const ::apollo::decision::ObjectDecisionType* p = object_decision_; + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.object_decision) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_ObjectDecisionType_default_instance_); +} +inline ::apollo::decision::ObjectDecisionType* PlanningObstacle::release_object_decision() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.PlanningObstacle.object_decision) + + ::apollo::decision::ObjectDecisionType* temp = object_decision_; + object_decision_ = NULL; + return temp; +} +inline ::apollo::decision::ObjectDecisionType* PlanningObstacle::mutable_object_decision() { + + if (object_decision_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::ObjectDecisionType>(GetArenaNoVirtual()); + object_decision_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.PlanningObstacle.object_decision) + return object_decision_; +} +inline void PlanningObstacle::set_allocated_object_decision(::apollo::decision::ObjectDecisionType* object_decision) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(object_decision_); + } + if (object_decision) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + object_decision = ::google::protobuf::internal::GetOwnedMessage( + message_arena, object_decision, submessage_arena); + } + + } else { + + } + object_decision_ = object_decision; + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.PlanningObstacle.object_decision) +} + +// repeated .apollo.decision.ObjectDecisionType planning_object_decision = 18; +inline int PlanningObstacle::planning_object_decision_size() const { + return planning_object_decision_.size(); +} +inline ::apollo::decision::ObjectDecisionType* PlanningObstacle::mutable_planning_object_decision(int index) { + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.PlanningObstacle.planning_object_decision) + return planning_object_decision_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecisionType >* +PlanningObstacle::mutable_planning_object_decision() { + // @@protoc_insertion_point(field_mutable_list:apollo.planning_internal.PlanningObstacle.planning_object_decision) + return &planning_object_decision_; +} +inline const ::apollo::decision::ObjectDecisionType& PlanningObstacle::planning_object_decision(int index) const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningObstacle.planning_object_decision) + return planning_object_decision_.Get(index); +} +inline ::apollo::decision::ObjectDecisionType* PlanningObstacle::add_planning_object_decision() { + // @@protoc_insertion_point(field_add:apollo.planning_internal.PlanningObstacle.planning_object_decision) + return planning_object_decision_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::decision::ObjectDecisionType >& +PlanningObstacle::planning_object_decision() const { + // @@protoc_insertion_point(field_list:apollo.planning_internal.PlanningObstacle.planning_object_decision) + return planning_object_decision_; +} + +// ------------------------------------------------------------------- + +// Debug_DebugMessage + +// .apollo.planning_internal.Debug.ErrorCode error_code = 1; +inline void Debug_DebugMessage::clear_error_code() { + error_code_ = 0; +} +inline ::apollo::planning_internal::Debug_ErrorCode Debug_DebugMessage::error_code() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.Debug.DebugMessage.error_code) + return static_cast< ::apollo::planning_internal::Debug_ErrorCode >(error_code_); +} +inline void Debug_DebugMessage::set_error_code(::apollo::planning_internal::Debug_ErrorCode value) { + + error_code_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.error_code) +} + +// int32 id = 2; +inline void Debug_DebugMessage::clear_id() { + id_ = 0; +} +inline ::google::protobuf::int32 Debug_DebugMessage::id() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.Debug.DebugMessage.id) + return id_; +} +inline void Debug_DebugMessage::set_id(::google::protobuf::int32 value) { + + id_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.id) +} + +// string trace = 3; +inline bool Debug_DebugMessage::has_trace() const { + return debug_string_case() == kTrace; +} +inline void Debug_DebugMessage::set_has_trace() { + _oneof_case_[0] = kTrace; +} +inline void Debug_DebugMessage::clear_trace() { + if (has_trace()) { + debug_string_.trace_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + clear_has_debug_string(); + } +} +inline const ::std::string& Debug_DebugMessage::trace() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.Debug.DebugMessage.trace) + if (has_trace()) { + return debug_string_.trace_.GetNoArena(); + } + return *&::google::protobuf::internal::GetEmptyStringAlreadyInited(); +} +inline void Debug_DebugMessage::set_trace(const ::std::string& value) { + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.trace) + if (!has_trace()) { + clear_debug_string(); + set_has_trace(); + debug_string_.trace_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.trace_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.trace) +} +#if LANG_CXX11 +inline void Debug_DebugMessage::set_trace(::std::string&& value) { + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.trace) + if (!has_trace()) { + clear_debug_string(); + set_has_trace(); + debug_string_.trace_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.trace_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.planning_internal.Debug.DebugMessage.trace) +} +#endif +inline void Debug_DebugMessage::set_trace(const char* value) { + GOOGLE_DCHECK(value != NULL); + if (!has_trace()) { + clear_debug_string(); + set_has_trace(); + debug_string_.trace_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.trace_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.planning_internal.Debug.DebugMessage.trace) +} +inline void Debug_DebugMessage::set_trace(const char* value, size_t size) { + if (!has_trace()) { + clear_debug_string(); + set_has_trace(); + debug_string_.trace_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.trace_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string( + reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.planning_internal.Debug.DebugMessage.trace) +} +inline ::std::string* Debug_DebugMessage::mutable_trace() { + if (!has_trace()) { + clear_debug_string(); + set_has_trace(); + debug_string_.trace_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.Debug.DebugMessage.trace) + return debug_string_.trace_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* Debug_DebugMessage::release_trace() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.Debug.DebugMessage.trace) + if (has_trace()) { + clear_has_debug_string(); + return debug_string_.trace_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } else { + return NULL; + } +} +inline void Debug_DebugMessage::set_allocated_trace(::std::string* trace) { + if (!has_trace()) { + debug_string_.trace_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + clear_debug_string(); + if (trace != NULL) { + set_has_trace(); + debug_string_.trace_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), trace); + } + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.Debug.DebugMessage.trace) +} + +// string info = 4; +inline bool Debug_DebugMessage::has_info() const { + return debug_string_case() == kInfo; +} +inline void Debug_DebugMessage::set_has_info() { + _oneof_case_[0] = kInfo; +} +inline void Debug_DebugMessage::clear_info() { + if (has_info()) { + debug_string_.info_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + clear_has_debug_string(); + } +} +inline const ::std::string& Debug_DebugMessage::info() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.Debug.DebugMessage.info) + if (has_info()) { + return debug_string_.info_.GetNoArena(); + } + return *&::google::protobuf::internal::GetEmptyStringAlreadyInited(); +} +inline void Debug_DebugMessage::set_info(const ::std::string& value) { + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.info) + if (!has_info()) { + clear_debug_string(); + set_has_info(); + debug_string_.info_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.info_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.info) +} +#if LANG_CXX11 +inline void Debug_DebugMessage::set_info(::std::string&& value) { + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.info) + if (!has_info()) { + clear_debug_string(); + set_has_info(); + debug_string_.info_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.info_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.planning_internal.Debug.DebugMessage.info) +} +#endif +inline void Debug_DebugMessage::set_info(const char* value) { + GOOGLE_DCHECK(value != NULL); + if (!has_info()) { + clear_debug_string(); + set_has_info(); + debug_string_.info_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.info_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.planning_internal.Debug.DebugMessage.info) +} +inline void Debug_DebugMessage::set_info(const char* value, size_t size) { + if (!has_info()) { + clear_debug_string(); + set_has_info(); + debug_string_.info_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.info_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string( + reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.planning_internal.Debug.DebugMessage.info) +} +inline ::std::string* Debug_DebugMessage::mutable_info() { + if (!has_info()) { + clear_debug_string(); + set_has_info(); + debug_string_.info_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.Debug.DebugMessage.info) + return debug_string_.info_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* Debug_DebugMessage::release_info() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.Debug.DebugMessage.info) + if (has_info()) { + clear_has_debug_string(); + return debug_string_.info_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } else { + return NULL; + } +} +inline void Debug_DebugMessage::set_allocated_info(::std::string* info) { + if (!has_info()) { + debug_string_.info_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + clear_debug_string(); + if (info != NULL) { + set_has_info(); + debug_string_.info_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), info); + } + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.Debug.DebugMessage.info) +} + +// string warn = 5; +inline bool Debug_DebugMessage::has_warn() const { + return debug_string_case() == kWarn; +} +inline void Debug_DebugMessage::set_has_warn() { + _oneof_case_[0] = kWarn; +} +inline void Debug_DebugMessage::clear_warn() { + if (has_warn()) { + debug_string_.warn_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + clear_has_debug_string(); + } +} +inline const ::std::string& Debug_DebugMessage::warn() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.Debug.DebugMessage.warn) + if (has_warn()) { + return debug_string_.warn_.GetNoArena(); + } + return *&::google::protobuf::internal::GetEmptyStringAlreadyInited(); +} +inline void Debug_DebugMessage::set_warn(const ::std::string& value) { + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.warn) + if (!has_warn()) { + clear_debug_string(); + set_has_warn(); + debug_string_.warn_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.warn_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.warn) +} +#if LANG_CXX11 +inline void Debug_DebugMessage::set_warn(::std::string&& value) { + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.warn) + if (!has_warn()) { + clear_debug_string(); + set_has_warn(); + debug_string_.warn_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.warn_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.planning_internal.Debug.DebugMessage.warn) +} +#endif +inline void Debug_DebugMessage::set_warn(const char* value) { + GOOGLE_DCHECK(value != NULL); + if (!has_warn()) { + clear_debug_string(); + set_has_warn(); + debug_string_.warn_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.warn_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.planning_internal.Debug.DebugMessage.warn) +} +inline void Debug_DebugMessage::set_warn(const char* value, size_t size) { + if (!has_warn()) { + clear_debug_string(); + set_has_warn(); + debug_string_.warn_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.warn_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string( + reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.planning_internal.Debug.DebugMessage.warn) +} +inline ::std::string* Debug_DebugMessage::mutable_warn() { + if (!has_warn()) { + clear_debug_string(); + set_has_warn(); + debug_string_.warn_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.Debug.DebugMessage.warn) + return debug_string_.warn_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* Debug_DebugMessage::release_warn() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.Debug.DebugMessage.warn) + if (has_warn()) { + clear_has_debug_string(); + return debug_string_.warn_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } else { + return NULL; + } +} +inline void Debug_DebugMessage::set_allocated_warn(::std::string* warn) { + if (!has_warn()) { + debug_string_.warn_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + clear_debug_string(); + if (warn != NULL) { + set_has_warn(); + debug_string_.warn_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), warn); + } + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.Debug.DebugMessage.warn) +} + +// string error = 6; +inline bool Debug_DebugMessage::has_error() const { + return debug_string_case() == kError; +} +inline void Debug_DebugMessage::set_has_error() { + _oneof_case_[0] = kError; +} +inline void Debug_DebugMessage::clear_error() { + if (has_error()) { + debug_string_.error_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + clear_has_debug_string(); + } +} +inline const ::std::string& Debug_DebugMessage::error() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.Debug.DebugMessage.error) + if (has_error()) { + return debug_string_.error_.GetNoArena(); + } + return *&::google::protobuf::internal::GetEmptyStringAlreadyInited(); +} +inline void Debug_DebugMessage::set_error(const ::std::string& value) { + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.error) + if (!has_error()) { + clear_debug_string(); + set_has_error(); + debug_string_.error_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.error_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.error) +} +#if LANG_CXX11 +inline void Debug_DebugMessage::set_error(::std::string&& value) { + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.error) + if (!has_error()) { + clear_debug_string(); + set_has_error(); + debug_string_.error_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.error_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.planning_internal.Debug.DebugMessage.error) +} +#endif +inline void Debug_DebugMessage::set_error(const char* value) { + GOOGLE_DCHECK(value != NULL); + if (!has_error()) { + clear_debug_string(); + set_has_error(); + debug_string_.error_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.error_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.planning_internal.Debug.DebugMessage.error) +} +inline void Debug_DebugMessage::set_error(const char* value, size_t size) { + if (!has_error()) { + clear_debug_string(); + set_has_error(); + debug_string_.error_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.error_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string( + reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.planning_internal.Debug.DebugMessage.error) +} +inline ::std::string* Debug_DebugMessage::mutable_error() { + if (!has_error()) { + clear_debug_string(); + set_has_error(); + debug_string_.error_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.Debug.DebugMessage.error) + return debug_string_.error_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* Debug_DebugMessage::release_error() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.Debug.DebugMessage.error) + if (has_error()) { + clear_has_debug_string(); + return debug_string_.error_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } else { + return NULL; + } +} +inline void Debug_DebugMessage::set_allocated_error(::std::string* error) { + if (!has_error()) { + debug_string_.error_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + clear_debug_string(); + if (error != NULL) { + set_has_error(); + debug_string_.error_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), error); + } + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.Debug.DebugMessage.error) +} + +// string fatal = 7; +inline bool Debug_DebugMessage::has_fatal() const { + return debug_string_case() == kFatal; +} +inline void Debug_DebugMessage::set_has_fatal() { + _oneof_case_[0] = kFatal; +} +inline void Debug_DebugMessage::clear_fatal() { + if (has_fatal()) { + debug_string_.fatal_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + clear_has_debug_string(); + } +} +inline const ::std::string& Debug_DebugMessage::fatal() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.Debug.DebugMessage.fatal) + if (has_fatal()) { + return debug_string_.fatal_.GetNoArena(); + } + return *&::google::protobuf::internal::GetEmptyStringAlreadyInited(); +} +inline void Debug_DebugMessage::set_fatal(const ::std::string& value) { + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.fatal) + if (!has_fatal()) { + clear_debug_string(); + set_has_fatal(); + debug_string_.fatal_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.fatal_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), value); + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.fatal) +} +#if LANG_CXX11 +inline void Debug_DebugMessage::set_fatal(::std::string&& value) { + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.DebugMessage.fatal) + if (!has_fatal()) { + clear_debug_string(); + set_has_fatal(); + debug_string_.fatal_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.fatal_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::move(value)); + // @@protoc_insertion_point(field_set_rvalue:apollo.planning_internal.Debug.DebugMessage.fatal) +} +#endif +inline void Debug_DebugMessage::set_fatal(const char* value) { + GOOGLE_DCHECK(value != NULL); + if (!has_fatal()) { + clear_debug_string(); + set_has_fatal(); + debug_string_.fatal_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.fatal_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), + ::std::string(value)); + // @@protoc_insertion_point(field_set_char:apollo.planning_internal.Debug.DebugMessage.fatal) +} +inline void Debug_DebugMessage::set_fatal(const char* value, size_t size) { + if (!has_fatal()) { + clear_debug_string(); + set_has_fatal(); + debug_string_.fatal_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + debug_string_.fatal_.SetNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), ::std::string( + reinterpret_cast(value), size)); + // @@protoc_insertion_point(field_set_pointer:apollo.planning_internal.Debug.DebugMessage.fatal) +} +inline ::std::string* Debug_DebugMessage::mutable_fatal() { + if (!has_fatal()) { + clear_debug_string(); + set_has_fatal(); + debug_string_.fatal_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.Debug.DebugMessage.fatal) + return debug_string_.fatal_.MutableNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +} +inline ::std::string* Debug_DebugMessage::release_fatal() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.Debug.DebugMessage.fatal) + if (has_fatal()) { + clear_has_debug_string(); + return debug_string_.fatal_.ReleaseNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } else { + return NULL; + } +} +inline void Debug_DebugMessage::set_allocated_fatal(::std::string* fatal) { + if (!has_fatal()) { + debug_string_.fatal_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + } + clear_debug_string(); + if (fatal != NULL) { + set_has_fatal(); + debug_string_.fatal_.SetAllocatedNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), fatal); + } + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.Debug.DebugMessage.fatal) +} + +inline bool Debug_DebugMessage::has_debug_string() const { + return debug_string_case() != DEBUG_STRING_NOT_SET; +} +inline void Debug_DebugMessage::clear_has_debug_string() { + _oneof_case_[0] = DEBUG_STRING_NOT_SET; +} +inline Debug_DebugMessage::DebugStringCase Debug_DebugMessage::debug_string_case() const { + return Debug_DebugMessage::DebugStringCase(_oneof_case_[0]); +} +// ------------------------------------------------------------------- + +// Debug + +// .apollo.planning_internal.Debug.ErrorCode error_code = 1; +inline void Debug::clear_error_code() { + error_code_ = 0; +} +inline ::apollo::planning_internal::Debug_ErrorCode Debug::error_code() const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.Debug.error_code) + return static_cast< ::apollo::planning_internal::Debug_ErrorCode >(error_code_); +} +inline void Debug::set_error_code(::apollo::planning_internal::Debug_ErrorCode value) { + + error_code_ = value; + // @@protoc_insertion_point(field_set:apollo.planning_internal.Debug.error_code) +} + +// .apollo.planning_internal.PlanningData planning_data = 2; +inline bool Debug::has_planning_data() const { + return this != internal_default_instance() && planning_data_ != NULL; +} +inline void Debug::clear_planning_data() { + if (GetArenaNoVirtual() == NULL && planning_data_ != NULL) { + delete planning_data_; + } + planning_data_ = NULL; +} +inline const ::apollo::planning_internal::PlanningData& Debug::_internal_planning_data() const { + return *planning_data_; +} +inline const ::apollo::planning_internal::PlanningData& Debug::planning_data() const { + const ::apollo::planning_internal::PlanningData* p = planning_data_; + // @@protoc_insertion_point(field_get:apollo.planning_internal.Debug.planning_data) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::planning_internal::_PlanningData_default_instance_); +} +inline ::apollo::planning_internal::PlanningData* Debug::release_planning_data() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.Debug.planning_data) + + ::apollo::planning_internal::PlanningData* temp = planning_data_; + planning_data_ = NULL; + return temp; +} +inline ::apollo::planning_internal::PlanningData* Debug::mutable_planning_data() { + + if (planning_data_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::planning_internal::PlanningData>(GetArenaNoVirtual()); + planning_data_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.Debug.planning_data) + return planning_data_; +} +inline void Debug::set_allocated_planning_data(::apollo::planning_internal::PlanningData* planning_data) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete planning_data_; + } + if (planning_data) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + planning_data = ::google::protobuf::internal::GetOwnedMessage( + message_arena, planning_data, submessage_arena); + } + + } else { + + } + planning_data_ = planning_data; + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.Debug.planning_data) +} + +// repeated .apollo.planning_internal.Debug.DebugMessage debug_message = 3; +inline int Debug::debug_message_size() const { + return debug_message_.size(); +} +inline void Debug::clear_debug_message() { + debug_message_.Clear(); +} +inline ::apollo::planning_internal::Debug_DebugMessage* Debug::mutable_debug_message(int index) { + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.Debug.debug_message) + return debug_message_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::planning_internal::Debug_DebugMessage >* +Debug::mutable_debug_message() { + // @@protoc_insertion_point(field_mutable_list:apollo.planning_internal.Debug.debug_message) + return &debug_message_; +} +inline const ::apollo::planning_internal::Debug_DebugMessage& Debug::debug_message(int index) const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.Debug.debug_message) + return debug_message_.Get(index); +} +inline ::apollo::planning_internal::Debug_DebugMessage* Debug::add_debug_message() { + // @@protoc_insertion_point(field_add:apollo.planning_internal.Debug.debug_message) + return debug_message_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::planning_internal::Debug_DebugMessage >& +Debug::debug_message() const { + // @@protoc_insertion_point(field_list:apollo.planning_internal.Debug.debug_message) + return debug_message_; +} + +// ------------------------------------------------------------------- + +// PlanningData + +// .apollo.common.Header header = 1; +inline bool PlanningData::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& PlanningData::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& PlanningData::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningData.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* PlanningData::release_header() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.PlanningData.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* PlanningData::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.PlanningData.header) + return header_; +} +inline void PlanningData::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.PlanningData.header) +} + +// .apollo.localization.Pose init_status = 2; +inline bool PlanningData::has_init_status() const { + return this != internal_default_instance() && init_status_ != NULL; +} +inline const ::apollo::localization::Pose& PlanningData::_internal_init_status() const { + return *init_status_; +} +inline const ::apollo::localization::Pose& PlanningData::init_status() const { + const ::apollo::localization::Pose* p = init_status_; + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningData.init_status) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::localization::_Pose_default_instance_); +} +inline ::apollo::localization::Pose* PlanningData::release_init_status() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.PlanningData.init_status) + + ::apollo::localization::Pose* temp = init_status_; + init_status_ = NULL; + return temp; +} +inline ::apollo::localization::Pose* PlanningData::mutable_init_status() { + + if (init_status_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::localization::Pose>(GetArenaNoVirtual()); + init_status_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.PlanningData.init_status) + return init_status_; +} +inline void PlanningData::set_allocated_init_status(::apollo::localization::Pose* init_status) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(init_status_); + } + if (init_status) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + init_status = ::google::protobuf::internal::GetOwnedMessage( + message_arena, init_status, submessage_arena); + } + + } else { + + } + init_status_ = init_status; + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.PlanningData.init_status) +} + +// .apollo.decision.MainDecision main_decision = 3; +inline bool PlanningData::has_main_decision() const { + return this != internal_default_instance() && main_decision_ != NULL; +} +inline const ::apollo::decision::MainDecision& PlanningData::_internal_main_decision() const { + return *main_decision_; +} +inline const ::apollo::decision::MainDecision& PlanningData::main_decision() const { + const ::apollo::decision::MainDecision* p = main_decision_; + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningData.main_decision) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_MainDecision_default_instance_); +} +inline ::apollo::decision::MainDecision* PlanningData::release_main_decision() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.PlanningData.main_decision) + + ::apollo::decision::MainDecision* temp = main_decision_; + main_decision_ = NULL; + return temp; +} +inline ::apollo::decision::MainDecision* PlanningData::mutable_main_decision() { + + if (main_decision_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::MainDecision>(GetArenaNoVirtual()); + main_decision_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.PlanningData.main_decision) + return main_decision_; +} +inline void PlanningData::set_allocated_main_decision(::apollo::decision::MainDecision* main_decision) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(main_decision_); + } + if (main_decision) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + main_decision = ::google::protobuf::internal::GetOwnedMessage( + message_arena, main_decision, submessage_arena); + } + + } else { + + } + main_decision_ = main_decision; + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.PlanningData.main_decision) +} + +// repeated .apollo.planning_internal.PlanningObstacle planning_obstacle = 4; +inline int PlanningData::planning_obstacle_size() const { + return planning_obstacle_.size(); +} +inline void PlanningData::clear_planning_obstacle() { + planning_obstacle_.Clear(); +} +inline ::apollo::planning_internal::PlanningObstacle* PlanningData::mutable_planning_obstacle(int index) { + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.PlanningData.planning_obstacle) + return planning_obstacle_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::planning_internal::PlanningObstacle >* +PlanningData::mutable_planning_obstacle() { + // @@protoc_insertion_point(field_mutable_list:apollo.planning_internal.PlanningData.planning_obstacle) + return &planning_obstacle_; +} +inline const ::apollo::planning_internal::PlanningObstacle& PlanningData::planning_obstacle(int index) const { + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningData.planning_obstacle) + return planning_obstacle_.Get(index); +} +inline ::apollo::planning_internal::PlanningObstacle* PlanningData::add_planning_obstacle() { + // @@protoc_insertion_point(field_add:apollo.planning_internal.PlanningData.planning_obstacle) + return planning_obstacle_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::planning_internal::PlanningObstacle >& +PlanningData::planning_obstacle() const { + // @@protoc_insertion_point(field_list:apollo.planning_internal.PlanningData.planning_obstacle) + return planning_obstacle_; +} + +// .apollo.decision.LightSignal light_signal = 5; +inline bool PlanningData::has_light_signal() const { + return this != internal_default_instance() && light_signal_ != NULL; +} +inline const ::apollo::decision::LightSignal& PlanningData::_internal_light_signal() const { + return *light_signal_; +} +inline const ::apollo::decision::LightSignal& PlanningData::light_signal() const { + const ::apollo::decision::LightSignal* p = light_signal_; + // @@protoc_insertion_point(field_get:apollo.planning_internal.PlanningData.light_signal) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::decision::_LightSignal_default_instance_); +} +inline ::apollo::decision::LightSignal* PlanningData::release_light_signal() { + // @@protoc_insertion_point(field_release:apollo.planning_internal.PlanningData.light_signal) + + ::apollo::decision::LightSignal* temp = light_signal_; + light_signal_ = NULL; + return temp; +} +inline ::apollo::decision::LightSignal* PlanningData::mutable_light_signal() { + + if (light_signal_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::decision::LightSignal>(GetArenaNoVirtual()); + light_signal_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.planning_internal.PlanningData.light_signal) + return light_signal_; +} +inline void PlanningData::set_allocated_light_signal(::apollo::decision::LightSignal* light_signal) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(light_signal_); + } + if (light_signal) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + light_signal = ::google::protobuf::internal::GetOwnedMessage( + message_arena, light_signal, submessage_arena); + } + + } else { + + } + light_signal_ = light_signal; + // @@protoc_insertion_point(field_set_allocated:apollo.planning_internal.PlanningData.light_signal) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace planning_internal +} // namespace apollo + +namespace google { +namespace protobuf { + +template <> struct is_proto_enum< ::apollo::planning_internal::Debug_ErrorCode> : ::std::true_type {}; +template <> +inline const EnumDescriptor* GetEnumDescriptor< ::apollo::planning_internal::Debug_ErrorCode>() { + return ::apollo::planning_internal::Debug_ErrorCode_descriptor(); +} + +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fplanning_2fplanning_5finternal_2eproto diff --git a/apollo_msgs/include/apollo_msgs/proto/prediction/prediction_obstacle.pb.cc b/apollo_msgs/include/apollo_msgs/proto/prediction/prediction_obstacle.pb.cc new file mode 100644 index 0000000..e694ac8 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/prediction/prediction_obstacle.pb.cc @@ -0,0 +1,1614 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/prediction/prediction_obstacle.proto + +#include "apollo_msgs/proto/prediction/prediction_obstacle.pb.h" + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +// This is a temporary google only hack +#ifdef GOOGLE_PROTOBUF_ENFORCE_UNIQUENESS +#include "third_party/protobuf/version.h" +#endif +// @@protoc_insertion_point(includes) + +namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Header; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_PerceptionObstacle; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto +namespace protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto { +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_TrajectoryPoint; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto ::google::protobuf::internal::SCCInfo<1> scc_info_Trajectory; +extern PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto ::google::protobuf::internal::SCCInfo<2> scc_info_PredictionObstacle; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto +namespace apollo { +namespace prediction { +class TrajectoryPointDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _TrajectoryPoint_default_instance_; +class TrajectoryDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _Trajectory_default_instance_; +class PredictionObstacleDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _PredictionObstacle_default_instance_; +class PredictionObstaclesDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed + _instance; +} _PredictionObstacles_default_instance_; +} // namespace prediction +} // namespace apollo +namespace protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto { +static void InitDefaultsTrajectoryPoint() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::prediction::_TrajectoryPoint_default_instance_; + new (ptr) ::apollo::prediction::TrajectoryPoint(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::prediction::TrajectoryPoint::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_TrajectoryPoint = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsTrajectoryPoint}, {}}; + +static void InitDefaultsTrajectory() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::prediction::_Trajectory_default_instance_; + new (ptr) ::apollo::prediction::Trajectory(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::prediction::Trajectory::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_Trajectory = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsTrajectory}, { + &protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::scc_info_TrajectoryPoint.base,}}; + +static void InitDefaultsPredictionObstacle() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::prediction::_PredictionObstacle_default_instance_; + new (ptr) ::apollo::prediction::PredictionObstacle(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::prediction::PredictionObstacle::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_PredictionObstacle = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsPredictionObstacle}, { + &protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::scc_info_PerceptionObstacle.base, + &protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::scc_info_Trajectory.base,}}; + +static void InitDefaultsPredictionObstacles() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::apollo::prediction::_PredictionObstacles_default_instance_; + new (ptr) ::apollo::prediction::PredictionObstacles(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::apollo::prediction::PredictionObstacles::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<2> scc_info_PredictionObstacles = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 2, InitDefaultsPredictionObstacles}, { + &protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::scc_info_Header.base, + &protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::scc_info_PredictionObstacle.base,}}; + +void InitDefaults() { + ::google::protobuf::internal::InitSCC(&scc_info_TrajectoryPoint.base); + ::google::protobuf::internal::InitSCC(&scc_info_Trajectory.base); + ::google::protobuf::internal::InitSCC(&scc_info_PredictionObstacle.base); + ::google::protobuf::internal::InitSCC(&scc_info_PredictionObstacles.base); +} + +::google::protobuf::Metadata file_level_metadata[4]; + +const ::google::protobuf::uint32 TableStruct::offsets[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::TrajectoryPoint, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::TrajectoryPoint, x_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::TrajectoryPoint, y_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::TrajectoryPoint, z_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::TrajectoryPoint, velocity_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::TrajectoryPoint, t_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::TrajectoryPoint, heading_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::Trajectory, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::Trajectory, probability_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::Trajectory, trajectory_point_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::PredictionObstacle, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::PredictionObstacle, perception_obstacle_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::PredictionObstacle, time_stamp_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::PredictionObstacle, predicted_period_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::PredictionObstacle, trajectory_), + ~0u, // no _has_bits_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::PredictionObstacles, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::PredictionObstacles, header_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::PredictionObstacles, prediction_obstacle_), + GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(::apollo::prediction::PredictionObstacles, perception_error_code_), +}; +static const ::google::protobuf::internal::MigrationSchema schemas[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + { 0, -1, sizeof(::apollo::prediction::TrajectoryPoint)}, + { 11, -1, sizeof(::apollo::prediction::Trajectory)}, + { 18, -1, sizeof(::apollo::prediction::PredictionObstacle)}, + { 27, -1, sizeof(::apollo::prediction::PredictionObstacles)}, +}; + +static ::google::protobuf::Message const * const file_default_instances[] = { + reinterpret_cast(&::apollo::prediction::_TrajectoryPoint_default_instance_), + reinterpret_cast(&::apollo::prediction::_Trajectory_default_instance_), + reinterpret_cast(&::apollo::prediction::_PredictionObstacle_default_instance_), + reinterpret_cast(&::apollo::prediction::_PredictionObstacles_default_instance_), +}; + +void protobuf_AssignDescriptors() { + AddDescriptors(); + AssignDescriptors( + "apollo_msgs/proto/prediction/prediction_obstacle.proto", schemas, file_default_instances, TableStruct::offsets, + file_level_metadata, NULL, NULL); +} + +void protobuf_AssignDescriptorsOnce() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, protobuf_AssignDescriptors); +} + +void protobuf_RegisterTypes(const ::std::string&) GOOGLE_PROTOBUF_ATTRIBUTE_COLD; +void protobuf_RegisterTypes(const ::std::string&) { + protobuf_AssignDescriptorsOnce(); + ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 4); +} + +void AddDescriptorsImpl() { + InitDefaults(); + static const char descriptor[] GOOGLE_PROTOBUF_ATTRIBUTE_SECTION_VARIABLE(protodesc_cold) = { + "\n6apollo_msgs/proto/prediction/predictio" + "n_obstacle.proto\022\021apollo.prediction\032%apo" + "llo_msgs/proto/common/header.proto\0326apol" + "lo_msgs/proto/perception/perception_obst" + "acle.proto\"`\n\017TrajectoryPoint\022\t\n\001x\030\001 \001(\001" + "\022\t\n\001y\030\002 \001(\001\022\t\n\001z\030\003 \001(\001\022\020\n\010velocity\030\004 \001(\001" + "\022\t\n\001t\030\005 \001(\001\022\017\n\007heading\030\006 \001(\001\"_\n\nTrajecto" + "ry\022\023\n\013probability\030\001 \001(\001\022<\n\020trajectory_po" + "int\030\002 \003(\0132\".apollo.prediction.Trajectory" + "Point\"\271\001\n\022PredictionObstacle\022B\n\023percepti" + "on_obstacle\030\001 \001(\0132%.apollo.perception.Pe" + "rceptionObstacle\022\022\n\ntime_stamp\030\002 \001(\001\022\030\n\020" + "predicted_period\030\003 \001(\001\0221\n\ntrajectory\030\004 \003" + "(\0132\035.apollo.prediction.Trajectory\"\307\001\n\023Pr" + "edictionObstacles\022%\n\006header\030\001 \001(\0132\025.apol" + "lo.common.Header\022B\n\023prediction_obstacle\030" + "\002 \003(\0132%.apollo.prediction.PredictionObst" + "acle\022E\n\025perception_error_code\030\003 \001(\0162&.ap" + "ollo.perception.PerceptionErrorCodeb\006pro" + "to3" + }; + ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( + descriptor, 763); + ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( + "apollo_msgs/proto/prediction/prediction_obstacle.proto", &protobuf_RegisterTypes); + ::protobuf_apollo_5fmsgs_2fproto_2fcommon_2fheader_2eproto::AddDescriptors(); + ::protobuf_apollo_5fmsgs_2fproto_2fperception_2fperception_5fobstacle_2eproto::AddDescriptors(); +} + +void AddDescriptors() { + static ::google::protobuf::internal::once_flag once; + ::google::protobuf::internal::call_once(once, AddDescriptorsImpl); +} +// Force AddDescriptors() to be called at dynamic initialization time. +struct StaticDescriptorInitializer { + StaticDescriptorInitializer() { + AddDescriptors(); + } +} static_descriptor_initializer; +} // namespace protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto +namespace apollo { +namespace prediction { + +// =================================================================== + +void TrajectoryPoint::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int TrajectoryPoint::kXFieldNumber; +const int TrajectoryPoint::kYFieldNumber; +const int TrajectoryPoint::kZFieldNumber; +const int TrajectoryPoint::kVelocityFieldNumber; +const int TrajectoryPoint::kTFieldNumber; +const int TrajectoryPoint::kHeadingFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +TrajectoryPoint::TrajectoryPoint() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::scc_info_TrajectoryPoint.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.prediction.TrajectoryPoint) +} +TrajectoryPoint::TrajectoryPoint(const TrajectoryPoint& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&x_, &from.x_, + static_cast(reinterpret_cast(&heading_) - + reinterpret_cast(&x_)) + sizeof(heading_)); + // @@protoc_insertion_point(copy_constructor:apollo.prediction.TrajectoryPoint) +} + +void TrajectoryPoint::SharedCtor() { + ::memset(&x_, 0, static_cast( + reinterpret_cast(&heading_) - + reinterpret_cast(&x_)) + sizeof(heading_)); +} + +TrajectoryPoint::~TrajectoryPoint() { + // @@protoc_insertion_point(destructor:apollo.prediction.TrajectoryPoint) + SharedDtor(); +} + +void TrajectoryPoint::SharedDtor() { +} + +void TrajectoryPoint::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* TrajectoryPoint::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const TrajectoryPoint& TrajectoryPoint::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::scc_info_TrajectoryPoint.base); + return *internal_default_instance(); +} + + +void TrajectoryPoint::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.prediction.TrajectoryPoint) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&x_, 0, static_cast( + reinterpret_cast(&heading_) - + reinterpret_cast(&x_)) + sizeof(heading_)); + _internal_metadata_.Clear(); +} + +bool TrajectoryPoint::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.prediction.TrajectoryPoint) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double x = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &x_))); + } else { + goto handle_unusual; + } + break; + } + + // double y = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &y_))); + } else { + goto handle_unusual; + } + break; + } + + // double z = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &z_))); + } else { + goto handle_unusual; + } + break; + } + + // double velocity = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(33u /* 33 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &velocity_))); + } else { + goto handle_unusual; + } + break; + } + + // double t = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(41u /* 41 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &t_))); + } else { + goto handle_unusual; + } + break; + } + + // double heading = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(49u /* 49 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &heading_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.prediction.TrajectoryPoint) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.prediction.TrajectoryPoint) + return false; +#undef DO_ +} + +void TrajectoryPoint::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.prediction.TrajectoryPoint) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output); + } + + // double y = 2; + if (this->y() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output); + } + + // double z = 3; + if (this->z() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->z(), output); + } + + // double velocity = 4; + if (this->velocity() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->velocity(), output); + } + + // double t = 5; + if (this->t() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->t(), output); + } + + // double heading = 6; + if (this->heading() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->heading(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.prediction.TrajectoryPoint) +} + +::google::protobuf::uint8* TrajectoryPoint::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.prediction.TrajectoryPoint) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double x = 1; + if (this->x() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target); + } + + // double y = 2; + if (this->y() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target); + } + + // double z = 3; + if (this->z() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->z(), target); + } + + // double velocity = 4; + if (this->velocity() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->velocity(), target); + } + + // double t = 5; + if (this->t() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->t(), target); + } + + // double heading = 6; + if (this->heading() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->heading(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.prediction.TrajectoryPoint) + return target; +} + +size_t TrajectoryPoint::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.prediction.TrajectoryPoint) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // double x = 1; + if (this->x() != 0) { + total_size += 1 + 8; + } + + // double y = 2; + if (this->y() != 0) { + total_size += 1 + 8; + } + + // double z = 3; + if (this->z() != 0) { + total_size += 1 + 8; + } + + // double velocity = 4; + if (this->velocity() != 0) { + total_size += 1 + 8; + } + + // double t = 5; + if (this->t() != 0) { + total_size += 1 + 8; + } + + // double heading = 6; + if (this->heading() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void TrajectoryPoint::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.prediction.TrajectoryPoint) + GOOGLE_DCHECK_NE(&from, this); + const TrajectoryPoint* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.prediction.TrajectoryPoint) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.prediction.TrajectoryPoint) + MergeFrom(*source); + } +} + +void TrajectoryPoint::MergeFrom(const TrajectoryPoint& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.prediction.TrajectoryPoint) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.x() != 0) { + set_x(from.x()); + } + if (from.y() != 0) { + set_y(from.y()); + } + if (from.z() != 0) { + set_z(from.z()); + } + if (from.velocity() != 0) { + set_velocity(from.velocity()); + } + if (from.t() != 0) { + set_t(from.t()); + } + if (from.heading() != 0) { + set_heading(from.heading()); + } +} + +void TrajectoryPoint::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.prediction.TrajectoryPoint) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void TrajectoryPoint::CopyFrom(const TrajectoryPoint& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.prediction.TrajectoryPoint) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool TrajectoryPoint::IsInitialized() const { + return true; +} + +void TrajectoryPoint::Swap(TrajectoryPoint* other) { + if (other == this) return; + InternalSwap(other); +} +void TrajectoryPoint::InternalSwap(TrajectoryPoint* other) { + using std::swap; + swap(x_, other->x_); + swap(y_, other->y_); + swap(z_, other->z_); + swap(velocity_, other->velocity_); + swap(t_, other->t_); + swap(heading_, other->heading_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata TrajectoryPoint::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void Trajectory::InitAsDefaultInstance() { +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Trajectory::kProbabilityFieldNumber; +const int Trajectory::kTrajectoryPointFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Trajectory::Trajectory() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::scc_info_Trajectory.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.prediction.Trajectory) +} +Trajectory::Trajectory(const Trajectory& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + trajectory_point_(from.trajectory_point_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + probability_ = from.probability_; + // @@protoc_insertion_point(copy_constructor:apollo.prediction.Trajectory) +} + +void Trajectory::SharedCtor() { + probability_ = 0; +} + +Trajectory::~Trajectory() { + // @@protoc_insertion_point(destructor:apollo.prediction.Trajectory) + SharedDtor(); +} + +void Trajectory::SharedDtor() { +} + +void Trajectory::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* Trajectory::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const Trajectory& Trajectory::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::scc_info_Trajectory.base); + return *internal_default_instance(); +} + + +void Trajectory::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.prediction.Trajectory) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + trajectory_point_.Clear(); + probability_ = 0; + _internal_metadata_.Clear(); +} + +bool Trajectory::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.prediction.Trajectory) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double probability = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(9u /* 9 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &probability_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.prediction.TrajectoryPoint trajectory_point = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_trajectory_point())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.prediction.Trajectory) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.prediction.Trajectory) + return false; +#undef DO_ +} + +void Trajectory::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.prediction.Trajectory) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double probability = 1; + if (this->probability() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->probability(), output); + } + + // repeated .apollo.prediction.TrajectoryPoint trajectory_point = 2; + for (unsigned int i = 0, + n = static_cast(this->trajectory_point_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, + this->trajectory_point(static_cast(i)), + output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.prediction.Trajectory) +} + +::google::protobuf::uint8* Trajectory::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.prediction.Trajectory) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double probability = 1; + if (this->probability() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->probability(), target); + } + + // repeated .apollo.prediction.TrajectoryPoint trajectory_point = 2; + for (unsigned int i = 0, + n = static_cast(this->trajectory_point_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->trajectory_point(static_cast(i)), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.prediction.Trajectory) + return target; +} + +size_t Trajectory::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.prediction.Trajectory) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.prediction.TrajectoryPoint trajectory_point = 2; + { + unsigned int count = static_cast(this->trajectory_point_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->trajectory_point(static_cast(i))); + } + } + + // double probability = 1; + if (this->probability() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Trajectory::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.prediction.Trajectory) + GOOGLE_DCHECK_NE(&from, this); + const Trajectory* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.prediction.Trajectory) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.prediction.Trajectory) + MergeFrom(*source); + } +} + +void Trajectory::MergeFrom(const Trajectory& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.prediction.Trajectory) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + trajectory_point_.MergeFrom(from.trajectory_point_); + if (from.probability() != 0) { + set_probability(from.probability()); + } +} + +void Trajectory::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.prediction.Trajectory) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Trajectory::CopyFrom(const Trajectory& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.prediction.Trajectory) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Trajectory::IsInitialized() const { + return true; +} + +void Trajectory::Swap(Trajectory* other) { + if (other == this) return; + InternalSwap(other); +} +void Trajectory::InternalSwap(Trajectory* other) { + using std::swap; + CastToBase(&trajectory_point_)->InternalSwap(CastToBase(&other->trajectory_point_)); + swap(probability_, other->probability_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata Trajectory::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void PredictionObstacle::InitAsDefaultInstance() { + ::apollo::prediction::_PredictionObstacle_default_instance_._instance.get_mutable()->perception_obstacle_ = const_cast< ::apollo::perception::PerceptionObstacle*>( + ::apollo::perception::PerceptionObstacle::internal_default_instance()); +} +void PredictionObstacle::clear_perception_obstacle() { + if (GetArenaNoVirtual() == NULL && perception_obstacle_ != NULL) { + delete perception_obstacle_; + } + perception_obstacle_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PredictionObstacle::kPerceptionObstacleFieldNumber; +const int PredictionObstacle::kTimeStampFieldNumber; +const int PredictionObstacle::kPredictedPeriodFieldNumber; +const int PredictionObstacle::kTrajectoryFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PredictionObstacle::PredictionObstacle() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::scc_info_PredictionObstacle.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.prediction.PredictionObstacle) +} +PredictionObstacle::PredictionObstacle(const PredictionObstacle& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + trajectory_(from.trajectory_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_perception_obstacle()) { + perception_obstacle_ = new ::apollo::perception::PerceptionObstacle(*from.perception_obstacle_); + } else { + perception_obstacle_ = NULL; + } + ::memcpy(&time_stamp_, &from.time_stamp_, + static_cast(reinterpret_cast(&predicted_period_) - + reinterpret_cast(&time_stamp_)) + sizeof(predicted_period_)); + // @@protoc_insertion_point(copy_constructor:apollo.prediction.PredictionObstacle) +} + +void PredictionObstacle::SharedCtor() { + ::memset(&perception_obstacle_, 0, static_cast( + reinterpret_cast(&predicted_period_) - + reinterpret_cast(&perception_obstacle_)) + sizeof(predicted_period_)); +} + +PredictionObstacle::~PredictionObstacle() { + // @@protoc_insertion_point(destructor:apollo.prediction.PredictionObstacle) + SharedDtor(); +} + +void PredictionObstacle::SharedDtor() { + if (this != internal_default_instance()) delete perception_obstacle_; +} + +void PredictionObstacle::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* PredictionObstacle::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const PredictionObstacle& PredictionObstacle::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::scc_info_PredictionObstacle.base); + return *internal_default_instance(); +} + + +void PredictionObstacle::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.prediction.PredictionObstacle) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + trajectory_.Clear(); + if (GetArenaNoVirtual() == NULL && perception_obstacle_ != NULL) { + delete perception_obstacle_; + } + perception_obstacle_ = NULL; + ::memset(&time_stamp_, 0, static_cast( + reinterpret_cast(&predicted_period_) - + reinterpret_cast(&time_stamp_)) + sizeof(predicted_period_)); + _internal_metadata_.Clear(); +} + +bool PredictionObstacle::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.prediction.PredictionObstacle) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.perception.PerceptionObstacle perception_obstacle = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_perception_obstacle())); + } else { + goto handle_unusual; + } + break; + } + + // double time_stamp = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(17u /* 17 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &time_stamp_))); + } else { + goto handle_unusual; + } + break; + } + + // double predicted_period = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(25u /* 25 & 0xFF */)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &predicted_period_))); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.prediction.Trajectory trajectory = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(34u /* 34 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_trajectory())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.prediction.PredictionObstacle) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.prediction.PredictionObstacle) + return false; +#undef DO_ +} + +void PredictionObstacle::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.prediction.PredictionObstacle) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.perception.PerceptionObstacle perception_obstacle = 1; + if (this->has_perception_obstacle()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_perception_obstacle(), output); + } + + // double time_stamp = 2; + if (this->time_stamp() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->time_stamp(), output); + } + + // double predicted_period = 3; + if (this->predicted_period() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->predicted_period(), output); + } + + // repeated .apollo.prediction.Trajectory trajectory = 4; + for (unsigned int i = 0, + n = static_cast(this->trajectory_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 4, + this->trajectory(static_cast(i)), + output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.prediction.PredictionObstacle) +} + +::google::protobuf::uint8* PredictionObstacle::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.prediction.PredictionObstacle) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.perception.PerceptionObstacle perception_obstacle = 1; + if (this->has_perception_obstacle()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_perception_obstacle(), deterministic, target); + } + + // double time_stamp = 2; + if (this->time_stamp() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->time_stamp(), target); + } + + // double predicted_period = 3; + if (this->predicted_period() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->predicted_period(), target); + } + + // repeated .apollo.prediction.Trajectory trajectory = 4; + for (unsigned int i = 0, + n = static_cast(this->trajectory_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 4, this->trajectory(static_cast(i)), deterministic, target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.prediction.PredictionObstacle) + return target; +} + +size_t PredictionObstacle::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.prediction.PredictionObstacle) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.prediction.Trajectory trajectory = 4; + { + unsigned int count = static_cast(this->trajectory_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->trajectory(static_cast(i))); + } + } + + // .apollo.perception.PerceptionObstacle perception_obstacle = 1; + if (this->has_perception_obstacle()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *perception_obstacle_); + } + + // double time_stamp = 2; + if (this->time_stamp() != 0) { + total_size += 1 + 8; + } + + // double predicted_period = 3; + if (this->predicted_period() != 0) { + total_size += 1 + 8; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void PredictionObstacle::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.prediction.PredictionObstacle) + GOOGLE_DCHECK_NE(&from, this); + const PredictionObstacle* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.prediction.PredictionObstacle) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.prediction.PredictionObstacle) + MergeFrom(*source); + } +} + +void PredictionObstacle::MergeFrom(const PredictionObstacle& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.prediction.PredictionObstacle) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + trajectory_.MergeFrom(from.trajectory_); + if (from.has_perception_obstacle()) { + mutable_perception_obstacle()->::apollo::perception::PerceptionObstacle::MergeFrom(from.perception_obstacle()); + } + if (from.time_stamp() != 0) { + set_time_stamp(from.time_stamp()); + } + if (from.predicted_period() != 0) { + set_predicted_period(from.predicted_period()); + } +} + +void PredictionObstacle::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.prediction.PredictionObstacle) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PredictionObstacle::CopyFrom(const PredictionObstacle& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.prediction.PredictionObstacle) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PredictionObstacle::IsInitialized() const { + return true; +} + +void PredictionObstacle::Swap(PredictionObstacle* other) { + if (other == this) return; + InternalSwap(other); +} +void PredictionObstacle::InternalSwap(PredictionObstacle* other) { + using std::swap; + CastToBase(&trajectory_)->InternalSwap(CastToBase(&other->trajectory_)); + swap(perception_obstacle_, other->perception_obstacle_); + swap(time_stamp_, other->time_stamp_); + swap(predicted_period_, other->predicted_period_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata PredictionObstacle::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// =================================================================== + +void PredictionObstacles::InitAsDefaultInstance() { + ::apollo::prediction::_PredictionObstacles_default_instance_._instance.get_mutable()->header_ = const_cast< ::apollo::common::Header*>( + ::apollo::common::Header::internal_default_instance()); +} +void PredictionObstacles::clear_header() { + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int PredictionObstacles::kHeaderFieldNumber; +const int PredictionObstacles::kPredictionObstacleFieldNumber; +const int PredictionObstacles::kPerceptionErrorCodeFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +PredictionObstacles::PredictionObstacles() + : ::google::protobuf::Message(), _internal_metadata_(NULL) { + ::google::protobuf::internal::InitSCC( + &protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::scc_info_PredictionObstacles.base); + SharedCtor(); + // @@protoc_insertion_point(constructor:apollo.prediction.PredictionObstacles) +} +PredictionObstacles::PredictionObstacles(const PredictionObstacles& from) + : ::google::protobuf::Message(), + _internal_metadata_(NULL), + prediction_obstacle_(from.prediction_obstacle_) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_header()) { + header_ = new ::apollo::common::Header(*from.header_); + } else { + header_ = NULL; + } + perception_error_code_ = from.perception_error_code_; + // @@protoc_insertion_point(copy_constructor:apollo.prediction.PredictionObstacles) +} + +void PredictionObstacles::SharedCtor() { + ::memset(&header_, 0, static_cast( + reinterpret_cast(&perception_error_code_) - + reinterpret_cast(&header_)) + sizeof(perception_error_code_)); +} + +PredictionObstacles::~PredictionObstacles() { + // @@protoc_insertion_point(destructor:apollo.prediction.PredictionObstacles) + SharedDtor(); +} + +void PredictionObstacles::SharedDtor() { + if (this != internal_default_instance()) delete header_; +} + +void PredictionObstacles::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ::google::protobuf::Descriptor* PredictionObstacles::descriptor() { + ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages].descriptor; +} + +const PredictionObstacles& PredictionObstacles::default_instance() { + ::google::protobuf::internal::InitSCC(&protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::scc_info_PredictionObstacles.base); + return *internal_default_instance(); +} + + +void PredictionObstacles::Clear() { +// @@protoc_insertion_point(message_clear_start:apollo.prediction.PredictionObstacles) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + prediction_obstacle_.Clear(); + if (GetArenaNoVirtual() == NULL && header_ != NULL) { + delete header_; + } + header_ = NULL; + perception_error_code_ = 0; + _internal_metadata_.Clear(); +} + +bool PredictionObstacles::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:apollo.prediction.PredictionObstacles) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .apollo.common.Header header = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(10u /* 10 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_header())); + } else { + goto handle_unusual; + } + break; + } + + // repeated .apollo.prediction.PredictionObstacle prediction_obstacle = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(18u /* 18 & 0xFF */)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, add_prediction_obstacle())); + } else { + goto handle_unusual; + } + break; + } + + // .apollo.perception.PerceptionErrorCode perception_error_code = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == + static_cast< ::google::protobuf::uint8>(24u /* 24 & 0xFF */)) { + int value; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_perception_error_code(static_cast< ::apollo::perception::PerceptionErrorCode >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:apollo.prediction.PredictionObstacles) + return true; +failure: + // @@protoc_insertion_point(parse_failure:apollo.prediction.PredictionObstacles) + return false; +#undef DO_ +} + +void PredictionObstacles::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:apollo.prediction.PredictionObstacles) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, this->_internal_header(), output); + } + + // repeated .apollo.prediction.PredictionObstacle prediction_obstacle = 2; + for (unsigned int i = 0, + n = static_cast(this->prediction_obstacle_size()); i < n; i++) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 2, + this->prediction_obstacle(static_cast(i)), + output); + } + + // .apollo.perception.PerceptionErrorCode perception_error_code = 3; + if (this->perception_error_code() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 3, this->perception_error_code(), output); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), output); + } + // @@protoc_insertion_point(serialize_end:apollo.prediction.PredictionObstacles) +} + +::google::protobuf::uint8* PredictionObstacles::InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const { + (void)deterministic; // Unused + // @@protoc_insertion_point(serialize_to_array_start:apollo.prediction.PredictionObstacles) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .apollo.common.Header header = 1; + if (this->has_header()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, this->_internal_header(), deterministic, target); + } + + // repeated .apollo.prediction.PredictionObstacle prediction_obstacle = 2; + for (unsigned int i = 0, + n = static_cast(this->prediction_obstacle_size()); i < n; i++) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 2, this->prediction_obstacle(static_cast(i)), deterministic, target); + } + + // .apollo.perception.PerceptionErrorCode perception_error_code = 3; + if (this->perception_error_code() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 3, this->perception_error_code(), target); + } + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance()), target); + } + // @@protoc_insertion_point(serialize_to_array_end:apollo.prediction.PredictionObstacles) + return target; +} + +size_t PredictionObstacles::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:apollo.prediction.PredictionObstacles) + size_t total_size = 0; + + if ((_internal_metadata_.have_unknown_fields() && ::google::protobuf::internal::GetProto3PreserveUnknownsDefault())) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + (::google::protobuf::internal::GetProto3PreserveUnknownsDefault() ? _internal_metadata_.unknown_fields() : _internal_metadata_.default_instance())); + } + // repeated .apollo.prediction.PredictionObstacle prediction_obstacle = 2; + { + unsigned int count = static_cast(this->prediction_obstacle_size()); + total_size += 1UL * count; + for (unsigned int i = 0; i < count; i++) { + total_size += + ::google::protobuf::internal::WireFormatLite::MessageSize( + this->prediction_obstacle(static_cast(i))); + } + } + + // .apollo.common.Header header = 1; + if (this->has_header()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *header_); + } + + // .apollo.perception.PerceptionErrorCode perception_error_code = 3; + if (this->perception_error_code() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->perception_error_code()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void PredictionObstacles::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:apollo.prediction.PredictionObstacles) + GOOGLE_DCHECK_NE(&from, this); + const PredictionObstacles* source = + ::google::protobuf::internal::DynamicCastToGenerated( + &from); + if (source == NULL) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:apollo.prediction.PredictionObstacles) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:apollo.prediction.PredictionObstacles) + MergeFrom(*source); + } +} + +void PredictionObstacles::MergeFrom(const PredictionObstacles& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:apollo.prediction.PredictionObstacles) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + prediction_obstacle_.MergeFrom(from.prediction_obstacle_); + if (from.has_header()) { + mutable_header()->::apollo::common::Header::MergeFrom(from.header()); + } + if (from.perception_error_code() != 0) { + set_perception_error_code(from.perception_error_code()); + } +} + +void PredictionObstacles::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:apollo.prediction.PredictionObstacles) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void PredictionObstacles::CopyFrom(const PredictionObstacles& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:apollo.prediction.PredictionObstacles) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool PredictionObstacles::IsInitialized() const { + return true; +} + +void PredictionObstacles::Swap(PredictionObstacles* other) { + if (other == this) return; + InternalSwap(other); +} +void PredictionObstacles::InternalSwap(PredictionObstacles* other) { + using std::swap; + CastToBase(&prediction_obstacle_)->InternalSwap(CastToBase(&other->prediction_obstacle_)); + swap(header_, other->header_); + swap(perception_error_code_, other->perception_error_code_); + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata PredictionObstacles::GetMetadata() const { + protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::protobuf_AssignDescriptorsOnce(); + return ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::file_level_metadata[kIndexInFileMessages]; +} + + +// @@protoc_insertion_point(namespace_scope) +} // namespace prediction +} // namespace apollo +namespace google { +namespace protobuf { +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::prediction::TrajectoryPoint* Arena::CreateMaybeMessage< ::apollo::prediction::TrajectoryPoint >(Arena* arena) { + return Arena::CreateInternal< ::apollo::prediction::TrajectoryPoint >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::prediction::Trajectory* Arena::CreateMaybeMessage< ::apollo::prediction::Trajectory >(Arena* arena) { + return Arena::CreateInternal< ::apollo::prediction::Trajectory >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::prediction::PredictionObstacle* Arena::CreateMaybeMessage< ::apollo::prediction::PredictionObstacle >(Arena* arena) { + return Arena::CreateInternal< ::apollo::prediction::PredictionObstacle >(arena); +} +template<> GOOGLE_PROTOBUF_ATTRIBUTE_NOINLINE ::apollo::prediction::PredictionObstacles* Arena::CreateMaybeMessage< ::apollo::prediction::PredictionObstacles >(Arena* arena) { + return Arena::CreateInternal< ::apollo::prediction::PredictionObstacles >(arena); +} +} // namespace protobuf +} // namespace google + +// @@protoc_insertion_point(global_scope) diff --git a/apollo_msgs/include/apollo_msgs/proto/prediction/prediction_obstacle.pb.h b/apollo_msgs/include/apollo_msgs/proto/prediction/prediction_obstacle.pb.h new file mode 100644 index 0000000..9fec104 --- /dev/null +++ b/apollo_msgs/include/apollo_msgs/proto/prediction/prediction_obstacle.pb.h @@ -0,0 +1,962 @@ +// Generated by the protocol buffer compiler. DO NOT EDIT! +// source: apollo_msgs/proto/prediction/prediction_obstacle.proto + +#ifndef PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto +#define PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto + +#include + +#include + +#if GOOGLE_PROTOBUF_VERSION < 3006001 +#error This file was generated by a newer version of protoc which is +#error incompatible with your Protocol Buffer headers. Please update +#error your headers. +#endif +#if 3006001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION +#error This file was generated by an older version of protoc which is +#error incompatible with your Protocol Buffer headers. Please +#error regenerate this file with a newer version of protoc. +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include // IWYU pragma: export +#include // IWYU pragma: export +#include +#include "apollo_msgs/proto/common/header.pb.h" +#include "apollo_msgs/proto/perception/perception_obstacle.pb.h" +// @@protoc_insertion_point(includes) +#define PROTOBUF_INTERNAL_EXPORT_protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto + +namespace protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto { +// Internal implementation detail -- do not use these members. +struct TableStruct { + static const ::google::protobuf::internal::ParseTableField entries[]; + static const ::google::protobuf::internal::AuxillaryParseTableField aux[]; + static const ::google::protobuf::internal::ParseTable schema[4]; + static const ::google::protobuf::internal::FieldMetadata field_metadata[]; + static const ::google::protobuf::internal::SerializationTable serialization_table[]; + static const ::google::protobuf::uint32 offsets[]; +}; +void AddDescriptors(); +} // namespace protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto +namespace apollo { +namespace prediction { +class PredictionObstacle; +class PredictionObstacleDefaultTypeInternal; +extern PredictionObstacleDefaultTypeInternal _PredictionObstacle_default_instance_; +class PredictionObstacles; +class PredictionObstaclesDefaultTypeInternal; +extern PredictionObstaclesDefaultTypeInternal _PredictionObstacles_default_instance_; +class Trajectory; +class TrajectoryDefaultTypeInternal; +extern TrajectoryDefaultTypeInternal _Trajectory_default_instance_; +class TrajectoryPoint; +class TrajectoryPointDefaultTypeInternal; +extern TrajectoryPointDefaultTypeInternal _TrajectoryPoint_default_instance_; +} // namespace prediction +} // namespace apollo +namespace google { +namespace protobuf { +template<> ::apollo::prediction::PredictionObstacle* Arena::CreateMaybeMessage<::apollo::prediction::PredictionObstacle>(Arena*); +template<> ::apollo::prediction::PredictionObstacles* Arena::CreateMaybeMessage<::apollo::prediction::PredictionObstacles>(Arena*); +template<> ::apollo::prediction::Trajectory* Arena::CreateMaybeMessage<::apollo::prediction::Trajectory>(Arena*); +template<> ::apollo::prediction::TrajectoryPoint* Arena::CreateMaybeMessage<::apollo::prediction::TrajectoryPoint>(Arena*); +} // namespace protobuf +} // namespace google +namespace apollo { +namespace prediction { + +// =================================================================== + +class TrajectoryPoint : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.prediction.TrajectoryPoint) */ { + public: + TrajectoryPoint(); + virtual ~TrajectoryPoint(); + + TrajectoryPoint(const TrajectoryPoint& from); + + inline TrajectoryPoint& operator=(const TrajectoryPoint& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + TrajectoryPoint(TrajectoryPoint&& from) noexcept + : TrajectoryPoint() { + *this = ::std::move(from); + } + + inline TrajectoryPoint& operator=(TrajectoryPoint&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const TrajectoryPoint& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const TrajectoryPoint* internal_default_instance() { + return reinterpret_cast( + &_TrajectoryPoint_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + void Swap(TrajectoryPoint* other); + friend void swap(TrajectoryPoint& a, TrajectoryPoint& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline TrajectoryPoint* New() const final { + return CreateMaybeMessage(NULL); + } + + TrajectoryPoint* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const TrajectoryPoint& from); + void MergeFrom(const TrajectoryPoint& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(TrajectoryPoint* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // double x = 1; + void clear_x(); + static const int kXFieldNumber = 1; + double x() const; + void set_x(double value); + + // double y = 2; + void clear_y(); + static const int kYFieldNumber = 2; + double y() const; + void set_y(double value); + + // double z = 3; + void clear_z(); + static const int kZFieldNumber = 3; + double z() const; + void set_z(double value); + + // double velocity = 4; + void clear_velocity(); + static const int kVelocityFieldNumber = 4; + double velocity() const; + void set_velocity(double value); + + // double t = 5; + void clear_t(); + static const int kTFieldNumber = 5; + double t() const; + void set_t(double value); + + // double heading = 6; + void clear_heading(); + static const int kHeadingFieldNumber = 6; + double heading() const; + void set_heading(double value); + + // @@protoc_insertion_point(class_scope:apollo.prediction.TrajectoryPoint) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + double x_; + double y_; + double z_; + double velocity_; + double t_; + double heading_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class Trajectory : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.prediction.Trajectory) */ { + public: + Trajectory(); + virtual ~Trajectory(); + + Trajectory(const Trajectory& from); + + inline Trajectory& operator=(const Trajectory& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Trajectory(Trajectory&& from) noexcept + : Trajectory() { + *this = ::std::move(from); + } + + inline Trajectory& operator=(Trajectory&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const Trajectory& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Trajectory* internal_default_instance() { + return reinterpret_cast( + &_Trajectory_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + void Swap(Trajectory* other); + friend void swap(Trajectory& a, Trajectory& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Trajectory* New() const final { + return CreateMaybeMessage(NULL); + } + + Trajectory* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Trajectory& from); + void MergeFrom(const Trajectory& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Trajectory* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.prediction.TrajectoryPoint trajectory_point = 2; + int trajectory_point_size() const; + void clear_trajectory_point(); + static const int kTrajectoryPointFieldNumber = 2; + ::apollo::prediction::TrajectoryPoint* mutable_trajectory_point(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::prediction::TrajectoryPoint >* + mutable_trajectory_point(); + const ::apollo::prediction::TrajectoryPoint& trajectory_point(int index) const; + ::apollo::prediction::TrajectoryPoint* add_trajectory_point(); + const ::google::protobuf::RepeatedPtrField< ::apollo::prediction::TrajectoryPoint >& + trajectory_point() const; + + // double probability = 1; + void clear_probability(); + static const int kProbabilityFieldNumber = 1; + double probability() const; + void set_probability(double value); + + // @@protoc_insertion_point(class_scope:apollo.prediction.Trajectory) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::prediction::TrajectoryPoint > trajectory_point_; + double probability_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class PredictionObstacle : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.prediction.PredictionObstacle) */ { + public: + PredictionObstacle(); + virtual ~PredictionObstacle(); + + PredictionObstacle(const PredictionObstacle& from); + + inline PredictionObstacle& operator=(const PredictionObstacle& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + PredictionObstacle(PredictionObstacle&& from) noexcept + : PredictionObstacle() { + *this = ::std::move(from); + } + + inline PredictionObstacle& operator=(PredictionObstacle&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const PredictionObstacle& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const PredictionObstacle* internal_default_instance() { + return reinterpret_cast( + &_PredictionObstacle_default_instance_); + } + static constexpr int kIndexInFileMessages = + 2; + + void Swap(PredictionObstacle* other); + friend void swap(PredictionObstacle& a, PredictionObstacle& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline PredictionObstacle* New() const final { + return CreateMaybeMessage(NULL); + } + + PredictionObstacle* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const PredictionObstacle& from); + void MergeFrom(const PredictionObstacle& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(PredictionObstacle* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.prediction.Trajectory trajectory = 4; + int trajectory_size() const; + void clear_trajectory(); + static const int kTrajectoryFieldNumber = 4; + ::apollo::prediction::Trajectory* mutable_trajectory(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::prediction::Trajectory >* + mutable_trajectory(); + const ::apollo::prediction::Trajectory& trajectory(int index) const; + ::apollo::prediction::Trajectory* add_trajectory(); + const ::google::protobuf::RepeatedPtrField< ::apollo::prediction::Trajectory >& + trajectory() const; + + // .apollo.perception.PerceptionObstacle perception_obstacle = 1; + bool has_perception_obstacle() const; + void clear_perception_obstacle(); + static const int kPerceptionObstacleFieldNumber = 1; + private: + const ::apollo::perception::PerceptionObstacle& _internal_perception_obstacle() const; + public: + const ::apollo::perception::PerceptionObstacle& perception_obstacle() const; + ::apollo::perception::PerceptionObstacle* release_perception_obstacle(); + ::apollo::perception::PerceptionObstacle* mutable_perception_obstacle(); + void set_allocated_perception_obstacle(::apollo::perception::PerceptionObstacle* perception_obstacle); + + // double time_stamp = 2; + void clear_time_stamp(); + static const int kTimeStampFieldNumber = 2; + double time_stamp() const; + void set_time_stamp(double value); + + // double predicted_period = 3; + void clear_predicted_period(); + static const int kPredictedPeriodFieldNumber = 3; + double predicted_period() const; + void set_predicted_period(double value); + + // @@protoc_insertion_point(class_scope:apollo.prediction.PredictionObstacle) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::prediction::Trajectory > trajectory_; + ::apollo::perception::PerceptionObstacle* perception_obstacle_; + double time_stamp_; + double predicted_period_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::TableStruct; +}; +// ------------------------------------------------------------------- + +class PredictionObstacles : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:apollo.prediction.PredictionObstacles) */ { + public: + PredictionObstacles(); + virtual ~PredictionObstacles(); + + PredictionObstacles(const PredictionObstacles& from); + + inline PredictionObstacles& operator=(const PredictionObstacles& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + PredictionObstacles(PredictionObstacles&& from) noexcept + : PredictionObstacles() { + *this = ::std::move(from); + } + + inline PredictionObstacles& operator=(PredictionObstacles&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor(); + static const PredictionObstacles& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const PredictionObstacles* internal_default_instance() { + return reinterpret_cast( + &_PredictionObstacles_default_instance_); + } + static constexpr int kIndexInFileMessages = + 3; + + void Swap(PredictionObstacles* other); + friend void swap(PredictionObstacles& a, PredictionObstacles& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline PredictionObstacles* New() const final { + return CreateMaybeMessage(NULL); + } + + PredictionObstacles* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const PredictionObstacles& from); + void MergeFrom(const PredictionObstacles& from); + void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + bool deterministic, ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(PredictionObstacles* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return NULL; + } + inline void* MaybeArenaPtr() const { + return NULL; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // repeated .apollo.prediction.PredictionObstacle prediction_obstacle = 2; + int prediction_obstacle_size() const; + void clear_prediction_obstacle(); + static const int kPredictionObstacleFieldNumber = 2; + ::apollo::prediction::PredictionObstacle* mutable_prediction_obstacle(int index); + ::google::protobuf::RepeatedPtrField< ::apollo::prediction::PredictionObstacle >* + mutable_prediction_obstacle(); + const ::apollo::prediction::PredictionObstacle& prediction_obstacle(int index) const; + ::apollo::prediction::PredictionObstacle* add_prediction_obstacle(); + const ::google::protobuf::RepeatedPtrField< ::apollo::prediction::PredictionObstacle >& + prediction_obstacle() const; + + // .apollo.common.Header header = 1; + bool has_header() const; + void clear_header(); + static const int kHeaderFieldNumber = 1; + private: + const ::apollo::common::Header& _internal_header() const; + public: + const ::apollo::common::Header& header() const; + ::apollo::common::Header* release_header(); + ::apollo::common::Header* mutable_header(); + void set_allocated_header(::apollo::common::Header* header); + + // .apollo.perception.PerceptionErrorCode perception_error_code = 3; + void clear_perception_error_code(); + static const int kPerceptionErrorCodeFieldNumber = 3; + ::apollo::perception::PerceptionErrorCode perception_error_code() const; + void set_perception_error_code(::apollo::perception::PerceptionErrorCode value); + + // @@protoc_insertion_point(class_scope:apollo.prediction.PredictionObstacles) + private: + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::RepeatedPtrField< ::apollo::prediction::PredictionObstacle > prediction_obstacle_; + ::apollo::common::Header* header_; + int perception_error_code_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::protobuf_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto::TableStruct; +}; +// =================================================================== + + +// =================================================================== + +#ifdef __GNUC__ + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// TrajectoryPoint + +// double x = 1; +inline void TrajectoryPoint::clear_x() { + x_ = 0; +} +inline double TrajectoryPoint::x() const { + // @@protoc_insertion_point(field_get:apollo.prediction.TrajectoryPoint.x) + return x_; +} +inline void TrajectoryPoint::set_x(double value) { + + x_ = value; + // @@protoc_insertion_point(field_set:apollo.prediction.TrajectoryPoint.x) +} + +// double y = 2; +inline void TrajectoryPoint::clear_y() { + y_ = 0; +} +inline double TrajectoryPoint::y() const { + // @@protoc_insertion_point(field_get:apollo.prediction.TrajectoryPoint.y) + return y_; +} +inline void TrajectoryPoint::set_y(double value) { + + y_ = value; + // @@protoc_insertion_point(field_set:apollo.prediction.TrajectoryPoint.y) +} + +// double z = 3; +inline void TrajectoryPoint::clear_z() { + z_ = 0; +} +inline double TrajectoryPoint::z() const { + // @@protoc_insertion_point(field_get:apollo.prediction.TrajectoryPoint.z) + return z_; +} +inline void TrajectoryPoint::set_z(double value) { + + z_ = value; + // @@protoc_insertion_point(field_set:apollo.prediction.TrajectoryPoint.z) +} + +// double velocity = 4; +inline void TrajectoryPoint::clear_velocity() { + velocity_ = 0; +} +inline double TrajectoryPoint::velocity() const { + // @@protoc_insertion_point(field_get:apollo.prediction.TrajectoryPoint.velocity) + return velocity_; +} +inline void TrajectoryPoint::set_velocity(double value) { + + velocity_ = value; + // @@protoc_insertion_point(field_set:apollo.prediction.TrajectoryPoint.velocity) +} + +// double t = 5; +inline void TrajectoryPoint::clear_t() { + t_ = 0; +} +inline double TrajectoryPoint::t() const { + // @@protoc_insertion_point(field_get:apollo.prediction.TrajectoryPoint.t) + return t_; +} +inline void TrajectoryPoint::set_t(double value) { + + t_ = value; + // @@protoc_insertion_point(field_set:apollo.prediction.TrajectoryPoint.t) +} + +// double heading = 6; +inline void TrajectoryPoint::clear_heading() { + heading_ = 0; +} +inline double TrajectoryPoint::heading() const { + // @@protoc_insertion_point(field_get:apollo.prediction.TrajectoryPoint.heading) + return heading_; +} +inline void TrajectoryPoint::set_heading(double value) { + + heading_ = value; + // @@protoc_insertion_point(field_set:apollo.prediction.TrajectoryPoint.heading) +} + +// ------------------------------------------------------------------- + +// Trajectory + +// double probability = 1; +inline void Trajectory::clear_probability() { + probability_ = 0; +} +inline double Trajectory::probability() const { + // @@protoc_insertion_point(field_get:apollo.prediction.Trajectory.probability) + return probability_; +} +inline void Trajectory::set_probability(double value) { + + probability_ = value; + // @@protoc_insertion_point(field_set:apollo.prediction.Trajectory.probability) +} + +// repeated .apollo.prediction.TrajectoryPoint trajectory_point = 2; +inline int Trajectory::trajectory_point_size() const { + return trajectory_point_.size(); +} +inline void Trajectory::clear_trajectory_point() { + trajectory_point_.Clear(); +} +inline ::apollo::prediction::TrajectoryPoint* Trajectory::mutable_trajectory_point(int index) { + // @@protoc_insertion_point(field_mutable:apollo.prediction.Trajectory.trajectory_point) + return trajectory_point_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::prediction::TrajectoryPoint >* +Trajectory::mutable_trajectory_point() { + // @@protoc_insertion_point(field_mutable_list:apollo.prediction.Trajectory.trajectory_point) + return &trajectory_point_; +} +inline const ::apollo::prediction::TrajectoryPoint& Trajectory::trajectory_point(int index) const { + // @@protoc_insertion_point(field_get:apollo.prediction.Trajectory.trajectory_point) + return trajectory_point_.Get(index); +} +inline ::apollo::prediction::TrajectoryPoint* Trajectory::add_trajectory_point() { + // @@protoc_insertion_point(field_add:apollo.prediction.Trajectory.trajectory_point) + return trajectory_point_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::prediction::TrajectoryPoint >& +Trajectory::trajectory_point() const { + // @@protoc_insertion_point(field_list:apollo.prediction.Trajectory.trajectory_point) + return trajectory_point_; +} + +// ------------------------------------------------------------------- + +// PredictionObstacle + +// .apollo.perception.PerceptionObstacle perception_obstacle = 1; +inline bool PredictionObstacle::has_perception_obstacle() const { + return this != internal_default_instance() && perception_obstacle_ != NULL; +} +inline const ::apollo::perception::PerceptionObstacle& PredictionObstacle::_internal_perception_obstacle() const { + return *perception_obstacle_; +} +inline const ::apollo::perception::PerceptionObstacle& PredictionObstacle::perception_obstacle() const { + const ::apollo::perception::PerceptionObstacle* p = perception_obstacle_; + // @@protoc_insertion_point(field_get:apollo.prediction.PredictionObstacle.perception_obstacle) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::perception::_PerceptionObstacle_default_instance_); +} +inline ::apollo::perception::PerceptionObstacle* PredictionObstacle::release_perception_obstacle() { + // @@protoc_insertion_point(field_release:apollo.prediction.PredictionObstacle.perception_obstacle) + + ::apollo::perception::PerceptionObstacle* temp = perception_obstacle_; + perception_obstacle_ = NULL; + return temp; +} +inline ::apollo::perception::PerceptionObstacle* PredictionObstacle::mutable_perception_obstacle() { + + if (perception_obstacle_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::perception::PerceptionObstacle>(GetArenaNoVirtual()); + perception_obstacle_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.prediction.PredictionObstacle.perception_obstacle) + return perception_obstacle_; +} +inline void PredictionObstacle::set_allocated_perception_obstacle(::apollo::perception::PerceptionObstacle* perception_obstacle) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(perception_obstacle_); + } + if (perception_obstacle) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + perception_obstacle = ::google::protobuf::internal::GetOwnedMessage( + message_arena, perception_obstacle, submessage_arena); + } + + } else { + + } + perception_obstacle_ = perception_obstacle; + // @@protoc_insertion_point(field_set_allocated:apollo.prediction.PredictionObstacle.perception_obstacle) +} + +// double time_stamp = 2; +inline void PredictionObstacle::clear_time_stamp() { + time_stamp_ = 0; +} +inline double PredictionObstacle::time_stamp() const { + // @@protoc_insertion_point(field_get:apollo.prediction.PredictionObstacle.time_stamp) + return time_stamp_; +} +inline void PredictionObstacle::set_time_stamp(double value) { + + time_stamp_ = value; + // @@protoc_insertion_point(field_set:apollo.prediction.PredictionObstacle.time_stamp) +} + +// double predicted_period = 3; +inline void PredictionObstacle::clear_predicted_period() { + predicted_period_ = 0; +} +inline double PredictionObstacle::predicted_period() const { + // @@protoc_insertion_point(field_get:apollo.prediction.PredictionObstacle.predicted_period) + return predicted_period_; +} +inline void PredictionObstacle::set_predicted_period(double value) { + + predicted_period_ = value; + // @@protoc_insertion_point(field_set:apollo.prediction.PredictionObstacle.predicted_period) +} + +// repeated .apollo.prediction.Trajectory trajectory = 4; +inline int PredictionObstacle::trajectory_size() const { + return trajectory_.size(); +} +inline void PredictionObstacle::clear_trajectory() { + trajectory_.Clear(); +} +inline ::apollo::prediction::Trajectory* PredictionObstacle::mutable_trajectory(int index) { + // @@protoc_insertion_point(field_mutable:apollo.prediction.PredictionObstacle.trajectory) + return trajectory_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::prediction::Trajectory >* +PredictionObstacle::mutable_trajectory() { + // @@protoc_insertion_point(field_mutable_list:apollo.prediction.PredictionObstacle.trajectory) + return &trajectory_; +} +inline const ::apollo::prediction::Trajectory& PredictionObstacle::trajectory(int index) const { + // @@protoc_insertion_point(field_get:apollo.prediction.PredictionObstacle.trajectory) + return trajectory_.Get(index); +} +inline ::apollo::prediction::Trajectory* PredictionObstacle::add_trajectory() { + // @@protoc_insertion_point(field_add:apollo.prediction.PredictionObstacle.trajectory) + return trajectory_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::prediction::Trajectory >& +PredictionObstacle::trajectory() const { + // @@protoc_insertion_point(field_list:apollo.prediction.PredictionObstacle.trajectory) + return trajectory_; +} + +// ------------------------------------------------------------------- + +// PredictionObstacles + +// .apollo.common.Header header = 1; +inline bool PredictionObstacles::has_header() const { + return this != internal_default_instance() && header_ != NULL; +} +inline const ::apollo::common::Header& PredictionObstacles::_internal_header() const { + return *header_; +} +inline const ::apollo::common::Header& PredictionObstacles::header() const { + const ::apollo::common::Header* p = header_; + // @@protoc_insertion_point(field_get:apollo.prediction.PredictionObstacles.header) + return p != NULL ? *p : *reinterpret_cast( + &::apollo::common::_Header_default_instance_); +} +inline ::apollo::common::Header* PredictionObstacles::release_header() { + // @@protoc_insertion_point(field_release:apollo.prediction.PredictionObstacles.header) + + ::apollo::common::Header* temp = header_; + header_ = NULL; + return temp; +} +inline ::apollo::common::Header* PredictionObstacles::mutable_header() { + + if (header_ == NULL) { + auto* p = CreateMaybeMessage<::apollo::common::Header>(GetArenaNoVirtual()); + header_ = p; + } + // @@protoc_insertion_point(field_mutable:apollo.prediction.PredictionObstacles.header) + return header_; +} +inline void PredictionObstacles::set_allocated_header(::apollo::common::Header* header) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == NULL) { + delete reinterpret_cast< ::google::protobuf::MessageLite*>(header_); + } + if (header) { + ::google::protobuf::Arena* submessage_arena = NULL; + if (message_arena != submessage_arena) { + header = ::google::protobuf::internal::GetOwnedMessage( + message_arena, header, submessage_arena); + } + + } else { + + } + header_ = header; + // @@protoc_insertion_point(field_set_allocated:apollo.prediction.PredictionObstacles.header) +} + +// repeated .apollo.prediction.PredictionObstacle prediction_obstacle = 2; +inline int PredictionObstacles::prediction_obstacle_size() const { + return prediction_obstacle_.size(); +} +inline void PredictionObstacles::clear_prediction_obstacle() { + prediction_obstacle_.Clear(); +} +inline ::apollo::prediction::PredictionObstacle* PredictionObstacles::mutable_prediction_obstacle(int index) { + // @@protoc_insertion_point(field_mutable:apollo.prediction.PredictionObstacles.prediction_obstacle) + return prediction_obstacle_.Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField< ::apollo::prediction::PredictionObstacle >* +PredictionObstacles::mutable_prediction_obstacle() { + // @@protoc_insertion_point(field_mutable_list:apollo.prediction.PredictionObstacles.prediction_obstacle) + return &prediction_obstacle_; +} +inline const ::apollo::prediction::PredictionObstacle& PredictionObstacles::prediction_obstacle(int index) const { + // @@protoc_insertion_point(field_get:apollo.prediction.PredictionObstacles.prediction_obstacle) + return prediction_obstacle_.Get(index); +} +inline ::apollo::prediction::PredictionObstacle* PredictionObstacles::add_prediction_obstacle() { + // @@protoc_insertion_point(field_add:apollo.prediction.PredictionObstacles.prediction_obstacle) + return prediction_obstacle_.Add(); +} +inline const ::google::protobuf::RepeatedPtrField< ::apollo::prediction::PredictionObstacle >& +PredictionObstacles::prediction_obstacle() const { + // @@protoc_insertion_point(field_list:apollo.prediction.PredictionObstacles.prediction_obstacle) + return prediction_obstacle_; +} + +// .apollo.perception.PerceptionErrorCode perception_error_code = 3; +inline void PredictionObstacles::clear_perception_error_code() { + perception_error_code_ = 0; +} +inline ::apollo::perception::PerceptionErrorCode PredictionObstacles::perception_error_code() const { + // @@protoc_insertion_point(field_get:apollo.prediction.PredictionObstacles.perception_error_code) + return static_cast< ::apollo::perception::PerceptionErrorCode >(perception_error_code_); +} +inline void PredictionObstacles::set_perception_error_code(::apollo::perception::PerceptionErrorCode value) { + + perception_error_code_ = value; + // @@protoc_insertion_point(field_set:apollo.prediction.PredictionObstacles.perception_error_code) +} + +#ifdef __GNUC__ + #pragma GCC diagnostic pop +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + + +// @@protoc_insertion_point(namespace_scope) + +} // namespace prediction +} // namespace apollo + +// @@protoc_insertion_point(global_scope) + +#endif // PROTOBUF_INCLUDED_apollo_5fmsgs_2fproto_2fprediction_2fprediction_5fobstacle_2eproto diff --git a/apollo_msgs/package.xml b/apollo_msgs/package.xml new file mode 100644 index 0000000..6b36d24 --- /dev/null +++ b/apollo_msgs/package.xml @@ -0,0 +1,20 @@ + + + apollo_msgs + 0.0.0 + The apollo_msgs package + forrest + TODO + + catkin + roscpp + roscpp + roscpp + + + + + + + + diff --git a/apollo_msgs/proto/apollo_msgs/proto/canbus/chassis.proto b/apollo_msgs/proto/apollo_msgs/proto/canbus/chassis.proto new file mode 100644 index 0000000..a8e91c7 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/canbus/chassis.proto @@ -0,0 +1,106 @@ +syntax = "proto3"; + +package apollo.canbus; + +import "apollo_msgs/proto/common/header.proto"; + +message Signal { + enum TurnSignal { + TURN_NONE = 0; + TURN_LEFT = 1; + TURN_RIGHT = 2; + }; + TurnSignal turn_signal = 1; + // lights enable command + bool high_beam = 2; + bool low_beam = 3; + bool horn = 4; + bool emergency_light = 5; +} + +// next id :28 +message Chassis { + enum DrivingMode { + COMPLETE_MANUAL = 0; // human drive + COMPLETE_AUTO_DRIVE = 1; + AUTO_STEER_ONLY = 2; // only steer + AUTO_SPEED_ONLY = 3; // include throttle and brake + + // security mode when manual intervention happens, only response status + EMERGENCY_MODE = 4; + } + + // FIXME: To be merged with common::ErrorCode + enum ErrorCode { + NO_ERROR = 0; + + CMD_NOT_IN_PERIOD = 1; // control cmd not in period + + // car chassis report error, like steer, brake, throttle, gear fault + CHASSIS_ERROR = 2; + + MANUAL_INTERVENTION = 3; // human manual intervention + + // receive car chassis can frame not in period + CHASSIS_CAN_NOT_IN_PERIOD = 4; + + UNKNOWN_ERROR = 5; + } + + enum GearPosition { + GEAR_NEUTRAL = 0; + GEAR_DRIVE = 1; + GEAR_REVERSE = 2; + GEAR_PARKING = 3; + GEAR_LOW = 4; + GEAR_INVALID = 5; + GEAR_NONE = 6; + } + + bool engine_started = 3; + // Engine speed in RPM. + float engine_rpm = 4; + // Vehicle Speed in meters per second. + float speed_mps = 5; + // Vehicle odometer in meters. + float odometer_m = 6; + // Fuel range in meters. + int32 fuel_range_m = 7; + // Real throttle location in [%], ranging from 0 to 100. + float throttle_percentage = 8; + // Real brake location in [%], ranging from 0 to 100. + float brake_percentage = 9; + // Real gear location. + // int32 gear_location = 10; deprecated use enum replace this [id 23] + // Real steering location in [%], ranging from 0 to 100. + float steering_percentage = 11; + // Applied steering torque in [Nm]. + float steering_torque_nm = 12; + + // Parking brake status. + bool parking_brake = 13; + + + bool wiper = 19; + bool disengage_status = 20; + DrivingMode driving_mode = 21; + ErrorCode error_code = 22; + GearPosition gear_location = 23; + + // timestamp for steering module + double steering_timestamp = 24; // In seconds, with 1e-6 accuracy + + // chassis also needs it own sending timestamp + apollo.common.Header header = 25; + + int32 chassis_error_mask = 26; + + Signal signal = 27; + + // Light signals. + bool high_beam_signal = 14; + bool low_beam_signal = 15; + bool left_turn_signal = 16; + bool right_turn_signal = 17; + bool horn = 18; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/canbus/chassis_detail.proto b/apollo_msgs/proto/apollo_msgs/proto/canbus/chassis_detail.proto new file mode 100644 index 0000000..b390133 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/canbus/chassis_detail.proto @@ -0,0 +1,503 @@ +syntax = "proto3"; + +package apollo.canbus; + +import "apollo_msgs/proto/canbus/chassis.proto"; + +message ChassisDetail { + enum Type { + QIRUI_EQ_15 = 0; + CHANGAN_RUICHENG = 1; + } + Type car_type = 1; // car type + BasicInfo basic = 2; // basic info + Safety safety = 3; // safety + Gear gear = 4; // gear + Ems ems = 5; // engine manager system + Esp esp = 6; // Electronic Stability Program + Gas gas = 7; // gas pedal + Epb epb = 8; // Electronic parking brake + Brake brake = 9; // brake pedal + Deceleration deceleration = 10; // deceleration + VehicleSpd vehicle_spd = 11; // vehicle speed + Eps eps = 12; // Electronic Power Steering + Light light = 13; // Light + Battery battery = 14; // Battery info + CheckResponseSignal check_response = 15; +} + +// CheckResponseSignal +message CheckResponseSignal { + bool is_eps_online = 1; // byd:0x34C qirui:0x505 + bool is_epb_online = 2; // byd:0x218 + bool is_esp_online = 3; // byd:0x122 qirui:0x451 + bool is_vtog_online = 4; // byd:0x242 + bool is_scu_online = 5; // byd:0x35C + bool is_switch_online = 6; // byd:0x133 + bool is_vcu_online = 7; // qirui:0x400 +} + +// Battery +message Battery { + double battery_percent = 1; // unit:%, battery percentage left + // lincoln fuellevel 72 + double fuel_level = 2; +} + +// light +message Light { + enum TurnLightType { + TURN_LIGHT_OFF = 0; + TURN_LEFT_ON = 1; + TURN_RIGHT_ON = 2; + TURN_LIGHT_ON = 3; + } + enum LampType { + BEAM_OFF = 0; + HIGH_BEAM_ON = 1; + LOW_BEAM_ON = 2; + } + enum LincolnLampType { + BEAM_NULL = 0; + BEAM_FLASH_TO_PASS = 1; + BEAM_HIGH = 2; + BEAM_INVALID = 3; + } + enum LincolnWiperType { + WIPER_OFF = 0; + WIPER_AUTO_OFF = 1; + WIPER_OFF_MOVING = 2; + WIPER_MANUAL_OFF = 3; + WIPER_MANUAL_ON = 4; + WIPER_MANUAL_LOW = 5; + WIPER_MANUAL_HIGH = 6; + WIPER_MIST_FLICK = 7; + WIPER_WASH = 8; + WIPER_AUTO_LOW = 9; + WIPER_AUTO_HIGH = 10; + WIPER_COURTESY_WIPE = 11; + WIPER_AUTO_ADJUST = 12; + WIPER_RESERVED = 13; + WIPER_STALLED = 14; + WIPER_NO_DATA = 15; + } + enum LincolnAmbientType { + AMBIENT_DARK = 0; + AMBIENT_LIGHT = 1; + AMBIENT_TWILIGHT = 2; + AMBIENT_TUNNEL_ON = 3; + AMBIENT_TUNNEL_OFF = 4; + AMBIENT_INVALID = 5; + AMBIENT_NO_DATA = 7; + } + + TurnLightType turn_light_type = 1; + LampType lamp_type = 2; + bool is_brake_lamp_on = 3; + // byd switch 133 + bool is_auto_light = 4; + int32 wiper_gear = 5; + int32 lotion_gear = 6; + bool is_horn_on = 7; + + // lincoln misc 69 + LincolnLampType lincoln_lamp_type = 8; + LincolnWiperType lincoln_wiper = 9; + LincolnAmbientType lincoln_ambient = 10; +} + +// Electrical Power Steering +message Eps { + enum Type { + NOT_AVAILABLE = 0; + READY = 1; + ACTIVE = 2; + INVALID = 3; + } + // changan: eps 2a0 + bool is_eps_fail = 1; + // eps 2a0 + Type eps_control_state = 2; // for changan to control steering + double eps_driver_hand_torq = 3; // unit:Nm + + bool is_steering_angle_valid = 4; + double steering_angle = 5; // unit:degree + double steering_angle_spd = 6; // unit:degree/s + + // byd sas 11f + bool is_trimming_status = 7; + bool is_calibration_status = 8; + bool is_failure_status = 9; + int32 allow_enter_autonomous_mode = 10; + int32 current_driving_mode = 11; + + // lincoln steering 65 + double steering_angle_cmd = 12; + double vehicle_speed = 13; + double epas_torque = 14; + bool steering_enabled = 15; + bool driver_override = 16; + bool driver_activity = 17; + bool watchdog_fault = 18; + bool channel_1_fault = 19; + bool channel_2_fault = 20; + bool calibration_fault = 21; + bool connector_fault = 22; + + double timestamp_65 = 23; + + // lincoln version 7f + int32 major_version = 24; + int32 minor_version = 25; + int32 build_number = 26; +} + +message VehicleSpd { + enum Type { + FORWARD = 0; + BACKWARD = 1; + STANDSTILL = 2; + INVALID = 3; + } + // esp 277 + bool is_vehicle_standstill = 1; + + // esp 218 + bool is_vehicle_spd_valid = 2; + double vehicle_spd = 3; // unit:m/s + // esp 208 + bool is_wheel_spd_rr_valid = 4; + Type wheel_direction_rr = 5; + double wheel_spd_rr = 6; + bool is_wheel_spd_rl_valid = 7; + Type wheel_direction_rl = 8; + double wheel_spd_rl = 9; + bool is_wheel_spd_fr_valid = 10; + Type wheel_direction_fr = 11; + double wheel_spd_fr = 12; + bool is_wheel_spd_fl_valid = 13; + Type wheel_direction_fl = 14; + double wheel_spd_fl = 15; + + // byd esp 222 + bool is_yaw_rate_valid = 16; + double yaw_rate = 17; + double yaw_rate_offset = 18; + + // byd esp 223 + bool is_ax_valid = 19; + double ax = 20; + double ax_offset = 21; + bool is_ay_valid = 22; + double ay = 23; + double ay_offset = 24; + + // lincoln accel 6b + double lat_acc = 25; + double long_acc = 26; + double vert_acc = 27; + + // lincoln gyro 6c + double roll_rate = 28; + + // lincoln brakeinfo 74 + double acc_est = 29; + + // lincoln wheelspeed 6a + double timestamp_sec = 30; +} + +message Deceleration { + // esp 277 + bool is_deceleration_available = + 1; // for changan to send deceleration value + bool is_deceleration_active = + 2; // for changan to send deceleration value + + double deceleration = 3; + + double is_evb_fail = 4; + double evb_pressure = 5; // mpa, 0~25.5 + + double brake_pressure = 6; + double brake_pressure_spd = 7; +} + +message Brake { + enum HSAStatusType { + HSA_INACTIVE = 0; + HSA_FINDING_GRADIENT = 1; + HSA_ACTIVE_PRESSED = 2; + HSA_ACTIVE_RELEASED = 3; + HSA_FAST_RELEASE = 4; + HSA_SLOW_RELEASE = 5; + HSA_FAILED = 6; + HSA_UNDEFINED = 7; + } + enum HSAModeType { + HSA_OFF = 0; + HSA_AUTO = 1; + HSA_MANUAL = 2; + HSA_MODE_UNDEFINED = 3; + } + // ems 255 + bool is_brake_pedal_pressed = 1 + ; // only manual brake + // esp 277 + bool is_brake_force_exist = + 2; // no matter auto mode brake or manual brake + bool is_brake_over_heat = 3; + + bool is_hand_brake_on = 4; // hand brake + double brake_pedal_position = 5; + + // byd vtog 342 + bool is_brake_valid = 6; + + // lincoln brake 61 + double brake_input = 7; + double brake_cmd = 8; + double brake_output = 9; + bool boo_input = 10; + bool boo_cmd = 11; + bool boo_output = 12; + bool watchdog_applying_brakes = 13; + int32 watchdog_source = 14; + bool brake_enabled = 15; + bool driver_override = 16; + bool driver_activity = 17; + bool watchdog_fault = 18; + bool channel_1_fault = 19; + bool channel_2_fault = 20; + bool boo_fault = 21; + bool connector_fault = 22; + + // lincoln brakeinfo 74 + int32 brake_torque_req = 23; + HSAStatusType hsa_status = 24; + int32 brake_torque_act = 25; + HSAModeType hsa_mode = 26; + int32 wheel_torque_act = 27; + + // lincoln version 7f + int32 major_version = 28; + int32 minor_version = 29; + int32 build_number = 30; +} + +// Electrical Parking Brake +message Epb { + enum PBrakeType { + PBRAKE_OFF = 0; + PBRAKE_TRANSITION = 1; + PBRAKE_ON = 2; + PBRAKE_FAULT = 3; + } + // epb 256 + bool is_epb_error = 1; + bool is_epb_released = 2; + + // byd epb 218 + int32 epb_status = 3; + + // lincoln brakeinfo 74 + PBrakeType parking_brake_status = 4; +} + +message Gas { + // ems 255 + bool is_gas_pedal_error = 1; + // ems 26a + bool is_gas_pedal_pressed_more = 2; // more than auto mode gas torq + double gas_pedal_position = 3; // manual gas + // byd vtog 342 + bool is_gas_valid = 4; + + // lincoln throttle 63 + double throttle_input = 5; + double throttle_cmd = 6; + double throttle_output = 7; + int32 watchdog_source = 8; + bool throttle_enabled = 9; + bool driver_override = 10; + bool driver_activity = 11; + bool watchdog_fault = 12; + bool channel_1_fault = 13; + bool channel_2_fault = 14; + bool connector_fault = 15; + + // lincoln throttleinfo 75 + double accelerator_pedal = 16; + double accelerator_pedal_rate = 17; + + // lincoln version 7f + int32 major_version = 18; + int32 minor_version = 19; + int32 build_number = 20; +} + +// Electronic Stability Program +message Esp { + // esp 277 + bool is_esp_acc_error = 1; // for changan to control car + + // esp 218 + bool is_esp_on = 2; + bool is_esp_active = 3; + bool is_abs_error = 4; + bool is_abs_active = 5; + bool is_tcsvdc_fail = 6; + + // lincoln brakeinfo 74 + bool is_abs_enabled = 7; + bool is_stab_active = 8; + bool is_stab_enabled = 9; + bool is_trac_active = 10; + bool is_trac_enabled = 11; +} + +// Engine Manager System +message Ems { + enum Type { + STOP = 0; + CRANK = 1; + RUNNING = 2; + INVALID = 3; + } + // ems 26a + bool is_engine_acc_available = 1; // for changan to control car + bool is_engine_acc_error = 2; // for changan to control car + + // ems 265 + Type engine_state = 3; + double max_engine_torq_percent = + 4; // for engine torq control, unit:% + double min_engine_torq_percent = + 5; // for engine torq control, unit:% + int32 base_engine_torq_constant = + 6; // for engine torq control, unit:Nm + + // ems 255 + bool is_engine_speed_error = 7; + double engine_speed = 8; + + // byd vtog 241 + int32 engine_torque = 9; + // byd vtog 242 + bool is_over_engine_torque = 10; + + // lincoln mkz throttleinfo 75 + double engine_rpm = 11; +} + +message Gear { + // tcu 268 + bool is_shift_position_valid = 1; + // chanan: tcu 268 + Chassis.GearPosition gear_state = 2; + // lincoln gear 67 + bool driver_override = 3; + Chassis.GearPosition gear_cmd = 4; + bool canbus_fault = 5; +} + +message Safety { + // ip 270 + bool is_driver_car_door_close = 1; + // sas 50 + bool is_driver_buckled = 2; + + // byd sws 4a8 + int32 emergency_button = 3; + + // qirui:403 + // when car chassis error, like system fault, or warning report + bool has_error = 4; + bool is_motor_invertor_fault = 5; + bool is_system_fault = 6; + bool is_power_battery_fault = 7; + bool is_motor_invertor_over_temperature = 8; + bool is_small_battery_charge_discharge_fault = 9; + int32 driving_mode = 10; + + // lincoln misc 69 + bool is_passenger_door_open = 11; + bool is_rearleft_door_open = 12; + bool is_rearright_door_open = 13; + bool is_hood_open = 14; + bool is_trunk_open = 15; + bool is_passenger_detected = 16; + bool is_passenger_airbag_enabled = 17; + bool is_passenger_buckled = 18; + + // lincoln tirepressure 71 + int32 front_left_tire_press = 19; + int32 front_right_tire_press = 20; + int32 rear_left_tire_press = 21; + int32 rear_right_tire_press = 22; + Chassis.DrivingMode car_driving_mode = 23; +} + +message BasicInfo { + enum Type { + OFF = 0; + ACC = 1; + ON = 2; + START = 3; + INVALID = 4; + } + enum GpsQuality { + FIX_NO = 0; + FIX_2D = 1; + FIX_3D = 2; + FIX_INVALID = 3; + } + bool is_auto_mode = 1; + Type power_state = 2; + bool is_air_bag_deployed = 3; + double odo_meter = 4; // odo meter, unit:km + double drive_range = + 5; // the meter left when drive continuously, unit:km + bool is_system_error = 6; + bool is_human_interrupt = 7; // human interrupt + + // lincoln misc 69 + bool acc_on_button = 8; // acc on button pressed + bool acc_off_button = 9; + bool acc_res_button = 10; + bool acc_cancel_button = 11; + bool acc_on_off_button = 12; + bool acc_res_cancel_button = 13; + bool acc_inc_spd_button = 14; + bool acc_dec_spd_button = 15; + bool acc_inc_gap_button = 16; + bool acc_dec_gap_button = 17; + bool lka_button = 18; + bool canbus_fault = 19; + + // lincoln gps 6d + double latitude = 20; + double longitude = 21; + bool gps_valid = 22; + + // lincoln gps 6e + int32 year = 23; + int32 month = 24; + int32 day = 25; + int32 hours = 26; + int32 minutes = 27; + int32 seconds = 28; + double compass_direction = 29; + double pdop = 30; + bool is_gps_fault = 31; + bool is_inferred = 32; + + // lincoln gps 6f + double altitude = 33; + double heading = 34; + double hdop = 35; + double vdop = 36; + GpsQuality quality = 37; + int32 num_satellites = 38; + double gps_speed = 39; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/common/adapter_config.proto b/apollo_msgs/proto/apollo_msgs/proto/common/adapter_config.proto new file mode 100644 index 0000000..15510da --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/common/adapter_config.proto @@ -0,0 +1,41 @@ +syntax = "proto3"; + +package apollo.common.adapter; + +// Property of a certain Input/Output that will be used by a module. +message AdapterConfig { + enum MessageType { + POINT_CLOUD = 0; + GPS = 1; + IMU = 2; + CHASSIS = 3; + LOCALIZATION = 4; + PLANNING_TRAJECTORY = 5; + MONITOR = 6; + PAD = 7; + CONTROL_COMMAND = 8; + PREDICTION = 9; + PERCEPTION_OBSTACLES = 10; + TRAFFIC_LIGHT_DETECTION = 11; + CHASSIS_DETAIL = 12; + DECISION = 13; + CANBUS = 14; + } + enum Mode { + RECEIVE_ONLY = 0; + PUBLISH_ONLY = 1; + DUPLEX = 2; + } + MessageType type = 1; + Mode mode = 2; + // The max number of received messages to keep in the adapter, this field + // is not useful for PUBLISH_ONLY mode messages. + int32 message_history_limit = 3; +} + +// A config to specify which messages a certain module would consume and +// produce. +message AdapterManagerConfig { + repeated AdapterConfig config = 1; + bool is_ros = 2; // Whether the message comes from ROS +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/common/config_extrinsics.proto b/apollo_msgs/proto/apollo_msgs/proto/common/config_extrinsics.proto new file mode 100644 index 0000000..eb58556 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/common/config_extrinsics.proto @@ -0,0 +1,21 @@ +syntax = "proto3"; + +package apollo.common.config; + +import "apollo_msgs/proto/common/geometry.proto"; + +message Transform { + bytes source_frame = 1; // Also known as "frame_id." + + bytes target_frame = 2; // Also known as "child_frame_id." + + // Position of target in the source frame. + Point3D translation = 3; + + // Activate rotation from the source frame to the target frame. + Quaternion rotation = 4; +} + +message Extrinsics { + repeated Transform tansforms = 1; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/common/error_code.proto b/apollo_msgs/proto/apollo_msgs/proto/common/error_code.proto new file mode 100644 index 0000000..8eda819 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/common/error_code.proto @@ -0,0 +1,30 @@ +syntax = "proto3"; + +package apollo.common; + +// Error codes enum for API's categorized by modules. +enum ErrorCode { + // No error, reutrns on success. + OK = 0; + + // Control module error codes start from here. + CONTROL_ERROR = 1000; + CONTROL_INIT_ERROR = 1001; + CONTROL_COMPUTE_ERROR = 1002; + + // Canbus module error codes start from here. + CANBUS_ERROR = 2000; + CAN_CLIENT_ERROR_BASE = 2100; + CAN_CLIENT_ERROR_OPEN_DEVICE_FAILED = 2101; + CAN_CLIENT_ERROR_FRAME_NUM = 2102; + CAN_CLIENT_ERROR_SEND_FAILED = 2103; + CAN_CLIENT_ERROR_RECV_FAILED = 2104; + + // Localization module error codes start from here. + LOCALIZATION_ERROR = 3000; +} + +message StatusPb { + ErrorCode error_code = 1; + string msg = 2; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/common/geometry.proto b/apollo_msgs/proto/apollo_msgs/proto/common/geometry.proto new file mode 100644 index 0000000..ca37379 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/common/geometry.proto @@ -0,0 +1,48 @@ +syntax = "proto3"; + +package apollo.common; + +// A point in the map reference frame. The map defines an origin, whose coordinate is (0, 0, 0). +// Most modules, including localization, perception, and prediction, generate results based on the +// map reference frame. +// Currently, the map uses Universal Transverse Mercator (UTM) projection. See the link below for +// the definition of map origin. +// https://en.wikipedia.org/wiki/Universal_Transverse_Mercator_coordinate_system +// The z field of PointENU can be omitted. If so, it is a 2D location and we do not care its height. +message PointENU { + double x = 1; // East from the origin, in meters. + double y = 2; // North from the origin, in meters. + double z = 3; // Up from the WGS-84 ellipsoid, in meters. +} + +// A point in the global reference frame. Similar to PointENU, PointLLH allows omitting the height +// field for representing a 2D location. +message PointLLH { + double lon = 1; // Longitude in degrees, ranging from -180 to 180. + double lat = 2; // Latitude in degrees, ranging from -90 to 90. + double height = 3; // WGS-84 ellipsoid height in meters. +} + +// A general 2D point. Its meaning and units depend on context, and must be explained in comments. +message Point2D { + double x = 1; + double y = 2; +} + +// A general 3D point. Its meaning and units depend on context, and must be explained in comments. +message Point3D { + double x = 1; + double y = 2; + double z = 3; +} + +// A unit quaternion that represents a spatial rotation. See the link below for details. +// https://en.wikipedia.org/wiki/Quaternions_and_spatial_rotation +// The scalar part qw can be omitted. In this case, qw should be calculated by +// qw = sqrt(1 - qx * qx - qy * qy - qz * qz). +message Quaternion { + double qx = 1; + double qy = 2; + double qz = 3; + double qw = 4; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/common/gnss_status.proto b/apollo_msgs/proto/apollo_msgs/proto/common/gnss_status.proto new file mode 100644 index 0000000..131f793 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/common/gnss_status.proto @@ -0,0 +1,41 @@ + +syntax = "proto3"; + +package apollo.common.gnss_status; + +import "apollo_msgs/proto/common/header.proto"; + +message StreamStatus { + apollo.common.Header header = 1; + enum Type { + DISCONNECTED = 0; + CONNECTED = 1; + } + + Type ins_stream_type = 2; + Type rtk_stream_in_type = 3; + Type rtk_stream_out_type = 4; +} + +message InsStatus { + apollo.common.Header header = 1; + + enum Type { + INVALID = 0; // Invalid solution due to insufficient observations, no initial GNSS, ... + + // Use with caution. The covariance matrix may be unavailable or incorrect. + CONVERGING = 1; // High-variance result due to aligning, insufficient vehicle dynamics, ... + + // Safe to use. The INS has fully converged. + GOOD = 2; + } + Type type = 2; +} + +message GnssStatus { + apollo.common.Header header = 1; + bool solution_completed = 2; + uint32 solution_status = 3; + uint32 position_type = 4; + int32 num_sats = 5; // Number of satellites in position solution. +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/common/header.proto b/apollo_msgs/proto/apollo_msgs/proto/common/header.proto new file mode 100644 index 0000000..b134c80 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/common/header.proto @@ -0,0 +1,32 @@ +syntax = "proto3"; + +package apollo.common; + +import "apollo_msgs/proto/common/error_code.proto"; + +message Header { + // Message publishing time in seconds. It is recommended to obtain timestamp_sec from + // ros::Time::now(), right before calling SerializeToString() and publish(). + double timestamp_sec = 1; + + // Module name. + string module_name = 2; + + // Sequence number for each message. Each module maintains its own counter for sequence_num, + // always starting from 0 on boot. + uint32 sequence_num = 3; + + // Lidar Sensor timestamp for nano-second. + uint64 lidar_timestamp = 4; + + // Camera Sensor timestamp for nano-second. + uint64 camera_timestamp = 5; + + // Radar Sensor timestamp for nano-second. + uint64 radar_timestamp = 6; + + // data version + uint32 version = 7; + + StatusPb status = 8; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/common/monitor.proto b/apollo_msgs/proto/apollo_msgs/proto/common/monitor.proto new file mode 100644 index 0000000..4fc305d --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/common/monitor.proto @@ -0,0 +1,37 @@ +syntax = "proto3"; + +package apollo.common.monitor; + +import "apollo_msgs/proto/common/header.proto"; + +message MonitorMessageItem { + enum MessageSource { + UNKNOWN = 0; + CANBUS = 1; + CONTROL = 2; + DECISION = 3; + LOCALIZATION = 4; + PLANNING = 5; + PREDICTION = 6; + SIMULATOR = 7; + HWSYS = 8; + } + + MessageSource source = 1; + + string msg = 2; + + enum LogLevel { + INFO = 0; + WARN = 1; + ERROR = 2; + FATAL = 3; + } + LogLevel log_level = 3; +} + +message MonitorMessage { + apollo.common.Header header = 1; + + repeated MonitorMessageItem item = 2; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/common/vehicle_config.proto b/apollo_msgs/proto/apollo_msgs/proto/common/vehicle_config.proto new file mode 100644 index 0000000..970f0b2 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/common/vehicle_config.proto @@ -0,0 +1,44 @@ +syntax = "proto3"; + +package apollo.common.config; + +import "apollo_msgs/proto/common/header.proto"; +import "apollo_msgs/proto/common/config_extrinsics.proto"; + +// Vehicle parameters shared among several modules. +// By default, all are measured with the SI units (meters, meters per second, +// etc.). +message VehicleParam { + // Car center point is car reference point, i.e., center of rear axle. + double front_edge_to_center = 1; + double back_edge_to_center = 2; + double left_edge_to_center = 3; + double right_edge_to_center = 4; + + double length = 5; + double width = 6; + double height = 7; + + double min_turn_radius = 8; + double max_acceleration = 9; + double max_deceleration = 10; + + // The following items are used to compute trajectory constraints in planning. + // vehicle max steer angle + double max_steer_angle = 11; + // vehicle max steer rate; how fast can the steering wheel turn. + double max_steer_angle_rate = 12; + // ratio between the turn of steering wheel and the turn of wheels + double steer_ratio = 13; + // the distance between the front and back wheels + double wheel_base = 14; + // Tire effective rolling radius (vertical distance between the wheel center + // and the ground). + double wheel_rolling_radius = 15; +} + +message VehicleConfig { + apollo.common.Header header = 1; + VehicleParam vehicle_param = 2; + Extrinsics extrinsics = 3; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/control/calibration_table.proto b/apollo_msgs/proto/apollo_msgs/proto/control/calibration_table.proto new file mode 100644 index 0000000..8080ac2 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/control/calibration_table.proto @@ -0,0 +1,13 @@ +syntax = "proto3"; + +package apollo.control.calibrationtable; + +message ControlCalibrationTable { + repeated ControlCalibrationInfo calibration = 1; +} + +message ControlCalibrationInfo { + double speed = 1; + double acceleration = 2; + double command = 3; +} \ No newline at end of file diff --git a/apollo_msgs/proto/apollo_msgs/proto/control/control_cmd.proto b/apollo_msgs/proto/apollo_msgs/proto/control/control_cmd.proto new file mode 100644 index 0000000..8ded164 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/control/control_cmd.proto @@ -0,0 +1,115 @@ +syntax = "proto3"; +package apollo.control; + +import "apollo_msgs/proto/canbus/chassis.proto"; +import "apollo_msgs/proto/common/header.proto"; +import "apollo_msgs/proto/control/pad_msg.proto"; + +enum TurnSignal { + TURN_NONE = 0; + TURN_LEFT = 1; + TURN_RIGHT = 2; +} + +message LatencyStats { + double total_time_ms = 1; + repeated double controller_time_ms = 2; +} + +message ControlCommand { + apollo.common.Header header = 1; + // target throttle in percentage [0, 100] + double throttle = 3; + + // target brake in percentage [0, 100] + double brake = 4; + + // target steering rate, in percentage of full scale per second [-100, 100] + double steering_rate = 6; + + // target steerig angle, in percentage of full scalce [-100, 100] + double steering_target = 7; + + // parking brake engage. true: engaged + bool parking_brake = 8; + + // target speed, in km/h + double speed = 9; + + // target acceleration in m`s^-2 + double acceleration = 10; + + // model reset + bool reset_model = 16; + // engine on/off, true: engine on + bool engine_on_off = 17; + // completion percentage of trajectory planned in last cycle + double trajectory_fraction = 18; + apollo.canbus.Chassis.DrivingMode driving_mode = 19; + apollo.canbus.Chassis.GearPosition gear_location = 20; + + Debug debug = 22; + apollo.canbus.Signal signal = 23; + LatencyStats latency_stats = 24; + PadMessage pad_msg = 25; + + // deprecated fields + bool left_turn = 13; + bool right_turn = 14; + bool high_beam = 11; + bool low_beam = 12; + bool horn = 15; + TurnSignal turnsignal = 21; +} + +message SimpleLongitudinalDebug { + double station_reference = 1; + double station_error = 2; + double station_error_limited = 3; + double preview_station_error = 4; + double speed_reference = 5; + double speed_error = 6; + double speed_controller_input_limited = 7; + double preview_speed_reference = 8; + double preview_speed_error = 9; + double preview_acceleration_reference = 10; + double acceleration_cmd_closeloop = 11; + double acceleration_cmd = 12; + double acceleration_lookup = 13; + double speed_lookup = 14; + double calibration_value = 15; + double throttle_cmd = 16; + double brake_cmd = 17; + bool is_full_stop = 18; +} + +message SimpleLateralDebug { + double lateral_error = 1; + double ref_heading = 2; + double heading = 3; + double heading_error = 4; + double heading_error_rate = 5; + double lateral_error_rate = 6; + double curvature = 7; + double steer_angle = 8; + double steer_angle_feedforward = 9; + double steer_angle_lateral_contribution = 10; + double steer_angle_lateral_rate_contribution = 11; + double steer_angle_heading_contribution = 12; + double steer_angle_heading_rate_contribution = 13; + double steer_angle_feedback = 14; + double steering_position = 15; + double ref_speed = 16; +} + +message InputDebug { + apollo.common.Header localization_header = 1; + apollo.common.Header canbus_header = 2; + apollo.common.Header trajectory_header = 3; + } + +message Debug { + SimpleLongitudinalDebug simple_lon_debug = 1; + SimpleLateralDebug simple_lat_debug = 2; + InputDebug input_debug = 3; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/control/control_conf.proto b/apollo_msgs/proto/apollo_msgs/proto/control/control_conf.proto new file mode 100644 index 0000000..35f0957 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/control/control_conf.proto @@ -0,0 +1,34 @@ +syntax = "proto3"; + +package apollo.control; + +import "apollo_msgs/proto/canbus/chassis.proto"; +import "apollo_msgs/proto/control/pad_msg.proto"; +import "apollo_msgs/proto/control/lat_controller_conf.proto"; +import "apollo_msgs/proto/control/lon_controller_conf.proto"; + +message ControlConf { + enum ControllerType { + LAT_CONTROLLER = 0; + LON_CONTROLLER = 1; + }; + + double control_period = 1; + double max_planning_interval_sec = 2; + double max_planning_delay_threshold = 3; + // 0 - manual; 1 - auto_drive; 2 - speed_only; 3 - steer_only + apollo.canbus.Chassis.DrivingMode driving_mode = 4; + // 0: stop, at first should stop, then receive pad msg to start + apollo.control.DrivingAction action = 5; + double soft_estop_brake = 6; + repeated ControllerType active_controllers = 7; + int32 max_steering_percentage_allowed = 8; + double max_status_interval_sec = 9; + + apollo.control.LatControllerConf lat_controller_conf = 10; + apollo.control.LonControllerConf lon_controller_conf = 11; + + double trajectory_period = 12; + double chassis_period = 13; + double localization_period = 14; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/control/lat_controller_conf.proto b/apollo_msgs/proto/apollo_msgs/proto/control/lat_controller_conf.proto new file mode 100644 index 0000000..a19c0e6 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/control/lat_controller_conf.proto @@ -0,0 +1,23 @@ +syntax = "proto3"; + +package apollo.control; + +// simple optimal steer control param +message LatControllerConf { + double ts = 1; // sample time (dt) 0.01 now, configurable + int32 preview_window = 2; // preview window n, preview time = preview window * ts + double cf = 3; + double cr = 4; // N/rad + double wheelbase = 5; // meter + int32 mass_fl = 6; + int32 mass_fr = 7; + int32 mass_rl = 8; + int32 mass_rr = 9; + double eps = 10; // converge threshold for lqr solver + repeated double matrix_q = 11; // matrix_q size = 4 + preview_window + int32 cutoff_freq = 12; // cutoff frequency + int32 mean_filter_window_size = 13; // window size of mean filter + int32 steer_transmission_ratio = 14; // for a normal car, it should be in range[16, 18] + int32 steer_single_direction_max_degree = 15; // in degree + int32 max_iteration = 16; // maximum iteration for lqr solve +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/control/lon_controller_conf.proto b/apollo_msgs/proto/apollo_msgs/proto/control/lon_controller_conf.proto new file mode 100644 index 0000000..1267cde --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/control/lon_controller_conf.proto @@ -0,0 +1,40 @@ +syntax = "proto3"; + +package apollo.control; + +import "apollo_msgs/proto/control/calibration_table.proto"; + +message PidConf { + bool integrator_enable = 1; + double integrator_saturation_level = 2; + double kp = 3; + double ki = 4; + double kd = 5; +} + +message FilterConf { + int32 cutoff_freq = 1; +} + +// controller param +message LonControllerConf { + double ts = 1; // longitudinal controller sampling time + + double brake_deadzone = 2; + double throttle_deadzone = 3; + double speed_controller_input_limit = 4; + double station_error_limit = 5; + double preview_window = 6; + double standstill_acceleration = 7; + + PidConf station_pid_conf = 8; + PidConf low_speed_pid_conf = 9; + PidConf high_speed_pid_conf = 10; + double switch_speed = 11; // low/high speed controller switch speed + + FilterConf throttle_filter_conf = 12; + FilterConf brake_filter_conf = 13; + FilterConf acceleration_filter_conf = 14; + + calibrationtable.ControlCalibrationTable calibration_table = 15; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/control/pad_msg.proto b/apollo_msgs/proto/apollo_msgs/proto/control/pad_msg.proto new file mode 100644 index 0000000..f099fe5 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/control/pad_msg.proto @@ -0,0 +1,22 @@ +syntax = "proto3"; +package apollo.control; + +import "apollo_msgs/proto/common/header.proto"; +import "apollo_msgs/proto/canbus/chassis.proto"; + +enum DrivingAction { + STOP = 0; + START = 1; + RESET = 2; +}; + +message PadMessage { + // control mode, set mode according to low level defination + apollo.common.Header header = 1; + + // send driving mode to drive + apollo.canbus.Chassis.DrivingMode driving_mode = 2; + + // action in the driving_mode + DrivingAction action = 3; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/decision/decision.proto b/apollo_msgs/proto/apollo_msgs/proto/decision/decision.proto new file mode 100644 index 0000000..e5a7d4e --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/decision/decision.proto @@ -0,0 +1,317 @@ +syntax = "proto3"; + +package apollo.decision; + +import "apollo_msgs/proto/common/header.proto"; +import "apollo_msgs/proto/common/geometry.proto"; +import "apollo_msgs/proto/prediction/prediction_obstacle.proto"; +import "apollo_msgs/proto/canbus/chassis.proto"; + +message Range { + double start = 1; + double end = 2; +} + +message TargetLane { + // lane id + string id = 1; + double start_s = 2; // in meters + double end_s = 3; // in meters + double speed_limit = 4; // in m/s +} + +message ObjectIgnore { +} + +enum StopReasonCode { + STOP_REASON_HEAD_VEHICLE = 0; + STOP_REASON_DESTINATION = 1; + STOP_REASON_PEDESTRIAN = 2; + STOP_REASON_OBSTACLE = 3; + STOP_REASON_PREPARKING = 4; + STOP_REASON_SIGNAL = 100; + STOP_REASON_STOP_SIGN = 101; + STOP_REASON_YIELD_SIGN = 102; + STOP_REASON_CLEAR_ZONE = 103; + STOP_REASON_CROSSWALK = 104; +} + +message ObjectStop { + // stop at least distance_s before the object + double distance_s = 1; // in meters + Range preferred_distance_s = 2; // NOT SUPPORTED FIELD + StopReasonCode reason_code = 3; + apollo.common.PointENU stop_point = 4; // stop point +} + +message ObjectNudge { + // minimum lateral distance with the object + double distance_l = 1; // in meters + enum Type { + LEFT_NUDGE = 0; + RIGHT_NUDGE = 1; + }; + Type type = 2; + Range preferred_distance_l = 3; // NOT SUPPORTED FIELD +} + +message ObjectYield { + // minimum longitutional distance with the object + double distance_s = 1; // in meters + Range preferred_distance_s = 2; // NOT SUPPORTED FIELD + apollo.common.PointENU yield_point = 3; +} + +message ObjectFollow { + // minimum longitutional distance with the object + double distance_s = 1; // in meters + Range preferred_distance_s = 2; // NOT SUPPORTED FIELD + apollo.common.PointENU follow_point = 3; +} + +message ObjectOvertake { + // minimum longitutional distance with the object + double distance_s = 1; // in meters + Range preferred_distance_s = 2; // NOT SUPPORTED FIELD + apollo.common.PointENU overtake_point = 3; +} + +message ObjectSidePass { + // follow or lead the object from side lane keeping a longitutional distance to it. + // if you want to cut in the neighbored lane, you may need to sidepass a neighbored object + // first. + double distance_s = 1; // in meters + Range preferred_distance_s = 2; // in meters, relative to the object + enum Type { + FOLLOW = 0; //follow the object from side lane + LEAD = 1; //lead the object from side lane + }; + Type type = 3; +} + +message ObjectAvoid { +} + +message ObjectDecisionType { + oneof object_tag { + ObjectIgnore ignore = 1; + ObjectStop stop = 2; + ObjectFollow follow = 3; + ObjectYield yield = 4; + ObjectOvertake overtake = 5; + ObjectNudge nudge = 6; + ObjectSidePass sidepass = 7; + ObjectAvoid avoid = 8; // unified object decision while estop + } +} + +message ObjectDecision { + enum ObjectType { + PREDICTION = 0; + PERCEPTION = 1; + VIRTUAL = 2; + } + apollo.prediction.PredictionObstacle prediction = 1; + string id = 2; + ObjectType type = 3; + ObjectDecisionType decision = 4; + repeated ObjectDecisionType object_decision = 5; +} + +message ObjectDecisions { + repeated ObjectDecision decision = 1; +} + +// stop at distance_s on lane +message StopLine { + string lane_id = 1; + double distance_s = 2; +} + +message MainStop { + // stop at or before distance_s relative to the lane_id + StopLine enforced_line = 1; + StopLine preferred_start = 2; // NOT SUPPORTED FIELD + StopLine preferred_end = 3; // NOT SUPPORTED FIELD + string reason = 4; + StopReasonCode reason_code = 5; + //when stopped, the front center of vehicle should be at this point + apollo.common.PointENU stop_point = 6; + //when stopped, the heading of the vehicle should be stop_heading + double stop_heading = 7; +} + +message EmergencyStopHardBrake { +} + +message EmergencyStopCruiseToStop { +} + +message MainEmergencyStop { + // unexpected event happened, human driver is required to take over the vehicle. + string reason = 1; + enum ReasonCode { + ESTOP_REASON_INTERNAL_ERR = 0; + ESTOP_REASON_COLLISION = 1; + ESTOP_REASON_ST_FIND_PATH = 2; + ESTOP_REASON_ST_MAKE_DECISION = 3; + ESTOP_REASON_SENSOR_ERROR = 4; + } + ReasonCode reason_code = 2; + oneof task { + EmergencyStopHardBrake hard_brake = 3; // hard brake + EmergencyStopCruiseToStop cruise_to_stop = 4; // cruise to stop + } +} + +message MainCruise { + // cruise current lane +} + +message MainChangeLane { + enum Type { + LEFT = 0; + RIGHT = 1; + }; + Type type = 1; + repeated TargetLane default_lane = 2; + MainStop default_lane_stop = 3; + MainStop target_lane_stop = 4; +} + +message MainMissionComplete { + // arrived at routing destination +} + +message MainNotReady { + // decision system is not ready. + // e.g. wait for routing data. + string reason = 1; +} + +message MainParking { + enum Type { + FORWARD_PARKING = 0; + REVERSE_PARKING = 1; + }; + Type type = 1; + // the heading of the final car position + double heading = 2; + // stop point + apollo.common.PointENU stop_point = 3; + // the polygon of the parking spot + repeated apollo.common.PointENU parking_polygon = 4; +} + +message MainDecision { + oneof task { + MainCruise cruise = 1; + MainStop stop = 2; + MainEmergencyStop estop = 3; + MainChangeLane change_lane = 4; + MainMissionComplete mission_complete = 6; + MainNotReady not_ready = 7; + MainParking parking = 8; + } + repeated TargetLane target_lane = 5; +} + +message MasterVehicleDebug { + apollo.common.PointENU position = 1; + string current_lane_id = 2; + double lane_s = 3; + double lane_l = 4; + double route_s = 5; + double route_l = 6; + double heading = 7; + double heading_speed = 8; + double heading_acceleration = 9; + Range route_s_range = 10; + Range route_l_range = 11; +} + +message ObjectDebug { + string id = 1; + string path_id = 2; + Range route_s = 3; + Range route_l = 4; + bool on_route = 5; + string lane_id = 6; + double lane_s = 7; + bool on_lane = 8; + double path_speed = 9; + // x is time (t), y is s + repeated apollo.common.Point3D st_region = 10; +} + +message LatencyStats { + double total_time_ms = 1; + double sensor_read_time_ms = 2; + double adc_prepare_time_ms = 3; + double obj_prepare_time_ms = 4; + double world_rule_time_ms = 5; + double st_graph_time_ms = 6; + // time diff between gateway_msg_receive_timestamp and gateway_msg_timestamp + double gateway_receive_delay_ms = 8; + // time diff between perception_msg_receive_timestamp and perception_msg_timestamp + double perception_receive_delay_ms = 9; + // time diff between prediction_msg_receive_timestamp and prediction_msg_timestamp + double prediction_receive_delay_ms = 10; + // time diff between signal_msg_receive_timestamp and signal_msg_timestamp + double signal_receive_delay_ms = 11; + // time interval in ms between perception last and its previous msg + double perception_interval_ms = 12; + // time interval in ms between prediction last and its previous msg + double prediction_interval_ms = 13; +} + +message Stats { + LatencyStats latency_stats = 1; +} + +message ModuleDebug { + uint32 gateway_sequence_num = 1; + uint32 perception_sequence_num = 2; + uint32 prediction_sequence_num = 3; + uint32 signal_sequence_num = 4; +} + +// next id: 8 +message Debug { + MasterVehicleDebug master_vehicle = 1; + // stores current frame's original decision when current decision has be modified. + // E.g., when current decision is the first encountered estop, we may use + // a valid history decision to replace current decision, but the estop decision + // will be stored in original_decision + MainDecision original_decision = 2; + repeated ObjectDebug object = 3; + // some meta data will be dumped into debug per sample frequency: + // e.g. every 500 decision, meta data will be dumped once. + bytes map_version = 5; + bytes decision_version = 7; + + // record per module debug info + ModuleDebug module_debug = 6; +} + +// The light signal of the adc +// naming reference https://en.wikipedia.org/wiki/Automotive_lighting +message LightSignal { + bool emergency = 1; // hazard signal + enum TurnSignal { + NO_TURN = 0; + LEFT_TURN = 1; + RIGHT_TURN = 2; + }; + TurnSignal turn_signal = 2; +} + +message DecisionResult { + apollo.common.Header header = 1; + ObjectDecisions object_decision = 2; + MainDecision main_decision = 3; + Debug debug = 4; + Stats stats = 6; + apollo.canbus.Signal signal = 7; + LightSignal light_signal = 5; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/localization/camera.proto b/apollo_msgs/proto/apollo_msgs/proto/localization/camera.proto new file mode 100644 index 0000000..88dcce1 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/localization/camera.proto @@ -0,0 +1,16 @@ +syntax = "proto3"; + +package apollo.localization; + +import "apollo_msgs/proto/common/header.proto"; + +message Camera { + apollo.common.Header header = 1; + + // The image from camera + bytes image = 2; + // The image width + uint32 width = 3; + // The image height + uint32 height = 4; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/localization/camera_parameter.proto b/apollo_msgs/proto/apollo_msgs/proto/localization/camera_parameter.proto new file mode 100644 index 0000000..5f9694c --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/localization/camera_parameter.proto @@ -0,0 +1,30 @@ +syntax = "proto3"; + +package apollo.localization; + +message CameraIntrinsicParameter { + // focus x pixels + double fx = 1; // pixels + // focus y pixels + double fy = 2; // pixels + // center x pixels + double cx = 3; // pixels + // center y pixels + double cy = 4; // pixels +} + +message CameraExtrinsicParameter { + // camera rotation parameters [-pi - pi] + double roll = 1; + double pitch = 2; + double yaw = 3; + // coordinates in the vehicle coordinates [meters] + double tx = 4; // meters + double ty = 5; // meters + double tz = 6; // meters +} + +message CameraParameter { + CameraIntrinsicParameter intrisic_parameter = 1; + CameraExtrinsicParameter extrisic_parameter = 2; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/localization/gps.proto b/apollo_msgs/proto/apollo_msgs/proto/localization/gps.proto new file mode 100644 index 0000000..3e88b7e --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/localization/gps.proto @@ -0,0 +1,13 @@ +syntax = "proto3"; + +package apollo.localization; + +import "apollo_msgs/proto/common/header.proto"; +import "apollo_msgs/proto/localization/pose.proto"; + +message Gps { + apollo.common.Header header = 1; + + // Localization message: from GPS or localization + apollo.localization.Pose localization = 2; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/localization/imu.proto b/apollo_msgs/proto/apollo_msgs/proto/localization/imu.proto new file mode 100644 index 0000000..cff2c3d --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/localization/imu.proto @@ -0,0 +1,13 @@ +syntax = "proto3"; + +package apollo.localization; + +import "apollo_msgs/proto/common/header.proto"; +import "apollo_msgs/proto/localization/pose.proto"; + +message Imu { + apollo.common.Header header = 1; + + // Inertial Measurement Unit(IMU) + apollo.localization.Pose imu = 3; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/localization/localization.proto b/apollo_msgs/proto/apollo_msgs/proto/localization/localization.proto new file mode 100644 index 0000000..8062cb6 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/localization/localization.proto @@ -0,0 +1,69 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +syntax = "proto3"; + +package apollo.localization; + +import "apollo_msgs/proto/common/header.proto"; +import "apollo_msgs/proto/localization/pose.proto"; +import "apollo_msgs/proto/common/geometry.proto"; + +message Uncertainty { + // Standard deviation of position, east/north/up in meters. + apollo.common.Point3D position_std_dev = 1; + + // Standard deviation of quaternion qx/qy/qz, unitless. + apollo.common.Point3D orientation_std_dev = 2; + + // Standard deviation of linear velocity, east/north/up in meters per second. + apollo.common.Point3D linear_velocity_std_dev = 3; + + // Standard deviation of linear acceleration, right/forward/up in meters per + // square second. + apollo.common.Point3D linear_acceleration_std_dev = 4; + + // Standard deviation of angular velocity, right/forward/up in radians per + // second. + apollo.common.Point3D angular_velocity_std_dev = 5; + + // TODO: Define covariance items when needed. +} + +message LocalizationEstimate { + apollo.common.Header header = 1; + apollo.localization.Pose pose = 2; + Uncertainty uncertainty = 3; + + // The time of pose measurement, seconds since the GPS epoch (Jan 6, 1980). + double measurement_time = 4; // In seconds. +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/localization/localization_config.proto b/apollo_msgs/proto/apollo_msgs/proto/localization/localization_config.proto new file mode 100644 index 0000000..cbb32d1 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/localization/localization_config.proto @@ -0,0 +1,11 @@ +syntax = "proto3"; + +package apollo.localization; + +message LocalizationConfig { + enum LocalizationType { + RTK = 0; + CAMERA = 1; + }; + LocalizationType localization_type = 1; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/localization/pose.proto b/apollo_msgs/proto/apollo_msgs/proto/localization/pose.proto new file mode 100644 index 0000000..e9d0803 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/localization/pose.proto @@ -0,0 +1,71 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +syntax = "proto3"; + +package apollo.localization; + +import "apollo_msgs/proto/common/geometry.proto"; + +message Pose { + // Position of the vehicle reference point (VRP) in the map reference frame. + // The VRP is the center of rear axle. + apollo.common.PointENU position = 1; + + // A quaternion that represents the rotation from the map coordinate + // (East/North/Up) to the + // vehicle coordinate (Right/Forward/Up). + apollo.common.Quaternion orientation = 2; + + // Linear velocity of the VRP in the map reference frame. + // East/north/up in meters per second. + apollo.common.Point3D linear_velocity = 3; + + // Linear acceleration of the VRP in the map reference frame. + // East/north/up in meters per second. + apollo.common.Point3D linear_acceleration = 4; + + // Angular velocity of the vehicle in the map reference frame. + // Around east/north/up axes in radians per second. + apollo.common.Point3D angular_velocity = 5; + + // heading + double heading = 6; + + // Linear acceleration of the VRP in the vehicle reference frame. + // Right/forward/up in meters per square second. + apollo.common.Point3D linear_acceleration_vrf = 7; + + // Angular velocity of the vehicle in the vehicle reference frame. + // Around right/forward/up axes in radians per second. + apollo.common.Point3D angular_velocity_vrf = 8; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/perception/perception_obstacle.proto b/apollo_msgs/proto/apollo_msgs/proto/perception/perception_obstacle.proto new file mode 100644 index 0000000..282b963 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/perception/perception_obstacle.proto @@ -0,0 +1,55 @@ +syntax = "proto3"; + +package apollo.perception; + +import "apollo_msgs/proto/common/header.proto"; + +// FIXME: To be merged with common::ErrorCode +enum PerceptionErrorCode { + ERROR_NONE = 0; + ERROR_TF = 1; + ERROR_PROCESS = 2; + ERROR_UNKNOWN = 3; +} + +message Point { + double x = 1; // in meters. + double y = 2; // in meters. + double z = 3; // height in meters. +} + +message PerceptionObstacle { + int32 id = 1; // obstacle ID. + Point position = 2; // obstacle position in the world coordinate system. + double theta = 3; // heading in the world coordinate system. + Point velocity = 4; // obstacle velocity. + + // Size of obstacle bounding box. + double length = 5; // obstacle length. + double width = 6; // obstacle width. + double height = 7; // obstacle height. + + repeated Point polygon_point = 8; // obstacle corner points. + double tracking_time = 9; // duration of an obstacle since detection in s. + + enum Type { + UNKNOWN = 0; + UNKNOWN_MOVABLE = 1; + UNKNOWN_UNMOVABLE = 2; + PEDESTRIAN = 3; // Pedestrian, usually determined by moving behaviour. + BICYCLE = 4; // bike, motor bike + VEHICLE = 5; // Passenger car or truck. + }; + Type type = 10; // obstacle type + double timestamp = 11; // GPS time in seconds. + + // Just for offline debuging, onboard will not fill this field. + // Format like : [x0, y0, z0, x1, y1, z1...] + repeated double point_cloud = 12; +} + +message PerceptionObstacles { + repeated PerceptionObstacle perception_obstacle = 1; // An array of obstacles + apollo.common.Header header = 2; // Header + PerceptionErrorCode error_code = 3; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/perception/traffic_light_detection.proto b/apollo_msgs/proto/apollo_msgs/proto/perception/traffic_light_detection.proto new file mode 100644 index 0000000..d6847ee --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/perception/traffic_light_detection.proto @@ -0,0 +1,30 @@ +syntax = "proto3"; + +package apollo.perception; + +import "apollo_msgs/proto/common/header.proto"; + +message TrafficLight { + enum Color { + UNKNOWN = 0; + RED = 1; + YELLOW = 2; + GREEN = 3; + }; + Color color = 1; + + // Traffic light string-ID in the map data. + string id = 2; + + // How confidence about the detected results, between 0 and 1. + double confidence = 3; + + // Duration of the traffic light since detected. + double tracking_time = 4; +} + +message TrafficLightDetection { + apollo.common.Header header = 2; + + repeated TrafficLight traffic_light = 1; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/planning/planning.proto b/apollo_msgs/proto/apollo_msgs/proto/planning/planning.proto new file mode 100644 index 0000000..88cfec7 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/planning/planning.proto @@ -0,0 +1,63 @@ +syntax = "proto3"; + +package apollo.planning; + +import "apollo_msgs/proto/common/header.proto"; +import "apollo_msgs/proto/canbus/chassis.proto"; +import "apollo_msgs/proto/planning/planning_internal.proto"; + +message ADCTrajectoryPoint { + double x = 1; // in meters. + double y = 2; // in meters. + double z = 3; // height in meters. + + double speed = 6; // speed, in meters / second + double acceleration_s = 7; // acceleration in s direction + double curvature = 8; // curvature (k = 1/r), unit: (1/meters) + double curvature_change_rate = 9; // change of curvature in unit s (dk/ds) + double relative_time = 10; // in seconds relative time (relative_time = time_of_this_state - timestamp_in_header) + double theta = 11; // relative to absolute coordinate system + double accumulated_s = 12; // calculated from the first point in this trajectory + + double s = 4; // in meters, reference to route SL-coordinate + double l = 5; // in meters, reference to route SL-coordinate +} + +message ADCSignals { + enum SignalType { + LEFT_TURN = 0; + RIGHT_TURN = 1; + LOW_BEAM_LIGHT = 2; + HIGH_BEAM_LIGHT = 3; + FOG_LIGHT = 4; + EMERGENCY_LIGHT = 5; + } + repeated SignalType signal = 1; +} + +message EStop { + bool is_estop = 1; // is_estop == true when emergency stop is required +} + +message ADCPathPoint { + double x = 1; // in meters + double y = 2; // in meters + double z = 3; // in meters + double curvature = 4; // curvature (k = 1/r), unit: (1/meters) + double heading = 5; // relative to absolute coordinate system +} + +message ADCTrajectory { + apollo.common.Header header = 1; + double total_path_length = 2; // in meters + double total_path_time = 3; // in seconds + repeated ADCTrajectoryPoint adc_trajectory_point = 4; + EStop estop = 6; + repeated ADCPathPoint adc_path_point = 7; + bool is_replan = 9; // is_replan == true mean replan triggered + apollo.canbus.Chassis.GearPosition gear = 10; // Specify trajectory gear + apollo.planning_internal.Debug debug = 8; + apollo.canbus.Signal signal = 11; + + ADCSignals signals = 5; +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/planning/planning_internal.proto b/apollo_msgs/proto/apollo_msgs/proto/planning/planning_internal.proto new file mode 100644 index 0000000..fbc6c23 --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/planning/planning_internal.proto @@ -0,0 +1,86 @@ +syntax = "proto3"; + +package apollo.planning_internal; + +import "apollo_msgs/proto/common/header.proto"; +import "apollo_msgs/proto/decision/decision.proto"; +import "apollo_msgs/proto/localization/localization.proto"; +import "apollo_msgs/proto/localization/pose.proto"; +import "apollo_msgs/proto/perception/perception_obstacle.proto"; +import "apollo_msgs/proto/prediction/prediction_obstacle.proto"; + +message PlanningObstacle { + int32 perception_id = 1; + string decision_id = 2; + + apollo.perception.Point position = 3; // obstacle position in the world coordinate system. + double theta = 4; // heading in the world coordinate system + apollo.perception.Point velocity = 5; // obstacle velocity. + // obstacle speed ( == sqrt(velocity.x^2 + velocity.y^2) + double speed = 6; + + // Size of obstacle bounding box. + double length = 7; // obstacle length. + double width = 8; // obstacle width. + double height = 9; // obstacle height. + + // obstacle corner points. + repeated apollo.perception.Point polygon_point = 10; + // duration of an obstacle since detection. + double tracking_time = 11; + + // perception timestamp in ms + double perception_timestamp = 12; + // object type in perception + apollo.perception.PerceptionObstacle.Type perception_object_type = 13; + + double prediction_timestamp = 14; // prediction_timestamp in ms + // from prediction + repeated apollo.prediction.Trajectory prediction_trajectory = 15; + + // object type in decision + apollo.decision.ObjectDecision.ObjectType decision_object_type = 16; + apollo.decision.ObjectDecisionType object_decision = 17; + repeated apollo.decision.ObjectDecisionType planning_object_decision = 18; +} + +message Debug { + enum ErrorCode { + OK = 0; + ERR_NOT_READY = 1; + ERR_ESTOP = 2; + ERR_PATH_OPTIMIZER = 3; + ERR_SPEED_OPTIMIZER = 4; + ERR_ST_GRAPH = 5; + ERR_SANITY_CHECK = 6; + } + + /* + PLEASE add id here + id = 1: st_graph_info + */ + message DebugMessage { + ErrorCode error_code = 1; + int32 id = 2; + oneof debug_string { + string trace = 3; + string info = 4; + string warn = 5; + string error = 6; + string fatal = 7; + } + } + + ErrorCode error_code = 1; + PlanningData planning_data = 2; + repeated DebugMessage debug_message = 3; +} + +message PlanningData { + apollo.common.Header header = 1; + apollo.localization.Pose init_status = 2; // initial status of adc + apollo.decision.MainDecision main_decision = 3; // from decision + // processed planning_obstacles + repeated PlanningObstacle planning_obstacle = 4; + apollo.decision.LightSignal light_signal = 5; // light signal from decision +} diff --git a/apollo_msgs/proto/apollo_msgs/proto/prediction/prediction_obstacle.proto b/apollo_msgs/proto/apollo_msgs/proto/prediction/prediction_obstacle.proto new file mode 100644 index 0000000..0d40ecf --- /dev/null +++ b/apollo_msgs/proto/apollo_msgs/proto/prediction/prediction_obstacle.proto @@ -0,0 +1,33 @@ +syntax = "proto3"; + +package apollo.prediction; + +import "apollo_msgs/proto/common/header.proto"; +import "apollo_msgs/proto/perception/perception_obstacle.proto"; + +message TrajectoryPoint { + double x = 1; // in meters. + double y = 2; // in meters. + double z = 3; // height in meters. + double velocity = 4; // velocity, in meters / second + double t = 5; // in seconds, relative to the time_stamp of this message (t = t_this_state - t_timestamp) + double heading = 6; // heading in angle +} + +message Trajectory { + double probability = 1; //probability of this trajectory + repeated TrajectoryPoint trajectory_point = 2; +} + +message PredictionObstacle { + apollo.perception.PerceptionObstacle perception_obstacle = 1; + double time_stamp = 2; // GPS time in seconds + double predicted_period = 3; // the length of the time for this prediction (e.g. 10s) + repeated Trajectory trajectory = 4; // can have multiple trajectories per obstacle +} + +message PredictionObstacles { + apollo.common.Header header = 1; // timestamp is included in header + repeated PredictionObstacle prediction_obstacle = 2; // make prediction for multiple obstacles + apollo.perception.PerceptionErrorCode perception_error_code = 3; // perception error code +} diff --git a/apollo_planning/CMakeLists.txt b/apollo_planning/CMakeLists.txt new file mode 100644 index 0000000..169a300 --- /dev/null +++ b/apollo_planning/CMakeLists.txt @@ -0,0 +1,54 @@ +cmake_minimum_required(VERSION 3.0.2) +project(apollo_planning) + +add_compile_options(-std=c++17) +# set(CMAKE_BUILD_TYPE "Debug") +set(CMAKE_BUILD_TYPE "Release") + +find_package(Eigen3 REQUIRED) + +find_package(catkin REQUIRED COMPONENTS + roscpp + apollo_msgs + apollo_common +) + +catkin_package( +# INCLUDE_DIRS include +# LIBRARIES apollo_planning +# CATKIN_DEPENDS roscpp +# DEPENDS system_lib +) + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIR} +) + +add_executable(${PROJECT_NAME} + src/main.cc + src/planning_node.cc + src/planning.cc + src/planner_factory.cc + # common + src/common/planning_gflags.cc + # planner + src/planner/rtk_replay_planner.cc +) +add_dependencies(${PROJECT_NAME} + ${${PROJECT_NAME}_EXPORTED_TARGETS} + ${catkin_EXPORTED_TARGETS} +) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} + protobuf + glog + gflags +) + +# install +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) \ No newline at end of file diff --git a/apollo_planning/README.md b/apollo_planning/README.md new file mode 100644 index 0000000..7ec31cd --- /dev/null +++ b/apollo_planning/README.md @@ -0,0 +1,19 @@ +# Planning + +## Introduction + Given localization (vehicle status (position, velocity, acceleration)), + perception (future work), prediction (future work) and decision (future work), + compute a trajectory that is safe and comfortable for controller to execute. + + Current version of planning is in actual an RTK replayer. + It first loads a recorded trajectory in the initialization and sends the proper segment of the trajectory according to current system time and vehicle position. + +## Input + * Localization + * Perception (future work) + * Prediction (future work) + * Decision (future work) + * (For current RTK replayer) Recorded RTK trajectory (put into the folder modules/planning/data, and change the gflag file name in planning/common/planning_gflags) + +## Output + * A collision-free and comfortable trajectory. (For current RTK replayer, a segment of the recorded RTK trajectory for execution.) \ No newline at end of file diff --git a/apollo_planning/conf/adapter.conf b/apollo_planning/conf/adapter.conf new file mode 100644 index 0000000..eebf8be --- /dev/null +++ b/apollo_planning/conf/adapter.conf @@ -0,0 +1,16 @@ +config { + type: LOCALIZATION + mode: RECEIVE_ONLY + message_history_limit: 10 +} +config { + type: CHASSIS + mode: RECEIVE_ONLY + message_history_limit: 10 +} +config { + type: PLANNING_TRAJECTORY + mode: PUBLISH_ONLY + message_history_limit: 10 +} +is_ros: true diff --git a/apollo_planning/conf/planning.conf b/apollo_planning/conf/planning.conf new file mode 100644 index 0000000..54beac9 --- /dev/null +++ b/apollo_planning/conf/planning.conf @@ -0,0 +1,5 @@ +--planning_loop_rate=10.0 + +# glog +--colorlogtostderr=1 +--stderrthreshold=0 \ No newline at end of file diff --git a/apollo_planning/data/garage.csv b/apollo_planning/data/garage.csv new file mode 100644 index 0000000..d9d7e6d --- /dev/null +++ b/apollo_planning/data/garage.csv @@ -0,0 +1,2083 @@ +x,y,z,speed,acceleration,curvature,curvature_change_rate,time,theta,gear,s,throttle,brake,steering +0.858607, 0.7357, -28.367020, 0.216667, 0.887545, 0.022767, -0.017740, 1496957374.614000, 2.834701, 1.000000, 0.002167, 22.015717, 13.693446, 12.638298 +0.855147, 0.73686, -28.367176, 0.216667, 0.913475, 0.022767, 0.000000, 1496957374.624600, 2.834818, 1.000000, 0.004333, 22.015717, 13.675136, 12.638298 +0.851608, 0.73803, -28.367333, 0.252778, 0.884692, 0.022690, -0.030410, 1496957374.634200, 2.834939, 1.000000, 0.006861, 22.102694, 13.675136, 12.595745 +0.847987, 0.73924, -28.367502, 0.252778, 0.874161, 0.022690, 0.000000, 1496957374.643800, 2.835011, 1.000000, 0.009389, 22.102694, 13.723965, 12.595745 +0.84427, 0.74047, -28.367668, 0.283333, 0.934227, 0.022652, -0.013566, 1496957374.654300, 2.835118, 1.000000, 0.012222, 22.102694, 13.723965, 12.574468 +0.840443, 0.74175, -28.367820, 0.283333, 1.034661, 0.022652, 0.000000, 1496957374.663900, 2.835242, 1.000000, 0.015056, 22.102694, 13.650721, 12.574468 +0.836527, 0.74305, -28.367978, 0.311111, 1.022756, 0.022575, -0.024707, 1496957374.674500, 2.835355, 1.000000, 0.018167, 22.114901, 13.650721, 12.531915 +0.832523, 0.74437, -28.368154, 0.311111, 0.965700, 0.022575, 0.000000, 1496957374.684100, 2.835467, 1.000000, 0.021278, 22.114901, 13.653772, 12.531915 +0.828455, 0.74571, -28.368321, 0.338889, 0.836594, 0.022498, -0.022681, 1496957374.693600, 2.835620, 1.000000, 0.024667, 22.163729, 13.653772, 12.489362 +0.824334, 0.74708, -28.368462, 0.338889, 0.697852, 0.022498, 0.000000, 1496957374.704100, 2.835720, 1.000000, 0.028056, 22.163729, 13.675136, 12.489362 +0.820131, 0.74848, -28.368583, 0.363889, 0.722276, 0.022383, -0.031684, 1496957374.714600, 2.835855, 1.000000, 0.031694, 22.261387, 13.675136, 12.425532 +0.81583, 0.7499, -28.368701, 0.363889, 0.858754, 0.022383, 0.000000, 1496957374.724200, 2.835976, 1.000000, 0.035333, 22.261387, 13.684291, 12.425532 +0.8114, 0.75136, -28.368819, 0.388889, 1.079375, 0.022306, -0.019764, 1496957374.733800, 2.836136, 1.000000, 0.039222, 22.212559, 13.684291, 12.382978 +0.806857, 0.75285, -28.368958, 0.388889, 1.169263, 0.022306, 0.000000, 1496957374.744400, 2.836275, 1.000000, 0.043111, 22.212559, 13.699550, 12.382978 +0.802227, 0.75435, -28.369088, 0.411111, 1.076318, 0.022229, -0.018695, 1496957374.753900, 2.836416, 1.000000, 0.047222, 22.273594, 13.699550, 12.340425 +0.797518, 0.75587, -28.369217, 0.411111, 0.955823, 0.022229, 0.000000, 1496957374.764400, 2.836458, 1.000000, 0.051333, 22.273594, 13.665980, 12.340425 +0.792717, 0.75743, -28.369343, 0.433333, 0.936041, 0.022114, -0.026604, 1496957374.773900, 2.836620, 1.000000, 0.055667, 22.188145, 13.665980, 12.276596 +0.78782, 0.75903, -28.369453, 0.433333, 0.968690, 0.022114, 0.000000, 1496957374.784500, 2.836713, 1.000000, 0.060000, 22.188145, 13.685817, 12.276596 +0.782841, 0.76065, -28.369563, 0.458333, 0.921227, 0.022037, -0.016768, 1496957374.794100, 2.836889, 1.000000, 0.064583, 22.346838, 13.685817, 12.234042 +0.777794, 0.76227, -28.369685, 0.458333, 0.803813, 0.022037, 0.000000, 1496957374.803500, 2.837025, 1.000000, 0.069167, 22.346838, 13.708705, 12.234042 +0.772648, 0.76392, -28.369826, 0.480556, 0.866057, 0.021960, -0.015992, 1496957374.814100, 2.837151, 1.000000, 0.073972, 22.407873, 13.708705, 12.191489 +0.767385, 0.76563, -28.369966, 0.480556, 1.051542, 0.021960, 0.000000, 1496957374.824600, 2.837278, 1.000000, 0.078778, 22.407873, 13.658351, 12.191489 +0.762008, 0.76739, -28.370087, 0.491667, 1.170272, 0.021845, -0.023445, 1496957374.834200, 2.837421, 1.000000, 0.083694, 22.493324, 13.658351, 12.127660 +0.756529, 0.76915, -28.370233, 0.491667, 1.144834, 0.021845, 0.000000, 1496957374.843700, 2.837606, 1.000000, 0.088611, 22.493324, 13.698024, 12.127660 +0.750946, 0.77093, -28.370402, 0.525000, 1.095471, 0.021768, -0.014637, 1496957374.854200, 2.837770, 1.000000, 0.093861, 22.481117, 13.698024, 12.085107 +0.745243, 0.77276, -28.370576, 0.525000, 1.173038, 0.021768, 0.000000, 1496957374.863700, 2.837893, 1.000000, 0.099111, 22.481117, 13.740749, 12.085107 +0.739419, 0.77466, -28.370696, 0.547222, 1.241507, 0.021691, -0.014043, 1496957374.874200, 2.838038, 1.000000, 0.104583, 22.554359, 13.740749, 12.042553 +0.733494, 0.77655, -28.370809, 0.547222, 1.143265, 0.021691, 0.000000, 1496957374.883700, 2.838250, 1.000000, 0.110056, 22.554359, 13.678187, 12.042553 +0.727492, 0.77846, -28.370998, 0.547222, 0.973106, 0.021691, 0.000000, 1496957374.894600, 2.838405, 1.000000, 0.115528, 22.554359, 13.678187, 12.042553 +0.721406, 0.78041, -28.371137, 0.572222, 0.915780, 0.021614, -0.013428, 1496957374.904200, 2.838532, 1.000000, 0.121250, 22.554359, 13.636988, 12.000000 +0.715221, 0.78241, -28.371252, 0.594444, 0.958832, 0.021537, -0.012926, 1496957374.913700, 2.838692, 1.000000, 0.127194, 22.688641, 13.636988, 11.957447 +0.708952, 0.78443, -28.371375, 0.594444, 0.934298, 0.021537, 0.000000, 1496957374.924200, 2.838885, 1.000000, 0.133139, 22.688641, 13.711757, 11.957447 +0.702577, 0.78648, -28.371478, 0.616667, 0.994907, 0.021422, -0.018690, 1496957374.933800, 2.839042, 1.000000, 0.139306, 22.774090, 13.711757, 11.893617 +0.696088, 0.78857, -28.371583, 0.616667, 1.091557, 0.021422, 0.000000, 1496957374.944400, 2.839232, 1.000000, 0.145472, 22.774090, 13.722439, 11.893617 +0.68949, 0.79068, -28.371731, 0.636111, 1.146401, 0.021345, -0.012079, 1496957374.954000, 2.839434, 1.000000, 0.151833, 22.798504, 13.722439, 11.851064 +0.682781, 0.79282, -28.371801, 0.636111, 1.143791, 0.021345, 0.000000, 1496957374.964500, 2.839565, 1.000000, 0.158194, 22.798504, 13.678187, 11.851064 +0.675966, 0.79499, -28.371892, 0.655556, 1.140102, 0.021230, -0.017580, 1496957374.974100, 2.839761, 1.000000, 0.164750, 22.810711, 13.678187, 11.787234 +0.669048, 0.79719, -28.372038, 0.655556, 1.117951, 0.021230, 0.000000, 1496957374.983600, 2.839949, 1.000000, 0.171306, 22.810711, 13.736172, 11.787234 +0.662033, 0.79942, -28.372120, 0.677778, 1.072928, 0.021115, -0.017003, 1496957374.994000, 2.840134, 1.000000, 0.178083, 22.871748, 13.736172, 11.723404 +0.654907, 0.80168, -28.372237, 0.677778, 1.073048, 0.021115, 0.000000, 1496957375.004400, 2.840296, 1.000000, 0.184861, 22.871748, 13.673610, 11.723404 +0.647681, 0.80398, -28.372378, 0.702778, 1.085170, 0.021000, -0.016397, 1496957375.013900, 2.840491, 1.000000, 0.191889, 22.920576, 13.673610, 11.659575 +0.640368, 0.8063, -28.372450, 0.702778, 1.022522, 0.021000, 0.000000, 1496957375.024500, 2.840677, 1.000000, 0.198917, 22.920576, 13.655298, 11.659575 +0.632939, 0.80866, -28.372600, 0.725000, 1.063223, 0.020884, -0.015894, 1496957375.034000, 2.840929, 1.000000, 0.206167, 22.883955, 13.655298, 11.595745 +0.625403, 0.81105, -28.372750, 0.725000, 1.130209, 0.020884, 0.000000, 1496957375.043500, 2.841130, 1.000000, 0.213417, 22.883955, 13.708705, 11.595745 +0.617751, 0.81348, -28.372863, 0.747222, 1.164882, 0.020731, -0.020561, 1496957375.054100, 2.841287, 1.000000, 0.220889, 22.969406, 13.708705, 11.510638 +0.609992, 0.81593, -28.373019, 0.747222, 1.145897, 0.020731, 0.000000, 1496957375.063500, 2.841492, 1.000000, 0.228361, 22.969406, 13.691920, 11.510638 +0.602125, 0.81843, -28.373117, 0.772222, 1.146585, 0.020577, -0.019894, 1496957375.074100, 2.841682, 1.000000, 0.236083, 23.030441, 13.691920, 11.425532 +0.593995, 0.82097, -28.373242, 0.772222, 1.129677, 0.020577, 0.000000, 1496957375.083600, 2.841678, 1.000000, 0.243806, 23.030441, 13.665980, 11.425532 +0.58568, 0.82353, -28.373310, 0.797222, 1.139351, 0.020462, -0.014452, 1496957375.094200, 2.841913, 1.000000, 0.251778, 22.969406, 13.665980, 11.361702 +0.577255, 0.82613, -28.373398, 0.797222, 1.164346, 0.020462, 0.000000, 1496957375.103800, 2.842112, 1.000000, 0.259750, 22.969406, 13.614100, 11.361702 +0.568711, 0.82875, -28.373503, 0.822222, 1.186266, 0.020308, -0.018683, 1496957375.114300, 2.842337, 1.000000, 0.267972, 23.054855, 13.614100, 11.276596 +0.56006, 0.83142, -28.373572, 0.822222, 1.181287, 0.020308, 0.000000, 1496957375.123800, 2.842558, 1.000000, 0.276194, 23.054855, 13.684291, 11.276596 +0.551301, 0.8341, -28.373708, 0.844444, 1.138158, 0.020155, -0.018191, 1496957375.134400, 2.842818, 1.000000, 0.284639, 23.189137, 13.684291, 11.191489 +0.542429, 0.83682, -28.373784, 0.844444, 1.144505, 0.020155, 0.000000, 1496957375.143900, 2.842999, 1.000000, 0.293083, 23.189137, 13.688869, 11.191489 +0.533449, 0.83958, -28.373916, 0.869444, 1.146625, 0.020001, -0.017666, 1496957375.154400, 2.843269, 1.000000, 0.301778, 23.262379, 13.688869, 11.106383 +0.524347, 0.84238, -28.374008, 0.869444, 1.197490, 0.020001, 0.000000, 1496957375.164100, 2.843516, 1.000000, 0.310472, 23.262379, 13.698024, 11.106383 +0.515116, 0.84521, -28.374137, 0.897222, 1.274330, 0.019847, -0.017119, 1496957375.174700, 2.843717, 1.000000, 0.319444, 23.433279, 13.698024, 11.021276 +0.505772, 0.84807, -28.374267, 0.897222, 1.247283, 0.019847, 0.000000, 1496957375.184300, 2.843930, 1.000000, 0.328417, 23.433279, 13.684291, 11.021276 +0.496302, 0.85097, -28.374380, 0.922222, 1.282361, 0.019694, -0.016654, 1496957375.193900, 2.844155, 1.000000, 0.337639, 23.530937, 13.684291, 10.936171 +0.486723, 0.85389, -28.374527, 0.922222, 1.207899, 0.019694, 0.000000, 1496957375.204300, 2.844355, 1.000000, 0.346861, 23.530937, 13.643091, 10.936171 +0.477007, 0.85687, -28.374616, 0.950000, 1.287314, 0.019502, -0.020208, 1496957375.213900, 2.844613, 1.000000, 0.356361, 23.421072, 13.643091, 10.829787 +0.467168, 0.85986, -28.374753, 0.950000, 1.291178, 0.019502, 0.000000, 1496957375.224500, 2.844819, 1.000000, 0.365861, 23.421072, 13.722439, 10.829787 +0.457195, 0.86289, -28.374864, 0.963889, 1.343269, 0.019348, -0.015932, 1496957375.234000, 2.845049, 1.000000, 0.375500, 23.518730, 13.722439, 10.744680 +0.447095, 0.86595, -28.374985, 0.963889, 1.319264, 0.019348, 0.000000, 1496957375.244600, 2.845264, 1.000000, 0.385139, 23.518730, 13.676661, 10.744680 +0.436873, 0.86905, -28.375106, 1.002778, 1.298833, 0.019156, -0.019142, 1496957375.254100, 2.845474, 1.000000, 0.395167, 23.640802, 13.676661, 10.638298 +0.426539, 0.87217, -28.375211, 1.002778, 1.222126, 0.019156, 0.000000, 1496957375.263600, 2.845679, 1.000000, 0.405194, 23.640802, 13.678187, 10.638298 +0.416094, 0.87533, -28.375300, 1.027778, 1.178429, 0.019003, -0.014940, 1496957375.274100, 2.845903, 1.000000, 0.415472, 23.738461, 13.678187, 10.553191 +0.405537, 0.87852, -28.375402, 1.027778, 1.171827, 0.019003, 0.000000, 1496957375.283600, 2.846138, 1.000000, 0.425750, 23.738461, 13.678187, 10.553191 +0.394855, 0.88175, -28.375483, 1.050000, 1.215696, 0.018811, -0.018279, 1496957375.294100, 2.846359, 1.000000, 0.436250, 23.848326, 13.678187, 10.446809 +0.384047, 0.885, -28.375581, 1.050000, 1.245199, 0.018811, 0.000000, 1496957375.303500, 2.846600, 1.000000, 0.446750, 23.848326, 13.681239, 10.446809 +0.373097, 0.8883, -28.375653, 1.075000, 1.362725, 0.018619, -0.017853, 1496957375.314100, 2.846814, 1.000000, 0.457500, 23.921568, 13.681239, 10.340425 +0.362026, 0.89163, -28.375761, 1.075000, 1.346405, 0.018619, 0.000000, 1496957375.323600, 2.847040, 1.000000, 0.468250, 23.921568, 13.685817, 10.340425 +0.350816, 0.895, -28.375828, 1.100000, 1.378651, 0.018389, -0.020935, 1496957375.334100, 2.847288, 1.000000, 0.479250, 23.860533, 13.685817, 10.212766 +0.339472, 0.89839, -28.375960, 1.100000, 1.386195, 0.018389, 0.000000, 1496957375.343600, 2.847521, 1.000000, 0.490250, 23.860533, 13.627832, 10.212766 +0.327998, 0.90182, -28.376074, 1.127778, 1.384518, 0.018197, -0.017015, 1496957375.354100, 2.847736, 1.000000, 0.501528, 23.884947, 13.627832, 10.106383 +0.316397, 0.90528, -28.376179, 1.127778, 1.340746, 0.018197, 0.000000, 1496957375.363600, 2.847974, 1.000000, 0.512806, 23.884947, 13.688869, 10.106383 +0.304664, 0.90877, -28.376331, 1.155556, 1.357396, 0.017851, -0.029889, 1496957375.373800, 2.848241, 1.000000, 0.524361, 23.933775, 13.688869, 9.914893 +0.292798, 0.9123, -28.376474, 1.155556, 1.363371, 0.017851, 0.000000, 1496957375.384300, 2.848470, 1.000000, 0.535917, 23.933775, 13.731594, 9.914893 +0.280791, 0.91586, -28.376626, 1.186111, 1.396016, 0.017621, -0.019411, 1496957375.393900, 2.848704, 1.000000, 0.547778, 23.909361, 13.731594, 9.787234 +0.268652, 0.91947, -28.376795, 1.186111, 1.423190, 0.017621, 0.000000, 1496957375.404500, 2.848943, 1.000000, 0.559639, 23.909361, 13.653772, 9.787234 +0.256372, 0.92312, -28.376949, 1.213889, 1.437165, 0.017353, -0.022126, 1496957375.413900, 2.849201, 1.000000, 0.571778, 24.031433, 13.653772, 9.638298 +0.243956, 0.9268, -28.377117, 1.213889, 1.432979, 0.017353, 0.000000, 1496957375.424500, 2.849429, 1.000000, 0.583917, 24.031433, 13.682765, 9.638298 +0.231388, 0.93052, -28.377305, 1.244444, 1.469919, 0.017084, -0.021581, 1496957375.434100, 2.849713, 1.000000, 0.596361, 23.921568, 13.682765, 9.489362 +0.218695, 0.93427, -28.377466, 1.244444, 1.434446, 0.017084, 0.000000, 1496957375.443500, 2.849948, 1.000000, 0.608806, 23.921568, 13.731594, 9.489362 +0.205856, 0.93808, -28.377669, 1.275000, 1.442190, 0.016777, -0.024071, 1496957375.454000, 2.850217, 1.000000, 0.621556, 23.933775, 13.731594, 9.319149 +0.192884, 0.94191, -28.377800, 1.275000, 1.408717, 0.016777, 0.000000, 1496957375.464600, 2.850474, 1.000000, 0.634306, 23.933775, 13.723965, 9.319149 +0.179783, 0.94578, -28.377991, 1.302778, 1.382331, 0.016470, -0.023556, 1496957375.474300, 2.850759, 1.000000, 0.647333, 24.019226, 13.723965, 9.148936 +0.166547, 0.94968, -28.378125, 1.302778, 1.372364, 0.016470, 0.000000, 1496957375.483700, 2.850996, 1.000000, 0.660361, 24.019226, 13.687343, 9.148936 +0.153178, 0.95363, -28.378289, 1.327778, 1.390139, 0.016202, -0.020222, 1496957375.494200, 2.851288, 1.000000, 0.673639, 23.982605, 13.687343, 9.000000 +0.139676, 0.95761, -28.378428, 1.327778, 1.395078, 0.016202, 0.000000, 1496957375.503500, 2.851553, 1.000000, 0.686917, 23.982605, 13.673610, 9.000000 +0.112256, 0.96567, -28.378717, 1.358333, 1.422694, 0.015895, -0.022589, 1496957375.514300, 2.852035, 1.000000, 0.700500, 24.068056, 13.673610, 8.829787 +0.112256, 0.96567, -28.378717, 1.358333, 1.422694, 0.015895, 0.000000, 1496957375.523800, 2.852035, 1.000000, 0.714083, 24.068056, 13.661403, 8.829787 +0.098324, 0.96976, -28.378866, 1.386111, 1.472362, 0.015588, -0.022135, 1496957375.534300, 2.852299, 1.000000, 0.727944, 24.031433, 13.661403, 8.659575 +0.084249, 0.97388, -28.378991, 1.386111, 1.492228, 0.015588, 0.000000, 1496957375.543800, 2.852557, 1.000000, 0.741806, 24.031433, 13.723965, 8.659575 +0.070035, 0.97802, -28.379129, 1.416667, 1.463343, 0.015243, -0.024363, 1496957375.554300, 2.852825, 1.000000, 0.755972, 24.019226, 13.723965, 8.468085 +0.055677, 0.98221, -28.379259, 1.416667, 1.471114, 0.015243, 0.000000, 1496957375.563800, 2.853063, 1.000000, 0.770139, 24.019226, 13.667506, 8.468085 +0.041181, 0.98643, -28.379376, 1.444444, 1.451639, 0.014936, -0.021238, 1496957375.573500, 2.853341, 1.000000, 0.784583, 24.055847, 13.667506, 8.297873 +0.02654, 0.99068, -28.379495, 1.444444, 1.458197, 0.014936, 0.000000, 1496957375.584100, 2.853568, 1.000000, 0.799028, 24.055847, 13.704127, 8.297873 +0.011776, 0.99497, -28.379608, 1.475000, 1.387880, 0.014591, -0.023395, 1496957375.593500, 2.853795, 1.000000, 0.813778, 24.068056, 13.704127, 8.106383 +-0.003137, 0.9993, -28.379728, 1.475000, 1.433107, 0.014591, 0.000000, 1496957375.604200, 2.854039, 1.000000, 0.828528, 24.068056, 13.698024, 8.106383 +-0.018179, 1.00367, -28.379819, 1.505556, 1.413793, 0.014246, -0.022919, 1496957375.613600, 2.854315, 1.000000, 0.843583, 24.031433, 13.698024, 7.914894 +-0.033374, 1.00809, -28.379933, 1.505556, 1.474462, 0.014246, 0.000000, 1496957375.624100, 2.854563, 1.000000, 0.858639, 24.031433, 13.694972, 7.914894 +-0.04871, 1.01253, -28.380024, 1.519444, 1.472502, 0.013901, -0.022707, 1496957375.633600, 2.854771, 1.000000, 0.873833, 24.068056, 13.694972, 7.723404 +-0.064201, 1.01704, -28.380134, 1.519444, 1.561093, 0.013901, 0.000000, 1496957375.644100, 2.855030, 1.000000, 0.889028, 24.068056, 13.682765, 7.723404 +-0.079822, 1.02156, -28.380188, 1.566667, 1.481299, 0.013518, -0.024468, 1496957375.653600, 2.855256, 1.000000, 0.904694, 24.043640, 13.682765, 7.510638 +-0.095586, 1.02614, -28.380288, 1.566667, 1.481777, 0.013518, 0.000000, 1496957375.664100, 2.855519, 1.000000, 0.920361, 24.043640, 13.713283, 7.510638 +-0.111496, 1.03075, -28.380333, 1.600000, 1.458794, 0.013134, -0.023956, 1496957375.673500, 2.855751, 1.000000, 0.936361, 24.068056, 13.713283, 7.297873 +-0.127552, 1.0354, -28.380426, 1.600000, 1.490949, 0.013134, 0.000000, 1496957375.684100, 2.855994, 1.000000, 0.952361, 24.068056, 13.713283, 7.297873 +-0.143753, 1.04009, -28.380459, 1.627778, 1.501174, 0.012751, -0.023546, 1496957375.693500, 2.856264, 1.000000, 0.968639, 24.068056, 13.713283, 7.085106 +-0.160097, 1.04482, -28.380522, 1.627778, 1.485558, 0.012751, 0.000000, 1496957375.704000, 2.856502, 1.000000, 0.984917, 24.068056, 13.684291, 7.085106 +-0.176578, 1.04957, -28.380535, 1.658333, 1.463823, 0.012406, -0.020799, 1496957375.713500, 2.856748, 1.000000, 1.001500, 24.080263, 13.684291, 6.893617 +-0.193212, 1.05438, -28.380564, 1.658333, 1.490200, 0.012406, 0.000000, 1496957375.724100, 2.856963, 1.000000, 1.018083, 24.080263, 13.722439, 6.893617 +-0.209985, 1.05921, -28.380539, 1.688889, 1.471525, 0.012061, -0.020421, 1496957375.733500, 2.857214, 1.000000, 1.034972, 24.068056, 13.722439, 6.702127 +-0.226906, 1.06407, -28.380527, 1.688889, 1.462200, 0.012061, 0.000000, 1496957375.744100, 2.857477, 1.000000, 1.051861, 24.068056, 13.691920, 6.702127 +-0.243956, 1.06897, -28.380479, 1.716667, 1.422519, 0.011755, -0.017857, 1496957375.753500, 2.857669, 1.000000, 1.069028, 24.068056, 13.691920, 6.531915 +-0.261151, 1.07389, -28.380420, 1.716667, 1.417379, 0.011755, 0.000000, 1496957375.764000, 2.857906, 1.000000, 1.086194, 24.068056, 13.664454, 6.531915 +-0.278484, 1.07886, -28.380331, 1.744444, 1.448063, 0.011448, -0.017572, 1496957375.774600, 2.858149, 1.000000, 1.103639, 24.068056, 13.664454, 6.361702 +-0.295953, 1.08385, -28.380237, 1.744444, 1.394881, 0.011448, 0.000000, 1496957375.784200, 2.858372, 1.000000, 1.121083, 24.068056, 13.644617, 6.361702 +-0.313553, 1.08887, -28.380120, 1.772222, 1.384347, 0.011180, -0.015134, 1496957375.793700, 2.858578, 1.000000, 1.138806, 24.055847, 13.644617, 6.212766 +-0.331296, 1.09391, -28.380002, 1.772222, 1.375013, 0.011180, 0.000000, 1496957375.804200, 2.858779, 1.000000, 1.156528, 24.055847, 13.679713, 6.212766 +-0.349185, 1.09901, -28.379884, 1.802778, 1.470176, 0.010912, -0.014876, 1496957375.813800, 2.858984, 1.000000, 1.174556, 24.031433, 13.679713, 6.063830 +-0.36722, 1.10411, -28.379734, 1.802778, 1.459046, 0.010912, 0.000000, 1496957375.824300, 2.859213, 1.000000, 1.192583, 24.031433, 13.708705, 6.063830 +-0.385398, 1.10927, -28.379626, 1.833333, 1.513415, 0.010644, -0.014628, 1496957375.833800, 2.859405, 1.000000, 1.210917, 24.068056, 13.708705, 5.914894 +-0.40372, 1.11444, -28.379523, 1.833333, 1.487178, 0.010644, 0.000000, 1496957375.844400, 2.859636, 1.000000, 1.229250, 24.068056, 13.691920, 5.914894 +-0.4222, 1.11966, -28.379463, 1.863889, 1.546386, 0.010375, -0.014387, 1496957375.853900, 2.859837, 1.000000, 1.247889, 24.031433, 13.691920, 5.765957 +-0.440822, 1.12491, -28.379384, 1.863889, 1.529809, 0.010375, 0.000000, 1496957375.864400, 2.860044, 1.000000, 1.266528, 24.031433, 13.701076, 5.765957 +-0.459598, 1.13021, -28.379343, 1.894444, 1.574303, 0.010107, -0.014155, 1496957375.874300, 2.860283, 1.000000, 1.285472, 24.043640, 13.701076, 5.617021 +-0.478508, 1.13553, -28.379331, 1.894444, 1.482609, 0.010107, 0.000000, 1496957375.883800, 2.860452, 1.000000, 1.304417, 24.043640, 13.665980, 5.617021 +-0.497576, 1.1409, -28.379350, 1.925000, 1.535935, 0.009916, -0.009950, 1496957375.894200, 2.860671, 1.000000, 1.323667, 24.080263, 13.665980, 5.510638 +-0.516775, 1.1463, -28.379359, 1.925000, 1.479308, 0.009916, 0.000000, 1496957375.903700, 2.860872, 1.000000, 1.342917, 24.080263, 13.690394, 5.510638 +-0.536128, 1.15176, -28.379454, 1.952778, 1.552305, 0.009724, -0.009808, 1496957375.914300, 2.861074, 1.000000, 1.362444, 24.031433, 13.690394, 5.404255 +-0.555622, 1.15725, -28.379481, 1.952778, 1.500227, 0.009724, 0.000000, 1496957375.923800, 2.861320, 1.000000, 1.381972, 24.031433, 13.629358, 5.404255 +-0.575262, 1.16279, -28.379603, 1.983333, 1.520437, 0.009494, -0.011588, 1496957375.934300, 2.861503, 1.000000, 1.401806, 24.031433, 13.629358, 5.276596 +-0.595041, 1.16836, -28.379640, 1.983333, 1.468405, 0.009494, 0.000000, 1496957375.943800, 2.861715, 1.000000, 1.421639, 24.031433, 13.658351, 5.276596 +-0.614963, 1.17397, -28.379784, 2.013889, 1.476530, 0.009303, -0.009510, 1496957375.954400, 2.861920, 1.000000, 1.441778, 24.068056, 13.658351, 5.170213 +-0.635029, 1.17962, -28.379839, 2.013889, 1.476920, 0.009303, 0.000000, 1496957375.963900, 2.862157, 1.000000, 1.461917, 24.068056, 13.669032, 5.170213 +-0.655228, 1.18531, -28.379934, 2.047222, 1.445340, 0.009111, -0.009354, 1496957375.974600, 2.862357, 1.000000, 1.482389, 24.055847, 13.669032, 5.063830 +-0.675557, 1.19104, -28.379998, 2.047222, 1.418875, 0.009111, 0.000000, 1496957375.984200, 2.862618, 1.000000, 1.502861, 24.055847, 13.658351, 5.063830 +-0.696059, 1.19681, -28.380054, 2.075000, 1.485185, 0.008843, -0.012920, 1496957375.994500, 2.862782, 1.000000, 1.523611, 24.092470, 13.658351, 4.914894 +-0.71667, 1.20261, -28.380101, 2.075000, 1.398118, 0.008843, 0.000000, 1496957376.003900, 2.863039, 1.000000, 1.544361, 24.092470, 13.754482, 4.914894 +-0.737437, 1.20843, -28.380143, 2.102778, 1.441214, 0.008575, -0.012749, 1496957376.014500, 2.863216, 1.000000, 1.565389, 24.068056, 13.754482, 4.765957 +-0.758327, 1.21429, -28.380178, 2.102778, 1.391089, 0.008575, 0.000000, 1496957376.024000, 2.863441, 1.000000, 1.586417, 24.068056, 13.694972, 4.765957 +-0.779379, 1.22017, -28.380215, 2.133333, 1.455567, 0.008307, -0.012566, 1496957376.034600, 2.863648, 1.000000, 1.607750, 24.092470, 13.694972, 4.617021 +-0.800561, 1.22607, -28.380199, 2.133333, 1.427385, 0.008307, 0.000000, 1496957376.044200, 2.863851, 1.000000, 1.629083, 24.092470, 13.696498, 4.617021 +-0.821901, 1.232, -28.380230, 2.161111, 1.463358, 0.008039, -0.012404, 1496957376.053600, 2.864060, 1.000000, 1.650694, 24.043640, 13.696498, 4.468085 +-0.843366, 1.23796, -28.380151, 2.161111, 1.396880, 0.008039, 0.000000, 1496957376.064100, 2.864284, 1.000000, 1.672306, 24.043640, 13.652246, 4.468085 +-0.864988, 1.24393, -28.380144, 2.191667, 1.454287, 0.007733, -0.013978, 1496957376.073600, 2.864431, 1.000000, 1.694222, 24.116884, 13.652246, 4.297873 +-0.887188, 1.2497, -28.380094, 2.191667, 1.399056, 0.007733, 0.000000, 1496957376.084100, 2.868314, 1.000000, 1.716139, 24.116884, 13.667506, 4.297873 +-0.909693, 1.25543, -28.380045, 2.222222, 1.390177, 0.007388, -0.015509, 1496957376.093600, 2.868510, 1.000000, 1.738361, 24.129091, 13.667506, 4.106383 +-0.932337, 1.26117, -28.379912, 2.222222, 1.369507, 0.007388, 0.000000, 1496957376.104200, 2.868677, 1.000000, 1.760583, 24.129091, 13.656825, 4.106383 +-0.955113, 1.26695, -28.379816, 2.250000, 1.374260, 0.007082, -0.013615, 1496957376.113700, 2.868862, 1.000000, 1.783083, 24.177919, 13.656825, 3.936170 +-0.978012, 1.27274, -28.379652, 2.250000, 1.304604, 0.007082, 0.000000, 1496957376.124300, 2.868999, 1.000000, 1.805583, 24.177919, 13.623255, 3.936170 +-1.00105, 1.27856, -28.379504, 2.277778, 1.357223, 0.006775, -0.013448, 1496957376.133800, 2.869195, 1.000000, 1.828361, 24.214542, 13.623255, 3.765957 +-1.02422, 1.2844, -28.379280, 2.277778, 1.302903, 0.006775, 0.000000, 1496957376.144400, 2.869385, 1.000000, 1.851139, 24.214542, 13.682765, 3.765957 +-1.04752, 1.29028, -28.379098, 2.305556, 1.338038, 0.006431, -0.014946, 1496957376.153900, 2.869518, 1.000000, 1.874194, 24.153505, 13.682765, 3.574468 +-1.07095, 1.29618, -28.378882, 2.305556, 1.316035, 0.006431, 0.000000, 1496957376.164400, 2.869693, 1.000000, 1.897250, 24.153505, 13.682765, 3.574468 +-1.09452, 1.30215, -28.378699, 2.333333, 1.410045, 0.006125, -0.013127, 1496957376.174000, 2.869866, 1.000000, 1.920583, 24.202335, 13.682765, 3.404255 +-1.1182, 1.30816, -28.378497, 2.333333, 1.341994, 0.006125, 0.000000, 1496957376.184500, 2.870058, 1.000000, 1.943917, 24.202335, 13.719387, 3.404255 +-1.14204, 1.31421, -28.378341, 2.361111, 1.427005, 0.005780, -0.014594, 1496957376.194100, 2.870184, 1.000000, 1.967528, 24.141298, 13.719387, 3.212766 +-1.16598, 1.3203, -28.378183, 2.361111, 1.347170, 0.005780, 0.000000, 1496957376.203600, 2.870347, 1.000000, 1.991139, 24.141298, 13.676661, 3.212766 +-1.19007, 1.32645, -28.378088, 2.388889, 1.405765, 0.005435, -0.014423, 1496957376.214100, 2.870529, 1.000000, 2.015028, 24.214542, 13.676661, 3.021277 +-1.21426, 1.33263, -28.377945, 2.388889, 1.306668, 0.005435, 0.000000, 1496957376.224600, 2.870678, 1.000000, 2.038917, 24.214542, 13.684291, 3.021277 +-1.2386, 1.33886, -28.377932, 2.416667, 1.383406, 0.005129, -0.012673, 1496957376.234200, 2.870842, 1.000000, 2.063083, 24.263371, 13.684291, 2.851064 +-1.26305, 1.34513, -28.377813, 2.416667, 1.305956, 0.005129, 0.000000, 1496957376.243800, 2.871015, 1.000000, 2.087250, 24.263371, 13.652246, 2.851064 +-1.26305, 1.34513, -28.377813, 2.444444, 1.305956, 0.004823, -0.012529, 1496957376.254300, 2.871015, 1.000000, 2.111694, 24.190128, 13.652246, 2.680851 +-1.31236, 1.35778, -28.377823, 2.444444, 1.366537, 0.004823, 0.000000, 1496957376.263800, 2.871313, 1.000000, 2.136139, 24.190128, 13.681239, 2.680851 +-1.33721, 1.36417, -28.377852, 2.475000, 1.409374, 0.004555, -0.010827, 1496957376.274400, 2.871422, 1.000000, 2.160889, 24.141298, 13.681239, 2.531915 +-1.36219, 1.37057, -28.377830, 2.475000, 1.340721, 0.004555, 0.000000, 1496957376.283900, 2.871590, 1.000000, 2.185639, 24.141298, 13.655298, 2.531915 +-1.38729, 1.37701, -28.377853, 2.502778, 1.285842, 0.004249, -0.012236, 1496957376.294600, 2.871712, 1.000000, 2.210667, 24.165712, 13.655298, 2.361702 +-1.4125, 1.38347, -28.377841, 2.502778, 1.187773, 0.004249, 0.000000, 1496957376.304200, 2.871855, 1.000000, 2.235694, 24.165712, 13.688869, 2.361702 +-1.43784, 1.38997, -28.377850, 2.541667, 1.226265, 0.003942, -0.012049, 1496957376.313900, 2.871957, 1.000000, 2.261111, 24.141298, 13.688869, 2.191489 +-1.46331, 1.39649, -28.377861, 2.541667, 1.281220, 0.003942, 0.000000, 1496957376.324400, 2.872052, 1.000000, 2.286528, 24.141298, 13.678187, 2.191489 +-1.48891, 1.40302, -28.377820, 2.569444, 1.309625, 0.003675, -0.010429, 1496957376.334000, 2.872186, 1.000000, 2.312222, 24.202335, 13.678187, 2.042553 +-1.51465, 1.40957, -28.377804, 2.569444, 1.310357, 0.003675, 0.000000, 1496957376.344600, 2.872282, 1.000000, 2.337917, 24.202335, 13.665980, 2.042553 +-1.54051, 1.41613, -28.377758, 2.597222, 1.308170, 0.003407, -0.010317, 1496957376.354100, 2.872360, 1.000000, 2.363889, 24.153505, 13.665980, 1.893617 +-1.56648, 1.4227, -28.377702, 2.597222, 1.226956, 0.003407, 0.000000, 1496957376.363600, 2.872464, 1.000000, 2.389861, 24.153505, 13.635462, 1.893617 +-1.59257, 1.42931, -28.377645, 2.597222, 1.205878, 0.003407, 0.000000, 1496957376.373900, 2.872574, 1.000000, 2.415833, 24.153505, 13.635462, 1.893617 +-1.61878, 1.43595, -28.377554, 2.622222, 1.159727, 0.003139, -0.010218, 1496957376.384600, 2.872624, 1.000000, 2.442056, 24.238956, 13.655298, 1.744681 +-1.64511, 1.44262, -28.377413, 2.636111, 1.196849, 0.002909, -0.008712, 1496957376.394500, 2.872702, 1.000000, 2.468417, 24.251163, 13.655298, 1.617021 +-1.67155, 1.4493, -28.377309, 2.636111, 1.164627, 0.002909, 0.000000, 1496957376.404200, 2.872807, 1.000000, 2.494778, 24.251163, 13.669032, 1.617021 +-1.69811, 1.45601, -28.377108, 2.661111, 1.194211, 0.002679, -0.008630, 1496957376.415000, 2.872903, 1.000000, 2.521389, 24.251163, 13.669032, 1.489362 +-1.7248, 1.46275, -28.376959, 2.661111, 1.211299, 0.002679, 0.000000, 1496957376.424700, 2.872968, 1.000000, 2.548000, 24.251163, 13.678187, 1.489362 +-1.75159, 1.46953, -28.376705, 2.688889, 1.198929, 0.002450, -0.008541, 1496957376.434300, 2.873065, 1.000000, 2.574889, 24.263371, 13.678187, 1.361702 +-1.7785, 1.47634, -28.376532, 2.688889, 1.190837, 0.002450, 0.000000, 1496957376.443900, 2.873094, 1.000000, 2.601778, 24.263371, 13.687343, 1.361702 +-1.80552, 1.48318, -28.376226, 2.725000, 1.200088, 0.002258, -0.007023, 1496957376.454400, 2.873180, 1.000000, 2.629028, 24.287785, 13.687343, 1.255319 +-1.83269, 1.49004, -28.376024, 2.725000, 1.231558, 0.002258, 0.000000, 1496957376.463900, 2.873210, 1.000000, 2.656278, 24.287785, 13.669032, 1.255319 +-1.85995, 1.49694, -28.375702, 2.738889, 1.202818, 0.002067, -0.006988, 1496957376.474500, 2.873298, 1.000000, 2.683667, 24.275578, 13.669032, 1.148936 +-1.88734, 1.50385, -28.375454, 2.738889, 1.199289, 0.002067, 0.000000, 1496957376.484000, 2.873363, 1.000000, 2.711056, 24.275578, 13.676661, 1.148936 +-1.91484, 1.51078, -28.375179, 2.761111, 1.177203, 0.001914, -0.005545, 1496957376.494500, 2.873416, 1.000000, 2.738667, 24.287785, 13.676661, 1.063830 +-1.94246, 1.51774, -28.374964, 2.761111, 1.179722, 0.001914, 0.000000, 1496957376.504000, 2.873470, 1.000000, 2.766278, 24.287785, 13.630884, 1.063830 +-1.99808, 1.53175, -28.374552, 2.797222, 1.298069, 0.001722, -0.006842, 1496957376.514500, 2.873625, 1.000000, 2.794250, 24.251163, 13.630884, 0.957447 +-1.99808, 1.53175, -28.374552, 2.797222, 1.298069, 0.001722, 0.000000, 1496957376.524100, 2.873625, 1.000000, 2.822222, 24.251163, 13.704127, 0.957447 +-2.02606, 1.53878, -28.374335, 2.811111, 1.215507, 0.001531, -0.006808, 1496957376.534700, 2.873703, 1.000000, 2.850333, 24.214542, 13.704127, 0.851064 +-2.05417, 1.54584, -28.374207, 2.811111, 1.236594, 0.001531, 0.000000, 1496957376.544300, 2.873768, 1.000000, 2.878444, 24.214542, 13.705653, 0.851064 +-2.08238, 1.55292, -28.374050, 2.836111, 1.143132, 0.001378, -0.005398, 1496957376.553800, 2.873776, 1.000000, 2.906806, 24.226749, 13.705653, 0.765957 +-2.11073, 1.56003, -28.373933, 2.836111, 1.248027, 0.001378, 0.000000, 1496957376.564400, 2.873832, 1.000000, 2.935167, 24.226749, 13.693446, 0.765957 +-2.13917, 1.56718, -28.373824, 2.861111, 1.173810, 0.001225, -0.005351, 1496957376.574000, 2.873920, 1.000000, 2.963778, 24.202335, 13.693446, 0.680851 +-2.16775, 1.57436, -28.373758, 2.861111, 1.228400, 0.001225, 0.000000, 1496957376.584600, 2.873964, 1.000000, 2.992389, 24.202335, 13.664454, 0.680851 +-2.19642, 1.58156, -28.373631, 2.888889, 1.169136, 0.001148, -0.002650, 1496957376.594100, 2.874005, 1.000000, 3.021278, 24.251163, 13.664454, 0.638298 +-2.22523, 1.5888, -28.373589, 2.888889, 1.253810, 0.001148, 0.000000, 1496957376.603600, 2.874086, 1.000000, 3.050167, 24.251163, 13.652246, 0.638298 +-2.25416, 1.59605, -28.373487, 2.922222, 1.203481, 0.001072, -0.002620, 1496957376.614100, 2.874110, 1.000000, 3.079389, 24.177919, 13.652246, 0.595745 +-2.2832, 1.60336, -28.373496, 2.922222, 1.246997, 0.001072, 0.000000, 1496957376.623500, 2.874153, 1.000000, 3.108611, 24.177919, 13.694972, 0.595745 +-2.31234, 1.61068, -28.373356, 2.947222, 1.135419, 0.000995, -0.002597, 1496957376.634000, 2.874157, 1.000000, 3.138083, 24.202335, 13.694972, 0.553191 +-2.34159, 1.61806, -28.373400, 2.947222, 1.180216, 0.000995, 0.000000, 1496957376.644600, 2.874210, 1.000000, 3.167556, 24.202335, 13.643091, 0.553191 +-2.37098, 1.62546, -28.373288, 2.972222, 1.224249, 0.000919, -0.002576, 1496957376.654100, 2.874281, 1.000000, 3.197278, 24.226749, 13.643091, 0.510638 +-2.40047, 1.63289, -28.373329, 2.972222, 1.221666, 0.000919, 0.000000, 1496957376.663500, 2.874256, 1.000000, 3.227000, 24.226749, 13.710231, 0.510638 +-2.43008, 1.64034, -28.373279, 2.994444, 1.181297, 0.000880, -0.001278, 1496957376.674300, 2.874284, 1.000000, 3.256944, 24.226749, 13.710231, 0.489362 +-2.45981, 1.64781, -28.373277, 2.994444, 1.218088, 0.000880, 0.000000, 1496957376.683800, 2.874299, 1.000000, 3.286889, 24.226749, 13.638514, 0.489362 +-2.48964, 1.6553, -28.373250, 3.008333, 1.163462, 0.000880, 0.000000, 1496957376.694300, 2.874309, 1.000000, 3.316972, 24.202335, 13.638514, 0.489362 +-2.51961, 1.66281, -28.373249, 3.008333, 1.213436, 0.000880, 0.000000, 1496957376.703900, 2.874369, 1.000000, 3.347056, 24.202335, 13.658351, 0.489362 +-2.54968, 1.67033, -28.373214, 3.044445, 1.151858, 0.000842, -0.001257, 1496957376.714500, 2.874395, 1.000000, 3.377500, 24.275578, 13.658351, 0.468085 +-2.57988, 1.67788, -28.373202, 3.044445, 1.194751, 0.000842, 0.000000, 1496957376.724100, 2.874392, 1.000000, 3.407944, 24.275578, 13.641565, 0.468085 +-2.61017, 1.68545, -28.373172, 3.066667, 1.115898, 0.000842, 0.000000, 1496957376.734600, 2.874422, 1.000000, 3.438611, 24.251163, 13.641565, 0.468085 +-2.6406, 1.69304, -28.373134, 3.066667, 1.192154, 0.000842, 0.000000, 1496957376.744200, 2.874462, 1.000000, 3.469278, 24.251163, 13.673610, 0.468085 +-2.67112, 1.70062, -28.373064, 3.091667, 1.086607, 0.000842, 0.000000, 1496957376.753600, 2.874501, 1.000000, 3.500194, 24.214542, 13.673610, 0.468085 +-2.70178, 1.70824, -28.372978, 3.091667, 1.209958, 0.000842, 0.000000, 1496957376.764200, 2.874500, 1.000000, 3.531111, 24.214542, 13.702601, 0.468085 +-2.73252, 1.71588, -28.372883, 3.113889, 1.088474, 0.000842, 0.000000, 1496957376.773700, 2.874537, 1.000000, 3.562250, 24.251163, 13.702601, 0.468085 +-2.76339, 1.72355, -28.372801, 3.113889, 1.172758, 0.000842, 0.000000, 1496957376.784200, 2.874584, 1.000000, 3.593389, 24.251163, 13.679713, 0.468085 +-2.79437, 1.73125, -28.372662, 3.125000, 1.141812, 0.000842, 0.000000, 1496957376.793800, 2.874602, 1.000000, 3.624639, 24.214542, 13.679713, 0.468085 +-2.82546, 1.73901, -28.372598, 3.125000, 1.209215, 0.000842, 0.000000, 1496957376.804300, 2.874632, 1.000000, 3.655889, 24.214542, 13.702601, 0.468085 +-2.85665, 1.74677, -28.372439, 3.158333, 1.129978, 0.000842, 0.000000, 1496957376.814100, 2.874624, 1.000000, 3.687472, 24.214542, 13.702601, 0.468085 +-2.88796, 1.75459, -28.372425, 3.158333, 1.213509, 0.000842, 0.000000, 1496957376.824600, 2.874625, 1.000000, 3.719056, 24.214542, 13.681239, 0.468085 +-2.91937, 1.76244, -28.372295, 3.183333, 1.131851, 0.000842, 0.000000, 1496957376.834200, 2.874687, 1.000000, 3.750889, 24.275578, 13.681239, 0.468085 +-2.95089, 1.77033, -28.372322, 3.183333, 1.159115, 0.000842, 0.000000, 1496957376.843800, 2.874691, 1.000000, 3.782722, 24.275578, 13.626307, 0.468085 +-2.98254, 1.77823, -28.372226, 3.205555, 1.179048, 0.000842, 0.000000, 1496957376.854300, 2.874718, 1.000000, 3.814778, 24.202335, 13.626307, 0.468085 +-3.01427, 1.78618, -28.372227, 3.205555, 1.106220, 0.000842, 0.000000, 1496957376.863800, 2.874736, 1.000000, 3.846833, 24.202335, 13.675136, 0.468085 +-3.04611, 1.79415, -28.372134, 3.230556, 1.080408, 0.000842, 0.000000, 1496957376.874900, 2.874749, 1.000000, 3.879139, 24.263371, 13.675136, 0.468085 +-3.07807, 1.80213, -28.372081, 3.230556, 1.118288, 0.000842, 0.000000, 1496957376.884400, 2.874765, 1.000000, 3.911444, 24.263371, 13.681239, 0.468085 +-3.11015, 1.81012, -28.372087, 3.244444, 1.154624, 0.000842, 0.000000, 1496957376.895700, 2.874817, 1.000000, 3.943889, 24.202335, 13.681239, 0.468085 +-3.14236, 1.81813, -28.372055, 3.244444, 1.266065, 0.000842, 0.000000, 1496957376.904600, 2.874806, 1.000000, 3.976333, 24.202335, 13.723965, 0.468085 +-3.17468, 1.82615, -28.372093, 3.244444, 1.204782, 0.000842, 0.000000, 1496957376.914200, 2.874705, 1.000000, 4.008778, 24.312199, 13.723965, 0.468085 +-3.20712, 1.8342, -28.372133, 3.277778, 1.225952, 0.000842, 0.000000, 1496957376.923700, 2.874746, 1.000000, 4.041556, 24.312199, 13.652246, 0.468085 +-3.23966, 1.84227, -28.372204, 3.277778, 1.115389, 0.000842, 0.000000, 1496957376.934200, 2.874738, 1.000000, 4.074333, 24.177919, 13.652246, 0.468085 +-3.27232, 1.85036, -28.372371, 3.288889, 1.168003, 0.000842, 0.000000, 1496957376.943700, 2.874767, 1.000000, 4.107222, 24.177919, 13.684291, 0.468085 +-3.30509, 1.85845, -28.372504, 3.288889, 1.116849, 0.000842, 0.000000, 1496957376.954300, 2.874700, 1.000000, 4.140111, 24.202335, 13.684291, 0.468085 +-3.33798, 1.86657, -28.372689, 3.319444, 1.178039, 0.000842, 0.000000, 1496957376.963900, 2.874712, 1.000000, 4.173306, 24.202335, 13.646143, 0.468085 +-3.37096, 1.8747, -28.372879, 3.319444, 1.065056, 0.000842, 0.000000, 1496957376.974500, 2.874713, 1.000000, 4.206500, 24.202335, 13.646143, 0.468085 +-3.40405, 1.88287, -28.373104, 3.347222, 1.085638, 0.000842, 0.000000, 1496957376.984100, 2.874707, 1.000000, 4.239972, 24.202335, 13.687343, 0.468085 +-3.43724, 1.89107, -28.373336, 3.347222, 1.062707, 0.000842, 0.000000, 1496957376.993800, 2.874721, 1.000000, 4.273444, 24.202335, 13.687343, 0.468085 +-3.47055, 1.89931, -28.373529, 3.369444, 1.154505, 0.000842, 0.000000, 1496957377.004300, 2.874730, 1.000000, 4.307139, 24.202335, 13.673610, 0.468085 +-3.50396, 1.90757, -28.373696, 3.369444, 1.115242, 0.000842, 0.000000, 1496957377.013800, 2.874749, 1.000000, 4.340833, 24.177919, 13.673610, 0.468085 +-3.53747, 1.91588, -28.373917, 3.394444, 1.143040, 0.000842, 0.000000, 1496957377.024300, 2.874750, 1.000000, 4.374778, 24.177919, 13.694972, 0.468085 +-3.5711, 1.92423, -28.374067, 3.416667, 1.127662, 0.000842, 0.000000, 1496957377.033800, 2.874765, 1.000000, 4.408944, 24.129091, 13.694972, 0.468085 +-3.60484, 1.93261, -28.374274, 3.416667, 1.146825, 0.000842, 0.000000, 1496957377.044300, 2.874834, 1.000000, 4.443111, 24.129091, 13.704127, 0.468085 +-3.63865, 1.94105, -28.374399, 3.416667, 1.036807, 0.000842, 0.000000, 1496957377.053900, 2.874852, 1.000000, 4.477278, 24.080263, 13.704127, 0.468085 +-3.67258, 1.94952, -28.374564, 3.438889, 1.007348, 0.000842, 0.000000, 1496957377.064500, 2.874912, 1.000000, 4.511667, 24.080263, 13.702601, 0.468085 +-3.70657, 1.95803, -28.374700, 3.438889, 0.988853, 0.000842, 0.000000, 1496957377.074000, 2.874965, 1.000000, 4.546056, 24.068056, 13.702601, 0.468085 +-3.74317, 1.96521, -28.375017, 3.461111, 1.026216, 0.000842, 0.000000, 1496957377.084600, 2.886206, 1.000000, 4.580667, 24.068056, 13.646143, 0.468085 +-3.7795, 1.97266, -28.375221, 3.461111, 1.017103, 0.000842, 0.000000, 1496957377.094100, 2.886277, 1.000000, 4.615278, 24.068056, 13.646143, 0.468085 +-3.81595, 1.98015, -28.375404, 3.472222, 1.042057, 0.000842, 0.000000, 1496957377.103600, 2.886352, 1.000000, 4.650000, 24.104677, 13.682765, 0.468085 +-3.85249, 1.98767, -28.375605, 3.472222, 1.079778, 0.000842, 0.000000, 1496957377.114100, 2.886409, 1.000000, 4.684722, 24.092470, 13.682765, 0.468085 +-3.88914, 1.99521, -28.375778, 3.502778, 1.092841, 0.000842, 0.000000, 1496957377.123600, 2.886483, 1.000000, 4.719750, 24.092470, 13.641565, 0.468085 +-3.92593, 2.00277, -28.375936, 3.502778, 1.176065, 0.000842, 0.000000, 1496957377.134100, 2.886541, 1.000000, 4.754778, 24.007019, 13.641565, 0.468085 +-3.9628, 2.01035, -28.376096, 3.525000, 1.075560, 0.000842, 0.000000, 1496957377.143500, 2.886620, 1.000000, 4.790028, 24.007019, 13.754482, 0.468085 +-3.99976, 2.01795, -28.376261, 3.525000, 1.005757, 0.000842, 0.000000, 1496957377.154100, 2.886702, 1.000000, 4.825278, 23.909361, 13.754482, 0.468085 +-4.03681, 2.02557, -28.376389, 3.544445, 0.954829, 0.000842, 0.000000, 1496957377.163500, 2.886760, 1.000000, 4.860722, 23.909361, 13.656825, 0.468085 +-4.07396, 2.03324, -28.376557, 3.544445, 1.004452, 0.000842, 0.000000, 1496957377.174100, 2.886829, 1.000000, 4.896167, 23.909361, 13.656825, 0.468085 +-4.11122, 2.0409, -28.376647, 3.563889, 0.970663, 0.000842, 0.000000, 1496957377.183600, 2.886899, 1.000000, 4.931806, 23.909361, 13.617151, 0.468085 +-4.14858, 2.04859, -28.376819, 3.563889, 1.041303, 0.000842, 0.000000, 1496957377.194100, 2.886977, 1.000000, 4.967444, 23.909361, 13.617151, 0.468085 +-4.18604, 2.05633, -28.376898, 3.577778, 1.040497, 0.000842, 0.000000, 1496957377.203500, 2.887034, 1.000000, 5.003222, 23.897154, 13.722439, 0.468085 +-4.2236, 2.06411, -28.377053, 3.577778, 1.038359, 0.000842, 0.000000, 1496957377.214000, 2.887055, 1.000000, 5.039000, 23.701839, 13.722439, 0.468085 +-4.26125, 2.07192, -28.377177, 3.611111, 1.054787, 0.000880, 0.001060, 1496957377.224500, 2.887110, 1.000000, 5.075111, 23.701839, 13.739223, 0.489362 +-4.29902, 2.07976, -28.377266, 3.611111, 1.094116, 0.000880, 0.000000, 1496957377.234000, 2.887105, 1.000000, 5.111222, 23.433279, 13.739223, 0.489362 +-4.33689, 2.08762, -28.377384, 3.630556, 1.092283, 0.000880, 0.000000, 1496957377.244600, 2.887154, 1.000000, 5.147528, 23.433279, 13.655298, 0.489362 +-4.37485, 2.09552, -28.377434, 3.630556, 1.060134, 0.000880, 0.000000, 1496957377.254100, 2.887196, 1.000000, 5.183833, 23.128099, 13.655298, 0.489362 +-4.41292, 2.10342, -28.377518, 3.641667, 1.019841, 0.000919, 0.001051, 1496957377.263500, 2.887228, 1.000000, 5.220250, 23.128099, 13.682765, 0.510638 +-4.45107, 2.11135, -28.377511, 3.641667, 0.962318, 0.000919, 0.000000, 1496957377.274100, 2.887247, 1.000000, 5.256667, 22.932783, 13.682765, 0.510638 +-4.48934, 2.1193, -28.377488, 3.672222, 0.996428, 0.000919, 0.000000, 1496957377.283500, 2.887275, 1.000000, 5.293389, 22.932783, 13.771267, 0.510638 +-4.52769, 2.12727, -28.377416, 3.672222, 0.982450, 0.000919, 0.000000, 1496957377.294100, 2.887318, 1.000000, 5.330111, 22.932783, 13.771267, 0.510638 +-4.56616, 2.13528, -28.377357, 3.680556, 1.045144, 0.000919, 0.000000, 1496957377.304600, 2.887358, 1.000000, 5.366917, 22.993820, 13.739223, 0.510638 +-4.60473, 2.14328, -28.377266, 3.680556, 1.038420, 0.000919, 0.000000, 1496957377.314100, 2.887373, 1.000000, 5.403722, 22.749676, 13.739223, 0.510638 +-4.64339, 2.1513, -28.377174, 3.708333, 0.990039, 0.000919, 0.000000, 1496957377.323600, 2.887409, 1.000000, 5.440806, 22.749676, 13.701076, 0.510638 +-4.68214, 2.15931, -28.377060, 3.708333, 0.933273, 0.000919, 0.000000, 1496957377.334100, 2.887446, 1.000000, 5.477889, 22.652018, 13.701076, 0.510638 +-4.72099, 2.16736, -28.376938, 3.727778, 0.934453, 0.000919, 0.000000, 1496957377.343600, 2.887471, 1.000000, 5.515167, 22.652018, 13.636988, 0.510638 +-4.75995, 2.1754, -28.376797, 3.727778, 0.967011, 0.000919, 0.000000, 1496957377.354200, 2.887479, 1.000000, 5.552444, 22.517738, 13.636988, 0.510638 +-4.79901, 2.18347, -28.376658, 3.744444, 1.052445, 0.000919, 0.000000, 1496957377.363800, 2.887539, 1.000000, 5.589889, 22.517738, 13.687343, 0.510638 +-4.83815, 2.19152, -28.376555, 3.744444, 0.937968, 0.000919, 0.000000, 1496957377.374500, 2.887537, 1.000000, 5.627333, 22.493324, 13.687343, 0.510638 +-4.87741, 2.1996, -28.376441, 3.752778, 1.006726, 0.000919, 0.000000, 1496957377.384100, 2.887576, 1.000000, 5.664861, 22.493324, 13.716334, 0.510638 +-4.91674, 2.20767, -28.376322, 3.752778, 0.952787, 0.000919, 0.000000, 1496957377.393700, 2.887631, 1.000000, 5.702389, 22.432287, 13.716334, 0.510638 +-4.9562, 2.21575, -28.376235, 3.769444, 0.996981, 0.000919, 0.000000, 1496957377.404800, 2.887633, 1.000000, 5.740083, 22.432287, 13.727016, 0.510638 +-4.99574, 2.22387, -28.376149, 3.769444, 0.982431, 0.000919, 0.000000, 1496957377.413600, 2.887686, 1.000000, 5.777778, 22.310215, 13.727016, 0.510638 +-5.03539, 2.232, -28.376073, 3.800000, 1.007432, 0.000919, 0.000000, 1496957377.424300, 2.887706, 1.000000, 5.815778, 22.310215, 13.684291, 0.510638 +-5.07512, 2.24016, -28.376072, 3.800000, 1.007064, 0.000919, 0.000000, 1496957377.433800, 2.887777, 1.000000, 5.853778, 22.249180, 13.684291, 0.510638 +-5.11493, 2.24831, -28.376005, 3.816667, 0.869583, 0.000919, 0.000000, 1496957377.444400, 2.887764, 1.000000, 5.891944, 22.249180, 13.656825, 0.510638 +-5.15484, 2.25651, -28.376021, 3.816667, 0.911019, 0.000919, 0.000000, 1496957377.453900, 2.887825, 1.000000, 5.930111, 22.188145, 13.656825, 0.510638 +-5.1948, 2.26473, -28.375985, 3.825000, 0.821029, 0.000957, 0.001001, 1496957377.464400, 2.887882, 1.000000, 5.968361, 22.188145, 13.733120, 0.531915 +-5.23487, 2.27298, -28.376049, 3.825000, 0.873141, 0.000957, 0.000000, 1496957377.473900, 2.887896, 1.000000, 6.006611, 22.163729, 13.733120, 0.531915 +-5.275, 2.28127, -28.376047, 3.850000, 0.859244, 0.000995, 0.000994, 1496957377.484400, 2.887911, 1.000000, 6.045111, 22.163729, 13.676661, 0.553191 +-5.31524, 2.28957, -28.376153, 3.850000, 0.895603, 0.000995, 0.000000, 1496957377.494000, 2.887973, 1.000000, 6.083611, 22.163729, 13.676661, 0.553191 +-5.35556, 2.29788, -28.376254, 3.861111, 0.943850, 0.000995, 0.000000, 1496957377.504500, 2.888014, 1.000000, 6.122222, 22.040131, 13.647669, 0.553191 +-5.43647, 2.31452, -28.376581, 3.861111, 0.914915, 0.000995, 0.000000, 1496957377.514100, 2.888077, 1.000000, 6.160833, 21.968414, 13.647669, 0.553191 +-5.43647, 2.31452, -28.376581, 3.880556, 0.914915, 0.001033, 0.000986, 1496957377.523600, 2.888077, 1.000000, 6.199639, 21.968414, 13.707179, 0.574468 +-5.47703, 2.32286, -28.376743, 3.880556, 0.819453, 0.001033, 0.000000, 1496957377.534200, 2.888113, 1.000000, 6.238444, 21.919584, 13.707179, 0.574468 +-5.51767, 2.33119, -28.376978, 3.905555, 0.778114, 0.001072, 0.000980, 1496957377.543700, 2.888158, 1.000000, 6.277500, 21.919584, 13.685817, 0.595745 +-5.55842, 2.33956, -28.377213, 3.905555, 0.868909, 0.001072, 0.000000, 1496957377.554300, 2.888182, 1.000000, 6.316556, 21.795986, 13.685817, 0.595745 +-5.59925, 2.34792, -28.377462, 3.916667, 0.812540, 0.001148, 0.001954, 1496957377.563700, 2.888172, 1.000000, 6.355722, 21.795986, 13.594263, 0.638298 +-5.64016, 2.35631, -28.377758, 3.916667, 0.923670, 0.001148, 0.000000, 1496957377.574300, 2.888232, 1.000000, 6.394889, 21.698330, 13.594263, 0.638298 +-5.68113, 2.36471, -28.378007, 3.936111, 0.789138, 0.001187, 0.000972, 1496957377.583800, 2.888256, 1.000000, 6.434250, 21.698330, 13.696498, 0.659574 +-5.72217, 2.37315, -28.378333, 3.936111, 0.728395, 0.001187, 0.000000, 1496957377.594500, 2.888268, 1.000000, 6.473611, 21.698330, 13.696498, 0.659574 +-5.76329, 2.38162, -28.378560, 3.952778, 0.742090, 0.001225, 0.000968, 1496957377.604000, 2.888322, 1.000000, 6.513139, 21.747158, 13.641565, 0.680851 +-5.80446, 2.39011, -28.378895, 3.952778, 0.703372, 0.001225, 0.000000, 1496957377.614600, 2.888322, 1.000000, 6.552667, 21.722744, 13.641565, 0.680851 +-5.84572, 2.39866, -28.379110, 3.972222, 0.759954, 0.001225, 0.000000, 1496957377.624100, 2.888354, 1.000000, 6.592389, 21.722744, 13.684291, 0.680851 +-5.88702, 2.40724, -28.379417, 3.972222, 0.720443, 0.001225, 0.000000, 1496957377.633500, 2.888412, 1.000000, 6.632111, 21.649500, 13.684291, 0.680851 +-5.92843, 2.41585, -28.379709, 3.997222, 0.805497, 0.001225, 0.000000, 1496957377.644100, 2.888439, 1.000000, 6.672083, 21.649500, 13.691920, 0.680851 +-5.96989, 2.42451, -28.379986, 3.997222, 0.802462, 0.001225, 0.000000, 1496957377.653500, 2.888538, 1.000000, 6.712056, 21.600672, 13.691920, 0.680851 +-6.01144, 2.43318, -28.380329, 4.013889, 0.797086, 0.001225, 0.000000, 1496957377.664100, 2.888606, 1.000000, 6.752194, 21.600672, 13.612574, 0.680851 +-6.05305, 2.4419, -28.380625, 4.013889, 0.820085, 0.001225, 0.000000, 1496957377.673500, 2.888668, 1.000000, 6.792333, 21.466393, 13.612574, 0.680851 +-6.09472, 2.45063, -28.380966, 4.022222, 0.703711, 0.001225, 0.000000, 1496957377.684000, 2.888765, 1.000000, 6.832556, 21.466393, 13.720913, 0.680851 +-6.13648, 2.45938, -28.381302, 4.022222, 0.785993, 0.001225, 0.000000, 1496957377.693500, 2.888839, 1.000000, 6.872778, 21.466393, 13.720913, 0.680851 +-6.17829, 2.46812, -28.381614, 4.038889, 0.642713, 0.001225, 0.000000, 1496957377.704100, 2.888869, 1.000000, 6.913167, 21.344320, 13.658351, 0.680851 +-6.22018, 2.47689, -28.381948, 4.038889, 0.695060, 0.001225, 0.000000, 1496957377.714600, 2.889007, 1.000000, 6.953556, 21.393148, 13.658351, 0.680851 +-6.26213, 2.48565, -28.382226, 4.061111, 0.675722, 0.001225, 0.000000, 1496957377.724200, 2.889046, 1.000000, 6.994167, 21.393148, 13.647669, 0.680851 +-6.30415, 2.49439, -28.382547, 4.061111, 0.612346, 0.001225, 0.000000, 1496957377.733800, 2.889119, 1.000000, 7.034778, 21.417562, 13.647669, 0.680851 +-6.34625, 2.50313, -28.382877, 4.075000, 0.679851, 0.001225, 0.000000, 1496957377.744300, 2.889221, 1.000000, 7.075528, 21.417562, 13.640039, 0.680851 +-6.38841, 2.51187, -28.383196, 4.075000, 0.677428, 0.001225, 0.000000, 1496957377.753800, 2.889255, 1.000000, 7.116278, 21.368734, 13.640039, 0.680851 +-6.43067, 2.52061, -28.383570, 4.088889, 0.780516, 0.001225, 0.000000, 1496957377.764300, 2.889356, 1.000000, 7.157167, 21.368734, 13.653772, 0.680851 +-6.47299, 2.52933, -28.383937, 4.088889, 0.758848, 0.001225, 0.000000, 1496957377.773800, 2.889369, 1.000000, 7.198056, 21.295490, 13.653772, 0.680851 +-6.5154, 2.53803, -28.384363, 4.102778, 0.713486, 0.001225, 0.000000, 1496957377.784300, 2.889447, 1.000000, 7.239083, 21.295490, 13.650721, 0.680851 +-6.55789, 2.54675, -28.384739, 4.102778, 0.716909, 0.001225, 0.000000, 1496957377.793900, 2.889512, 1.000000, 7.280111, 21.295490, 13.650721, 0.680851 +-6.60041, 2.55544, -28.385185, 4.116667, 0.602251, 0.001225, 0.000000, 1496957377.804400, 2.889479, 1.000000, 7.321278, 21.197834, 13.643091, 0.680851 +-6.64302, 2.56415, -28.385613, 4.116667, 0.678231, 0.001225, 0.000000, 1496957377.813900, 2.889556, 1.000000, 7.362444, 21.197834, 13.643091, 0.680851 +-6.68567, 2.57284, -28.386039, 4.125000, 0.596654, 0.001225, 0.000000, 1496957377.824400, 2.889552, 1.000000, 7.403694, 21.185625, 13.673610, 0.680851 +-6.7284, 2.58154, -28.386497, 4.125000, 0.615710, 0.001225, 0.000000, 1496957377.833900, 2.889589, 1.000000, 7.444944, 21.197834, 13.673610, 0.680851 +-6.77118, 2.59028, -28.386960, 4.144444, 0.619633, 0.001225, 0.000000, 1496957377.844400, 2.889622, 1.000000, 7.486389, 21.197834, 13.655298, 0.680851 +-6.81404, 2.599, -28.387399, 4.144444, 0.681414, 0.001225, 0.000000, 1496957377.853900, 2.889624, 1.000000, 7.527833, 21.173418, 13.655298, 0.680851 +-6.85696, 2.60776, -28.387849, 4.158333, 0.718839, 0.001225, 0.000000, 1496957377.864400, 2.889698, 1.000000, 7.569417, 21.173418, 13.630884, 0.680851 +-6.89993, 2.61652, -28.388230, 4.158333, 0.532554, 0.001225, 0.000000, 1496957377.873900, 2.889725, 1.000000, 7.611000, 21.149004, 13.630884, 0.680851 +-6.94296, 2.6253, -28.388582, 4.172222, 0.570883, 0.001225, 0.000000, 1496957377.884700, 2.889793, 1.000000, 7.652722, 21.149004, 13.665980, 0.680851 +-6.98603, 2.63409, -28.388934, 4.172222, 0.551014, 0.001225, 0.000000, 1496957377.894300, 2.889828, 1.000000, 7.694444, 21.173418, 13.665980, 0.680851 +-7.02918, 2.6429, -28.389284, 4.177778, 0.585207, 0.001187, -0.000916, 1496957377.904100, 2.889873, 1.000000, 7.736222, 21.173418, 13.673610, 0.659574 +-7.0724, 2.65173, -28.389619, 4.177778, 0.688430, 0.001187, 0.000000, 1496957377.914100, 2.889909, 1.000000, 7.778000, 21.173418, 13.673610, 0.659574 +-7.11568, 2.66058, -28.390044, 4.191667, 0.688495, 0.001148, -0.000913, 1496957377.923600, 2.889991, 1.000000, 7.819917, 21.014725, 13.707179, 0.638298 +-7.15903, 2.66944, -28.390470, 4.191667, 0.728472, 0.001148, 0.000000, 1496957377.934100, 2.890035, 1.000000, 7.861833, 21.014725, 13.707179, 0.638298 +-7.20243, 2.6783, -28.390967, 4.205555, 0.641859, 0.001110, -0.000910, 1496957377.943600, 2.890114, 1.000000, 7.903889, 20.819410, 13.727016, 0.617021 +-7.24591, 2.68717, -28.391489, 4.205555, 0.690402, 0.001110, 0.000000, 1496957377.954200, 2.890145, 1.000000, 7.945944, 20.819410, 13.727016, 0.617021 +-7.28943, 2.69605, -28.392067, 4.222222, 0.614139, 0.001072, -0.000907, 1496957377.963800, 2.890172, 1.000000, 7.988167, 20.672922, 13.658351, 0.595745 +-7.33304, 2.70493, -28.392699, 4.222222, 0.651146, 0.001072, 0.000000, 1496957377.974300, 2.890230, 1.000000, 8.030389, 20.672922, 13.658351, 0.595745 +-7.37672, 2.7138, -28.393409, 4.233333, 0.723171, 0.000995, -0.001808, 1496957377.983900, 2.890262, 1.000000, 8.072722, 20.709545, 13.725491, 0.553191 +-7.42048, 2.72267, -28.394107, 4.233333, 0.736657, 0.000995, 0.000000, 1496957377.994500, 2.890296, 1.000000, 8.115056, 20.648508, 13.725491, 0.553191 +-7.46431, 2.73154, -28.394891, 4.247222, 0.746956, 0.000880, -0.002704, 1496957378.004100, 2.890296, 1.000000, 8.157528, 20.648508, 13.649195, 0.489362 +-7.50817, 2.7404, -28.395651, 4.247222, 0.623040, 0.000880, 0.000000, 1496957378.013600, 2.890331, 1.000000, 8.200000, 20.624094, 13.649195, 0.489362 +-7.55215, 2.74926, -28.396500, 4.255556, 0.622122, 0.000765, -0.002698, 1496957378.024100, 2.890396, 1.000000, 8.242556, 20.624094, 13.664454, 0.425532 +-7.59617, 2.75816, -28.397405, 4.255556, 0.732242, 0.000765, 0.000000, 1496957378.033600, 2.890429, 1.000000, 8.285111, 20.624094, 13.664454, 0.425532 +-7.64025, 2.76705, -28.398361, 4.269444, 0.674356, 0.000651, -0.002689, 1496957378.044100, 2.890442, 1.000000, 8.327806, 20.624094, 13.688869, 0.361702 +-7.6844, 2.77599, -28.399334, 4.269444, 0.711341, 0.000651, 0.000000, 1496957378.053600, 2.890474, 1.000000, 8.370500, 20.672922, 13.688869, 0.361702 +-7.7286, 2.78492, -28.400280, 4.286111, 0.614642, 0.000536, -0.002679, 1496957378.064200, 2.890478, 1.000000, 8.413361, 20.672922, 13.665980, 0.297872 +-7.77286, 2.7939, -28.401315, 4.286111, 0.596660, 0.000536, 0.000000, 1496957378.073700, 2.890532, 1.000000, 8.456222, 20.624094, 13.665980, 0.297872 +-7.81823, 2.80307, -28.402457, 4.300000, 0.640607, 0.000421, -0.002670, 1496957378.084200, 2.893460, 1.000000, 8.499222, 20.624094, 13.632410, 0.234043 +-7.86263, 2.81262, -28.403633, 4.300000, 0.714449, 0.000421, 0.000000, 1496957378.093800, 2.893494, 1.000000, 8.542222, 20.624094, 13.632410, 0.234043 +-7.90709, 2.82221, -28.404818, 4.308333, 0.713619, 0.000306, -0.002665, 1496957378.104400, 2.893536, 1.000000, 8.585306, 20.819410, 13.665980, 0.170213 +-7.9516, 2.83178, -28.405959, 4.308333, 0.587723, 0.000306, 0.000000, 1496957378.113800, 2.893561, 1.000000, 8.628389, 20.660715, 13.665980, 0.170213 +-7.99617, 2.84139, -28.407163, 4.327778, 0.566285, 0.000230, -0.001769, 1496957378.124300, 2.893636, 1.000000, 8.671667, 20.660715, 13.662929, 0.127660 +-8.04079, 2.851, -28.408253, 4.327778, 0.514932, 0.000230, 0.000000, 1496957378.133900, 2.893660, 1.000000, 8.714944, 20.624094, 13.662929, 0.127660 +-8.08545, 2.86063, -28.409352, 4.330555, 0.504223, 0.000153, -0.001768, 1496957378.144500, 2.893722, 1.000000, 8.758250, 20.624094, 13.650721, 0.085106 +-8.13017, 2.87029, -28.410363, 4.330555, 0.538142, 0.000153, 0.000000, 1496957378.154000, 2.893765, 1.000000, 8.801556, 20.709545, 13.650721, 0.085106 +-8.17494, 2.87995, -28.411325, 4.350000, 0.485268, 0.000115, -0.000880, 1496957378.164600, 2.893837, 1.000000, 8.845056, 20.709545, 13.682765, 0.063830 +-8.21975, 2.88964, -28.412219, 4.350000, 0.491670, 0.000115, 0.000000, 1496957378.174200, 2.893857, 1.000000, 8.888556, 20.636301, 13.682765, 0.063830 +-8.26462, 2.89932, -28.413035, 4.363889, 0.474504, 0.000077, -0.000877, 1496957378.183600, 2.893925, 1.000000, 8.932194, 20.636301, 13.652246, 0.042553 +-8.30953, 2.90906, -28.413845, 4.363889, 0.520692, 0.000077, 0.000000, 1496957378.194200, 2.894025, 1.000000, 8.975833, 20.648508, 13.652246, 0.042553 +-8.35448, 2.9188, -28.414562, 4.375000, 0.432239, 0.000077, 0.000000, 1496957378.203800, 2.894054, 1.000000, 9.019583, 20.648508, 13.652246, 0.042553 +-8.39948, 2.92856, -28.415303, 4.375000, 0.464669, 0.000077, 0.000000, 1496957378.214300, 2.894120, 1.000000, 9.063333, 20.685129, 13.652246, 0.042553 +-8.44451, 2.93834, -28.415961, 4.380556, 0.432952, 0.000077, 0.000000, 1496957378.223800, 2.894154, 1.000000, 9.107139, 20.685129, 13.643091, 0.042553 +-8.48959, 2.94814, -28.416602, 4.380556, 0.428423, 0.000077, 0.000000, 1496957378.234300, 2.894249, 1.000000, 9.150944, 20.636301, 13.643091, 0.042553 +-8.53473, 2.95798, -28.417213, 4.394444, 0.543814, 0.000077, 0.000000, 1496957378.243800, 2.894287, 1.000000, 9.194889, 20.636301, 13.681239, 0.042553 +-8.5799, 2.96784, -28.417729, 4.394444, 0.439826, 0.000077, 0.000000, 1496957378.254300, 2.894349, 1.000000, 9.238833, 20.685129, 13.681239, 0.042553 +-8.62512, 2.97771, -28.418232, 4.400000, 0.480537, 0.000077, 0.000000, 1496957378.263900, 2.894422, 1.000000, 9.282833, 20.685129, 13.669032, 0.042553 +-8.67038, 2.98761, -28.418644, 4.400000, 0.441560, 0.000077, 0.000000, 1496957378.274500, 2.894472, 1.000000, 9.326833, 20.636301, 13.669032, 0.042553 +-8.71568, 2.99751, -28.419048, 4.405556, 0.423498, 0.000077, 0.000000, 1496957378.284100, 2.894506, 1.000000, 9.370889, 20.636301, 13.667506, 0.042553 +-8.76103, 3.00745, -28.419398, 4.405556, 0.486882, 0.000077, 0.000000, 1496957378.294600, 2.894574, 1.000000, 9.414944, 20.636301, 13.667506, 0.042553 +-8.80643, 3.0174, -28.419745, 4.413889, 0.474044, 0.000077, 0.000000, 1496957378.304200, 2.894617, 1.000000, 9.459083, 20.624094, 13.647669, 0.042553 +-8.85187, 3.02736, -28.419992, 4.413889, 0.433592, 0.000077, 0.000000, 1496957378.313600, 2.894680, 1.000000, 9.503222, 20.624094, 13.647669, 0.042553 +-8.89733, 3.03734, -28.420269, 4.425000, 0.388629, 0.000077, 0.000000, 1496957378.324100, 2.894723, 1.000000, 9.547472, 20.672922, 13.667506, 0.042553 +-8.94283, 3.04734, -28.420513, 4.425000, 0.436627, 0.000077, 0.000000, 1496957378.333500, 2.894748, 1.000000, 9.591722, 20.672922, 13.667506, 0.042553 +-8.98841, 3.05736, -28.420760, 4.433333, 0.477199, 0.000038, -0.000863, 1496957378.344200, 2.894767, 1.000000, 9.636056, 20.575266, 13.640039, 0.021277 +-9.03403, 3.06737, -28.421025, 4.433333, 0.480118, 0.000038, 0.000000, 1496957378.353700, 2.894805, 1.000000, 9.680389, 20.575266, 13.640039, 0.021277 +-9.07969, 3.07742, -28.421275, 4.438889, 0.497868, 0.000000, -0.000862, 1496957378.364300, 2.894842, 1.000000, 9.724778, 20.440987, 13.629358, 0.000000 +-9.12539, 3.08744, -28.421559, 4.438889, 0.443368, 0.000000, 0.000000, 1496957378.373900, 2.894894, 1.000000, 9.769167, 20.440987, 13.629358, 0.000000 +-9.17114, 3.09749, -28.421832, 4.450000, 0.451341, -0.000115, -0.002580, 1496957378.383500, 2.894910, 1.000000, 9.813667, 20.135805, 13.661403, -0.063830 +-9.21692, 3.10751, -28.422132, 4.450000, 0.387241, -0.000115, 0.000000, 1496957378.394500, 2.894910, 1.000000, 9.858167, 20.135805, 13.661403, -0.063830 +-9.26277, 3.11754, -28.422459, 4.455555, 0.504294, -0.000191, -0.001718, 1496957378.404200, 2.894940, 1.000000, 9.902722, 19.940491, 13.710231, -0.106383 +-9.30865, 3.12757, -28.422763, 4.455555, 0.445949, -0.000191, 0.000000, 1496957378.414100, 2.894931, 1.000000, 9.947278, 19.940491, 13.710231, -0.106383 +-9.3546, 3.1376, -28.423125, 4.469444, 0.519462, -0.000344, -0.003425, 1496957378.423600, 2.894929, 1.000000, 9.991972, 19.818419, 13.690394, -0.191489 +-9.40058, 3.14761, -28.423428, 4.469444, 0.470025, -0.000344, 0.000000, 1496957378.434000, 2.894923, 1.000000, 10.036667, 19.818419, 13.690394, -0.191489 +-9.44661, 3.15762, -28.423804, 4.477778, 0.437541, -0.000498, -0.003419, 1496957378.444600, 2.894958, 1.000000, 10.081444, 19.757381, 13.656825, -0.276596 +-9.49268, 3.16763, -28.424118, 4.477778, 0.399048, -0.000498, 0.000000, 1496957378.454200, 2.894929, 1.000000, 10.126222, 19.757381, 13.656825, -0.276596 +-9.53879, 3.17762, -28.424456, 4.480556, 0.338203, -0.000651, -0.003417, 1496957378.463700, 2.894950, 1.000000, 10.171028, 19.732967, 13.687343, -0.361702 +-9.58496, 3.18762, -28.424851, 4.480556, 0.427489, -0.000651, 0.000000, 1496957378.474300, 2.894953, 1.000000, 10.215833, 19.732967, 13.687343, -0.361702 +-9.63114, 3.19761, -28.425198, 4.488889, 0.427134, -0.000842, -0.004263, 1496957378.483800, 2.894957, 1.000000, 10.260722, 19.708553, 13.649195, -0.468085 +-9.6774, 3.2076, -28.425672, 4.488889, 0.421840, -0.000842, 0.000000, 1496957378.494200, 2.894954, 1.000000, 10.305611, 19.708553, 13.649195, -0.468085 +-9.72369, 3.21761, -28.426094, 4.497222, 0.469130, -0.000995, -0.003404, 1496957378.503900, 2.894949, 1.000000, 10.350583, 19.586481, 13.647669, -0.553191 +-9.77003, 3.22761, -28.426582, 4.497222, 0.490352, -0.000995, 0.000000, 1496957378.514500, 2.894934, 1.000000, 10.395556, 19.586481, 13.647669, -0.553191 +-9.81642, 3.23763, -28.427100, 4.513889, 0.518107, -0.001148, -0.003392, 1496957378.524100, 2.894873, 1.000000, 10.440694, 19.501030, 13.617151, -0.638298 +-9.86284, 3.24766, -28.427640, 4.513889, 0.434584, -0.001148, 0.000000, 1496957378.533500, 2.894891, 1.000000, 10.485833, 19.501030, 13.617151, -0.638298 +-9.90933, 3.25772, -28.428245, 4.516667, 0.508097, -0.001340, -0.004237, 1496957378.544100, 2.894821, 1.000000, 10.531000, 19.293507, 13.725491, -0.744681 +-9.95584, 3.26779, -28.428877, 4.516667, 0.486802, -0.001340, 0.000000, 1496957378.553600, 2.894780, 1.000000, 10.576167, 19.293507, 13.725491, -0.744681 +-10.0024, 3.27789, -28.429580, 4.527778, 0.528161, -0.001454, -0.002536, 1496957378.564200, 2.894722, 1.000000, 10.621444, 19.073778, 13.688869, -0.808511 +-10.049, 3.288, -28.430344, 4.527778, 0.474481, -0.001454, 0.000000, 1496957378.573600, 2.894704, 1.000000, 10.666722, 19.073778, 13.688869, -0.808511 +-10.0957, 3.29811, -28.431110, 4.536111, 0.461924, -0.001608, -0.003375, 1496957378.584100, 2.894650, 1.000000, 10.712083, 19.000534, 13.646143, -0.893617 +-10.1423, 3.30822, -28.431918, 4.536111, 0.459692, -0.001608, 0.000000, 1496957378.593700, 2.894614, 1.000000, 10.757444, 19.000534, 13.646143, -0.893617 +-10.1891, 3.31831, -28.432737, 4.541667, 0.409378, -0.001722, -0.002528, 1496957378.604200, 2.894547, 1.000000, 10.802861, 19.000534, 13.647669, -0.957447 +-10.2359, 3.32838, -28.433582, 4.541667, 0.497228, -0.001722, 0.000000, 1496957378.613700, 2.894481, 1.000000, 10.848278, 19.000534, 13.647669, -0.957447 +-10.2827, 3.33843, -28.434495, 4.558333, 0.495347, -0.001799, -0.001679, 1496957378.624300, 2.894407, 1.000000, 10.893861, 18.988327, 13.699550, -1.000000 +-10.3297, 3.34848, -28.435441, 4.558333, 0.596486, -0.001799, 0.000000, 1496957378.633800, 2.894311, 1.000000, 10.939444, 18.988327, 13.699550, -1.000000 +-10.3767, 3.3585, -28.436354, 4.563889, 0.570324, -0.001875, -0.001677, 1496957378.644400, 2.894215, 1.000000, 10.985083, 18.878462, 13.649195, -1.042553 +-10.4237, 3.36849, -28.437358, 4.563889, 0.481138, -0.001875, 0.000000, 1496957378.653900, 2.894104, 1.000000, 11.030722, 18.878462, 13.649195, -1.042553 +-10.4707, 3.3785, -28.438347, 4.575000, 0.436605, -0.001990, -0.002510, 1496957378.664400, 2.893985, 1.000000, 11.076472, 18.854048, 13.682765, -1.106383 +-10.5179, 3.38848, -28.439382, 4.575000, 0.413094, -0.001990, 0.000000, 1496957378.673900, 2.893842, 1.000000, 11.122222, 18.854048, 13.682765, -1.106383 +-10.5651, 3.39848, -28.440489, 4.583333, 0.513623, -0.002029, -0.000835, 1496957378.684600, 2.893728, 1.000000, 11.168056, 18.805218, 13.659877, -1.127660 +-10.6123, 3.40846, -28.441568, 4.583333, 0.517185, -0.002029, 0.000000, 1496957378.694100, 2.893647, 1.000000, 11.213889, 18.805218, 13.659877, -1.127660 +-10.6595, 3.41846, -28.442704, 4.588889, 0.520748, -0.002067, -0.000834, 1496957378.703500, 2.893521, 1.000000, 11.259778, 18.829634, 13.647669, -1.148936 +-10.7069, 3.42848, -28.443810, 4.588889, 0.497255, -0.002067, 0.000000, 1496957378.714100, 2.893445, 1.000000, 11.305667, 18.829634, 13.647669, -1.148936 +-10.7542, 3.43847, -28.444959, 4.600000, 0.451526, -0.002067, 0.000000, 1496957378.723500, 2.893317, 1.000000, 11.351667, 18.780804, 13.672084, -1.148936 +-10.8016, 3.4485, -28.446090, 4.600000, 0.479451, -0.002067, 0.000000, 1496957378.734000, 2.893201, 1.000000, 11.397667, 18.780804, 13.672084, -1.148936 +-10.8491, 3.45851, -28.447121, 4.613889, 0.417176, -0.002067, 0.000000, 1496957378.744600, 2.893107, 1.000000, 11.443806, 18.878462, 13.687343, -1.148936 +-10.8966, 3.46855, -28.448158, 4.613889, 0.462964, -0.002067, 0.000000, 1496957378.754100, 2.892994, 1.000000, 11.489944, 18.878462, 13.687343, -1.148936 +-10.9441, 3.47859, -28.449156, 4.625000, 0.409384, -0.002067, 0.000000, 1496957378.763600, 2.892877, 1.000000, 11.536194, 18.817427, 13.632410, -1.148936 +-10.9917, 3.48866, -28.450106, 4.625000, 0.435468, -0.002067, 0.000000, 1496957378.774300, 2.892806, 1.000000, 11.582444, 18.817427, 13.632410, -1.148936 +-11.0393, 3.49876, -28.450953, 4.633333, 0.419024, -0.002067, 0.000000, 1496957378.783800, 2.892719, 1.000000, 11.628778, 18.841841, 13.664454, -1.148936 +-11.087, 3.50889, -28.451819, 4.633333, 0.380684, -0.002067, 0.000000, 1496957378.794500, 2.892665, 1.000000, 11.675111, 18.841841, 13.664454, -1.148936 +-11.1347, 3.51904, -28.452577, 4.638889, 0.382774, -0.002067, 0.000000, 1496957378.804100, 2.892581, 1.000000, 11.721500, 18.780804, 13.652246, -1.148936 +-11.1824, 3.52923, -28.453379, 4.638889, 0.402908, -0.002067, 0.000000, 1496957378.813600, 2.892507, 1.000000, 11.767889, 18.780804, 13.652246, -1.148936 +-11.2302, 3.53948, -28.454108, 4.650000, 0.483181, -0.002067, 0.000000, 1496957378.824100, 2.892479, 1.000000, 11.814389, 18.719769, 13.630884, -1.148936 +-11.278, 3.54974, -28.454754, 4.650000, 0.429207, -0.002067, 0.000000, 1496957378.833600, 2.892448, 1.000000, 11.860889, 18.719769, 13.630884, -1.148936 +-11.3258, 3.56005, -28.455387, 4.655556, 0.478853, -0.002029, 0.000822, 1496957378.844100, 2.892410, 1.000000, 11.907444, 18.596170, 13.690394, -1.127660 +-11.3737, 3.57038, -28.455963, 4.655556, 0.359511, -0.002029, 0.000000, 1496957378.853500, 2.892357, 1.000000, 11.954000, 18.596170, 13.690394, -1.127660 +-11.4216, 3.58075, -28.456506, 4.666667, 0.356709, -0.001990, 0.000820, 1496957378.864100, 2.892311, 1.000000, 12.000667, 18.413061, 13.641565, -1.106383 +-11.4695, 3.59117, -28.457026, 4.666667, 0.376967, -0.001990, 0.000000, 1496957378.873600, 2.892287, 1.000000, 12.047333, 18.413061, 13.641565, -1.106383 +-11.5175, 3.60161, -28.457471, 4.672222, 0.385000, -0.001990, 0.000000, 1496957378.884200, 2.892290, 1.000000, 12.094056, 18.339819, 13.606470, -1.106383 +-11.5655, 3.6121, -28.457901, 4.672222, 0.430173, -0.001990, 0.000000, 1496957378.894100, 2.892275, 1.000000, 12.140778, 18.339819, 13.606470, -1.106383 +-11.6136, 3.6226, -28.458308, 4.672222, 0.402376, -0.001990, 0.000000, 1496957378.903800, 2.892275, 1.000000, 12.187500, 18.339819, 13.606470, -1.106383 +-11.6616, 3.63313, -28.458602, 4.675000, 0.397686, -0.001914, 0.001637, 1496957378.915400, 2.892230, 1.000000, 12.234250, 18.278782, 13.676661, -1.063830 +-11.7097, 3.64367, -28.458920, 4.683333, 0.319276, -0.001914, 0.000000, 1496957378.923900, 2.892209, 1.000000, 12.281083, 18.193333, 13.696498, -1.063830 +-11.7579, 3.65423, -28.459182, 4.683333, 0.337930, -0.001914, 0.000000, 1496957378.934600, 2.892182, 1.000000, 12.327917, 18.193333, 13.696498, -1.063830 +-11.8061, 3.6648, -28.459430, 4.688889, 0.323995, -0.001875, 0.000816, 1496957378.944100, 2.892132, 1.000000, 12.374806, 18.242161, 13.656825, -1.042553 +-11.8543, 3.67538, -28.459697, 4.688889, 0.364708, -0.001875, 0.000000, 1496957378.953600, 2.892084, 1.000000, 12.421694, 18.242161, 13.656825, -1.042553 +-11.9025, 3.686, -28.459919, 4.694445, 0.453584, -0.001875, 0.000000, 1496957378.964100, 2.892019, 1.000000, 12.468639, 18.205540, 13.661403, -1.042553 +-11.9508, 3.6966, -28.460171, 4.694445, 0.443538, -0.001875, 0.000000, 1496957378.973600, 2.891973, 1.000000, 12.515583, 18.205540, 13.661403, -1.042553 +-11.9991, 3.70721, -28.460451, 4.702778, 0.373098, -0.001875, 0.000000, 1496957378.984200, 2.891891, 1.000000, 12.562611, 18.071260, 13.641565, -1.042553 +-12.0475, 3.71781, -28.460703, 4.702778, 0.341264, -0.001875, 0.000000, 1496957378.993800, 2.891863, 1.000000, 12.609639, 18.071260, 13.641565, -1.042553 +-12.0959, 3.72843, -28.461030, 4.705555, 0.386877, -0.001875, 0.000000, 1496957379.004300, 2.891751, 1.000000, 12.656694, 17.949188, 13.679713, -1.042553 +-12.1444, 3.73905, -28.461389, 4.705555, 0.374137, -0.001875, 0.000000, 1496957379.013900, 2.891650, 1.000000, 12.703750, 17.949188, 13.679713, -1.042553 +-12.1929, 3.74965, -28.461768, 4.713889, 0.426640, -0.001875, 0.000000, 1496957379.023800, 2.891591, 1.000000, 12.750889, 17.888151, 13.699550, -1.042553 +-12.2414, 3.76024, -28.462232, 4.713889, 0.441758, -0.001875, 0.000000, 1496957379.034400, 2.891505, 1.000000, 12.798028, 17.888151, 13.699550, -1.042553 +-12.29, 3.77083, -28.462726, 4.719444, 0.441814, -0.001875, 0.000000, 1496957379.044000, 2.891425, 1.000000, 12.845222, 17.875944, 13.707179, -1.042553 +-12.3386, 3.78143, -28.463234, 4.719444, 0.475065, -0.001875, 0.000000, 1496957379.054600, 2.891354, 1.000000, 12.892417, 17.875944, 13.707179, -1.042553 +-12.3873, 3.79201, -28.463824, 4.733333, 0.377851, -0.001875, 0.000000, 1496957379.064200, 2.891313, 1.000000, 12.939750, 17.851530, 13.670558, -1.042553 +-12.436, 3.80261, -28.464410, 4.733333, 0.423169, -0.001875, 0.000000, 1496957379.073800, 2.891248, 1.000000, 12.987083, 17.851530, 13.670558, -1.042553 +-12.4839, 3.81374, -28.464852, 4.741667, 0.341877, -0.001875, 0.000000, 1496957379.084200, 2.889680, 1.000000, 13.034500, 17.912565, 13.630884, -1.042553 +-12.5314, 3.82489, -28.465347, 4.741667, 0.382860, -0.001875, 0.000000, 1496957379.093700, 2.889585, 1.000000, 13.081917, 17.912565, 13.630884, -1.042553 +-12.5789, 3.83604, -28.465860, 4.747222, 0.340815, -0.001875, 0.000000, 1496957379.104300, 2.889510, 1.000000, 13.129389, 17.802700, 13.731594, -1.042553 +-12.6266, 3.84723, -28.466502, 4.747222, 0.513273, -0.001875, 0.000000, 1496957379.113800, 2.889456, 1.000000, 13.176861, 17.802700, 13.731594, -1.042553 +-12.6742, 3.85843, -28.467122, 4.755556, 0.486353, -0.001875, 0.000000, 1496957379.124300, 2.889397, 1.000000, 13.224417, 17.631800, 13.623255, -1.042553 +-12.7219, 3.86964, -28.467834, 4.755556, 0.431258, -0.001875, 0.000000, 1496957379.133800, 2.889385, 1.000000, 13.271972, 17.631800, 13.623255, -1.042553 +-12.7696, 3.88087, -28.468529, 4.763889, 0.418357, -0.001837, 0.000803, 1496957379.144300, 2.889317, 1.000000, 13.319611, 17.314413, 13.679713, -1.021277 +-12.8173, 3.89211, -28.469265, 4.763889, 0.299097, -0.001837, 0.000000, 1496957379.153800, 2.889298, 1.000000, 13.367250, 17.314413, 13.679713, -1.021277 +-12.8651, 3.90337, -28.470041, 4.775000, 0.370943, -0.001799, 0.000802, 1496957379.164300, 2.889226, 1.000000, 13.415000, 16.935987, 13.649195, -1.000000 +-12.9129, 3.91462, -28.470731, 4.775000, 0.298760, -0.001799, 0.000000, 1496957379.173800, 2.889178, 1.000000, 13.462750, 16.935987, 13.649195, -1.000000 +-12.9608, 3.92588, -28.471511, 4.780556, 0.350358, -0.001722, 0.001601, 1496957379.184300, 2.889110, 1.000000, 13.510556, 16.923780, 13.676661, -0.957447 +-13.0086, 3.93715, -28.472224, 4.780556, 0.328955, -0.001722, 0.000000, 1496957379.193800, 2.889049, 1.000000, 13.558361, 16.923780, 13.676661, -0.957447 +-13.0566, 3.9484, -28.472967, 4.786111, 0.320418, -0.001608, 0.002399, 1496957379.204300, 2.888968, 1.000000, 13.606222, 16.850538, 13.662929, -0.893617 +-13.1045, 3.95964, -28.473720, 4.786111, 0.352396, -0.001608, 0.000000, 1496957379.213800, 2.888926, 1.000000, 13.654083, 16.850538, 13.662929, -0.893617 +-13.1525, 3.97087, -28.474518, 4.791667, 0.276869, -0.001493, 0.002396, 1496957379.224300, 2.888822, 1.000000, 13.702000, 16.911573, 13.640039, -0.829787 +-13.2005, 3.9821, -28.475332, 4.791667, 0.342642, -0.001493, 0.000000, 1496957379.233800, 2.888739, 1.000000, 13.749917, 16.911573, 13.640039, -0.829787 +-13.2485, 3.99332, -28.476162, 4.802778, 0.373898, -0.001378, 0.002391, 1496957379.244300, 2.888652, 1.000000, 13.797944, 16.862745, 13.652246, -0.765957 +-13.2967, 4.00455, -28.477001, 4.802778, 0.455317, -0.001378, 0.000000, 1496957379.253800, 2.888556, 1.000000, 13.845972, 16.862745, 13.652246, -0.765957 +-13.3448, 4.01579, -28.477850, 4.811111, 0.409425, -0.001301, 0.001591, 1496957379.264300, 2.888449, 1.000000, 13.894083, 16.801708, 13.603418, -0.723404 +-13.393, 4.02704, -28.478642, 4.811111, 0.344446, -0.001301, 0.000000, 1496957379.273800, 2.888338, 1.000000, 13.942194, 16.801708, 13.603418, -0.723404 +-13.4412, 4.03831, -28.479460, 4.822222, 0.288880, -0.001187, 0.002381, 1496957379.284300, 2.888238, 1.000000, 13.990417, 16.740673, 13.653772, -0.659574 +-13.4894, 4.0496, -28.480185, 4.822222, 0.266407, -0.001187, 0.000000, 1496957379.293800, 2.888128, 1.000000, 14.038639, 16.740673, 13.653772, -0.659574 +-13.5376, 4.0609, -28.480914, 4.825000, 0.236601, -0.001148, 0.000793, 1496957379.304200, 2.888038, 1.000000, 14.086889, 16.704052, 13.659877, -0.638298 +-13.5859, 4.07221, -28.481573, 4.825000, 0.222835, -0.001148, 0.000000, 1496957379.313600, 2.888017, 1.000000, 14.135139, 16.704052, 13.659877, -0.638298 +-13.6341, 4.08353, -28.482240, 4.827778, 0.218453, -0.001110, 0.000793, 1496957379.324200, 2.887885, 1.000000, 14.183417, 16.752880, 13.678187, -0.617021 +-13.6824, 4.09487, -28.482831, 4.827778, 0.273292, -0.001110, 0.000000, 1496957379.333800, 2.887814, 1.000000, 14.231694, 16.752880, 13.678187, -0.617021 +-13.7308, 4.10622, -28.483385, 4.836111, 0.340459, -0.001072, 0.000791, 1496957379.344300, 2.887741, 1.000000, 14.280056, 16.752880, 13.705653, -0.595745 +-13.7792, 4.11757, -28.483882, 4.836111, 0.266984, -0.001072, 0.000000, 1496957379.353700, 2.887697, 1.000000, 14.328417, 16.752880, 13.705653, -0.595745 +-13.8276, 4.12894, -28.484309, 4.841667, 0.270986, -0.001072, 0.000000, 1496957379.364300, 2.887631, 1.000000, 14.376833, 16.838331, 13.598841, -0.595745 +-13.876, 4.14029, -28.484704, 4.841667, 0.187976, -0.001072, 0.000000, 1496957379.373800, 2.887560, 1.000000, 14.425250, 16.838331, 13.598841, -0.595745 +-13.9244, 4.15165, -28.485056, 4.844444, 0.178367, -0.001072, 0.000000, 1496957379.384300, 2.887551, 1.000000, 14.473694, 16.667429, 13.679713, -0.595745 +-13.9729, 4.16299, -28.485392, 4.844444, 0.168630, -0.001072, 0.000000, 1496957379.393900, 2.887508, 1.000000, 14.522139, 16.667429, 13.679713, -0.595745 +-14.0214, 4.17435, -28.485734, 4.847222, 0.249044, -0.001072, 0.000000, 1496957379.404500, 2.887407, 1.000000, 14.570611, 16.679636, 13.609522, -0.595745 +-14.0699, 4.18572, -28.486104, 4.847222, 0.282614, -0.001072, 0.000000, 1496957379.414100, 2.887360, 1.000000, 14.619083, 16.679636, 13.609522, -0.595745 +-14.1184, 4.19709, -28.486496, 4.850000, 0.321436, -0.001072, 0.000000, 1496957379.423900, 2.887348, 1.000000, 14.667583, 16.618601, 13.716334, -0.595745 +-14.167, 4.20847, -28.486936, 4.850000, 0.318953, -0.001072, 0.000000, 1496957379.434500, 2.887335, 1.000000, 14.716083, 16.618601, 13.716334, -0.595745 +-14.2156, 4.21986, -28.487405, 4.855556, 0.242445, -0.001072, 0.000000, 1496957379.444100, 2.887278, 1.000000, 14.764639, 16.655222, 13.669032, -0.595745 +-14.2642, 4.23126, -28.487883, 4.855556, 0.233995, -0.001072, 0.000000, 1496957379.453600, 2.887285, 1.000000, 14.813194, 16.655222, 13.669032, -0.595745 +-14.3128, 4.24265, -28.488418, 4.858333, 0.216861, -0.001072, 0.000000, 1496957379.464100, 2.887287, 1.000000, 14.861778, 16.667429, 13.669032, -0.595745 +-14.3615, 4.25408, -28.489003, 4.858333, 0.271272, -0.001072, 0.000000, 1496957379.473500, 2.887250, 1.000000, 14.910361, 16.667429, 13.669032, -0.595745 +-14.4102, 4.26549, -28.489585, 4.861111, 0.246370, -0.001072, 0.000000, 1496957379.484100, 2.887260, 1.000000, 14.958972, 16.691845, 13.646143, -0.595745 +-14.4589, 4.27692, -28.490226, 4.861111, 0.257807, -0.001072, 0.000000, 1496957379.493600, 2.887199, 1.000000, 15.007583, 16.691845, 13.646143, -0.595745 +-14.5076, 4.28835, -28.490870, 4.863889, 0.220960, -0.001072, 0.000000, 1496957379.504200, 2.887195, 1.000000, 15.056222, 16.630808, 13.647669, -0.595745 +-14.5563, 4.2998, -28.491530, 4.863889, 0.165450, -0.001072, 0.000000, 1496957379.513600, 2.887175, 1.000000, 15.104861, 16.630808, 13.647669, -0.595745 +-14.6051, 4.31124, -28.492222, 4.869444, 0.104598, -0.001072, 0.000000, 1496957379.524300, 2.887171, 1.000000, 15.153556, 16.704052, 13.579003, -0.595745 +-14.6538, 4.32269, -28.492924, 4.869444, 0.163452, -0.001072, 0.000000, 1496957379.533800, 2.887152, 1.000000, 15.202250, 16.704052, 13.579003, -0.595745 +-14.7026, 4.33414, -28.493696, 4.872222, 0.147841, -0.001033, 0.000786, 1496957379.544300, 2.887102, 1.000000, 15.250972, 16.667429, 13.649195, -0.574468 +-14.7514, 4.34559, -28.494477, 4.872222, 0.211236, -0.001033, 0.000000, 1496957379.553900, 2.887101, 1.000000, 15.299694, 16.667429, 13.649195, -0.574468 +-14.8002, 4.35703, -28.495280, 4.877778, 0.269832, -0.001033, 0.000000, 1496957379.564400, 2.887082, 1.000000, 15.348472, 16.545357, 13.665980, -0.574468 +-14.8491, 4.36848, -28.496048, 4.877778, 0.247763, -0.001033, 0.000000, 1496957379.574000, 2.887049, 1.000000, 15.397250, 16.545357, 13.665980, -0.574468 +-14.8979, 4.37992, -28.496745, 4.883333, 0.096285, -0.000995, 0.000784, 1496957379.584600, 2.886997, 1.000000, 15.446083, 16.459908, 13.620203, -0.553191 +-14.9468, 4.39134, -28.497417, 4.883333, 0.070731, -0.000995, 0.000000, 1496957379.594200, 2.886943, 1.000000, 15.494917, 16.459908, 13.620203, -0.553191 +-14.9956, 4.40277, -28.498025, 4.886111, 0.057485, -0.000957, 0.000783, 1496957379.603600, 2.886922, 1.000000, 15.543778, 16.423285, 13.615625, -0.531915 +-15.0445, 4.41419, -28.498582, 4.886111, 0.081251, -0.000957, 0.000000, 1496957379.614100, 2.886848, 1.000000, 15.592639, 16.423285, 13.615625, -0.531915 +-15.0934, 4.42562, -28.499057, 4.888889, 0.169389, -0.000957, 0.000000, 1496957379.623500, 2.886808, 1.000000, 15.641528, 16.447701, 13.600367, -0.531915 +-15.1424, 4.43702, -28.499511, 4.888889, 0.082663, -0.000957, 0.000000, 1496957379.634100, 2.886764, 1.000000, 15.690417, 16.447701, 13.600367, -0.531915 +-15.1913, 4.44843, -28.499873, 4.891667, 0.094344, -0.000957, 0.000000, 1496957379.643600, 2.886710, 1.000000, 15.739333, 16.435492, 13.600367, -0.531915 +-15.2402, 4.45986, -28.500210, 4.891667, 0.080715, -0.000957, 0.000000, 1496957379.654100, 2.886666, 1.000000, 15.788250, 16.435492, 13.644617, -0.531915 +-15.2892, 4.4713, -28.500491, 4.894444, 0.180467, -0.000957, 0.000000, 1496957379.663500, 2.886625, 1.000000, 15.837194, 16.423285, 13.644617, -0.531915 +-15.3382, 4.48272, -28.500722, 4.894444, 0.143493, -0.000957, 0.000000, 1496957379.674000, 2.886619, 1.000000, 15.886139, 16.423285, 13.633936, -0.531915 +-15.3872, 4.49416, -28.501016, 4.894444, 0.089599, -0.000957, 0.000000, 1496957379.684600, 2.886611, 1.000000, 15.935083, 16.325628, 13.633936, -0.531915 +-15.4362, 4.5056, -28.501223, 4.894444, 0.055397, -0.000957, 0.000000, 1496957379.694100, 2.886544, 1.000000, 15.984028, 16.325628, 13.676661, -0.531915 +-15.4852, 4.51707, -28.501477, 4.891667, 0.108313, -0.000957, 0.000000, 1496957379.703600, 2.886505, 1.000000, 16.032944, 16.374456, 13.676661, -0.531915 +-15.5342, 4.52854, -28.501740, 4.891667, 0.073863, -0.000957, 0.000000, 1496957379.714100, 2.886496, 1.000000, 16.081861, 16.374456, 13.633936, -0.531915 +-15.5832, 4.54004, -28.502045, 4.891667, 0.094834, -0.000957, 0.000000, 1496957379.723600, 2.886484, 1.000000, 16.130778, 16.350042, 13.633936, -0.531915 +-15.6322, 4.55154, -28.502345, 4.891667, 0.086037, -0.000957, 0.000000, 1496957379.734200, 2.886483, 1.000000, 16.179694, 16.350042, 13.633936, -0.531915 +-15.6812, 4.56305, -28.502656, 4.897222, 0.133809, -0.000957, 0.000000, 1496957379.743800, 2.886443, 1.000000, 16.228667, 16.337835, 13.673610, -0.531915 +-15.7302, 4.57462, -28.502930, 4.897222, 0.096801, -0.000957, 0.000000, 1496957379.754300, 2.886461, 1.000000, 16.277639, 16.337835, 13.673610, -0.531915 +-15.7792, 4.58618, -28.503272, 4.900000, 0.080342, -0.000957, 0.000000, 1496957379.763800, 2.886494, 1.000000, 16.326639, 16.264591, 13.670558, -0.531915 +-15.8283, 4.59778, -28.503551, 4.900000, 0.126545, -0.000957, 0.000000, 1496957379.774400, 2.886545, 1.000000, 16.375639, 16.264591, 13.670558, -0.531915 +-15.8773, 4.60936, -28.503886, 4.902778, 0.114459, -0.000957, 0.000000, 1496957379.784100, 2.886577, 1.000000, 16.424667, 16.350042, 13.670558, -0.531915 +-15.9264, 4.62096, -28.504175, 4.902778, 0.120731, -0.000957, 0.000000, 1496957379.793500, 2.886635, 1.000000, 16.473694, 16.350042, 13.716334, -0.531915 +-15.9755, 4.63256, -28.504411, 4.905556, 0.039512, -0.000919, 0.000780, 1496957379.804100, 2.886686, 1.000000, 16.522750, 16.337835, 13.716334, -0.510638 +-16.0245, 4.64421, -28.504686, 4.905556, 0.045906, -0.000919, 0.000000, 1496957379.813600, 2.886747, 1.000000, 16.571806, 16.337835, 13.617151, -0.510638 +-16.0735, 4.65585, -28.504921, 4.908333, -0.029125, -0.000880, 0.000780, 1496957379.824100, 2.886772, 1.000000, 16.620889, 16.289005, 13.617151, -0.489362 +-16.1226, 4.66752, -28.505251, 4.908333, 0.011831, -0.000880, 0.000000, 1496957379.833500, 2.886848, 1.000000, 16.669972, 16.289005, 13.589684, -0.489362 +-16.1716, 4.67921, -28.505622, 4.908333, 0.135002, -0.000842, 0.000780, 1496957379.844100, 2.886858, 1.000000, 16.719056, 16.276798, 13.589684, -0.468085 +-16.2207, 4.69097, -28.506045, 4.908333, 0.227341, -0.000842, 0.000000, 1496957379.853500, 2.886874, 1.000000, 16.768139, 16.276798, 13.658351, -0.468085 +-16.2698, 4.70273, -28.506508, 4.908333, 0.129856, -0.000804, 0.000780, 1496957379.864100, 2.886905, 1.000000, 16.817222, 16.276798, 13.658351, -0.446809 +-16.3188, 4.71451, -28.507026, 4.908333, 0.060442, -0.000804, 0.000000, 1496957379.873600, 2.886955, 1.000000, 16.866306, 16.276798, 13.672084, -0.446809 +-16.3679, 4.72629, -28.507579, 4.908333, 0.085097, -0.000765, 0.000780, 1496957379.884200, 2.886943, 1.000000, 16.915389, 16.179140, 13.672084, -0.425532 +-16.417, 4.73808, -28.508139, 4.908333, 0.132508, -0.000765, 0.000000, 1496957379.894400, 2.886980, 1.000000, 16.964472, 16.179140, 13.627832, -0.425532 +-16.4661, 4.74986, -28.508667, 4.913889, 0.058443, -0.000727, 0.000779, 1496957379.903500, 2.886993, 1.000000, 17.013611, 16.252384, 13.627832, -0.404255 +-16.5152, 4.76159, -28.509278, 4.913889, 0.033121, -0.000727, 0.000000, 1496957379.914500, 2.886999, 1.000000, 17.062750, 16.252384, 13.694972, -0.404255 +-16.5643, 4.77331, -28.509910, 4.916667, 0.022183, -0.000689, 0.000778, 1496957379.923900, 2.886966, 1.000000, 17.111917, 16.191349, 13.694972, -0.382979 +-16.6134, 4.785, -28.510625, 4.916667, 0.150723, -0.000689, 0.000000, 1496957379.934600, 2.886944, 1.000000, 17.161083, 16.191349, 13.682765, -0.382979 +-16.6625, 4.79668, -28.511367, 4.919445, 0.217200, -0.000689, 0.000000, 1496957379.944200, 2.886899, 1.000000, 17.210278, 16.191349, 13.682765, -0.382979 +-16.7117, 4.80834, -28.512136, 4.919445, 0.189644, -0.000689, 0.000000, 1496957379.953800, 2.886829, 1.000000, 17.259472, 16.191349, 13.667506, -0.382979 +-16.7609, 4.81995, -28.512940, 4.919445, 0.059945, -0.000689, 0.000000, 1496957379.964300, 2.886799, 1.000000, 17.308667, 16.252384, 13.667506, -0.382979 +-16.8101, 4.83153, -28.513815, 4.919445, -0.008277, -0.000689, 0.000000, 1496957379.973900, 2.886747, 1.000000, 17.357861, 16.252384, 13.644617, -0.382979 +-16.8593, 4.8431, -28.514690, 4.925000, 0.080518, -0.000689, 0.000000, 1496957379.984500, 2.886721, 1.000000, 17.407111, 16.203556, 13.644617, -0.382979 +-16.9085, 4.85463, -28.515617, 4.925000, 0.123633, -0.000689, 0.000000, 1496957379.994900, 2.886684, 1.000000, 17.456361, 16.203556, 13.691920, -0.382979 +-16.9578, 4.86615, -28.516545, 4.927778, 0.107713, -0.000689, 0.000000, 1496957380.004400, 2.886602, 1.000000, 17.505639, 16.252384, 13.691920, -0.382979 +-17.007, 4.87763, -28.517497, 4.927778, 0.088616, -0.000689, 0.000000, 1496957380.013900, 2.886545, 1.000000, 17.554917, 16.252384, 13.647669, -0.382979 +-17.0563, 4.88912, -28.518473, 4.927778, 0.075332, -0.000727, -0.000777, 1496957380.024400, 2.886483, 1.000000, 17.604194, 16.276798, 13.647669, -0.404255 +-17.1056, 4.90058, -28.519430, 4.927778, 0.048607, -0.000727, 0.000000, 1496957380.034000, 2.886416, 1.000000, 17.653472, 16.276798, 13.633936, -0.404255 +-17.1548, 4.91201, -28.520365, 4.930555, 0.064551, -0.000727, 0.000000, 1496957380.044500, 2.886367, 1.000000, 17.702778, 16.301212, 13.633936, -0.404255 +-17.2041, 4.92342, -28.521295, 4.930555, -0.042571, -0.000727, 0.000000, 1496957380.054000, 2.886340, 1.000000, 17.752083, 16.301212, 13.636988, -0.404255 +-17.2534, 4.93482, -28.522178, 4.930555, -0.015247, -0.000727, 0.000000, 1496957380.064500, 2.886341, 1.000000, 17.801389, 16.289005, 13.636988, -0.404255 +-17.3027, 4.94621, -28.523015, 4.930555, -0.010387, -0.000727, 0.000000, 1496957380.074000, 2.886297, 1.000000, 17.850694, 16.289005, 13.682765, -0.404255 +-17.351, 4.95808, -28.523644, 4.930555, 0.027002, -0.000727, 0.000000, 1496957380.084500, 2.886176, 1.000000, 17.900000, 16.289005, 13.682765, -0.404255 +-17.3996, 4.96976, -28.524188, 4.930555, 0.015068, -0.000727, 0.000000, 1496957380.094100, 2.886124, 1.000000, 17.949306, 16.289005, 13.647669, -0.404255 +-17.4482, 4.98147, -28.524781, 4.930555, 0.091520, -0.000765, -0.000776, 1496957380.103500, 2.886111, 1.000000, 17.998611, 16.227970, 13.647669, -0.425532 +-17.4967, 4.99316, -28.525264, 4.930555, -0.086543, -0.000765, 0.000000, 1496957380.114100, 2.886061, 1.000000, 18.047917, 16.227970, 13.629358, -0.425532 +-17.5452, 5.00486, -28.525816, 4.930555, -0.124755, -0.000765, 0.000000, 1496957380.123500, 2.886038, 1.000000, 18.097222, 16.313421, 13.629358, -0.425532 +-17.5937, 5.01653, -28.526383, 4.930555, -0.017114, -0.000765, 0.000000, 1496957380.134100, 2.886035, 1.000000, 18.146528, 16.313421, 13.627832, -0.425532 +-17.6423, 5.0282, -28.526960, 4.930555, 0.049712, -0.000765, 0.000000, 1496957380.143500, 2.885981, 1.000000, 18.195833, 16.264591, 13.627832, -0.425532 +-17.6908, 5.03984, -28.527557, 4.930555, 0.049776, -0.000765, 0.000000, 1496957380.154200, 2.885953, 1.000000, 18.245139, 16.264591, 13.665980, -0.425532 +-17.7394, 5.05146, -28.528191, 4.927778, 0.011612, -0.000727, 0.000777, 1496957380.163800, 2.885943, 1.000000, 18.294417, 16.264591, 13.665980, -0.404255 +-17.7879, 5.06306, -28.528825, 4.927778, -0.063797, -0.000727, 0.000000, 1496957380.174400, 2.885887, 1.000000, 18.343694, 16.264591, 13.667506, -0.404255 +-17.8365, 5.07464, -28.529507, 4.930555, -0.064542, -0.000689, 0.000776, 1496957380.184000, 2.885822, 1.000000, 18.393000, 16.264591, 13.667506, -0.382979 +-17.885, 5.08623, -28.530157, 4.930555, -0.155686, -0.000689, 0.000000, 1496957380.193500, 2.885756, 1.000000, 18.442306, 16.264591, 13.647669, -0.382979 +-17.9335, 5.09783, -28.530873, 4.927778, -0.066721, -0.000689, 0.000000, 1496957380.204100, 2.885720, 1.000000, 18.491583, 16.252384, 13.647669, -0.382979 +-17.982, 5.10941, -28.531548, 4.927778, -0.126253, -0.000689, 0.000000, 1496957380.213500, 2.885696, 1.000000, 18.540861, 16.252384, 13.626307, -0.382979 +-18.0306, 5.12102, -28.532284, 4.933333, 0.133245, -0.000651, 0.000776, 1496957380.224100, 2.885620, 1.000000, 18.590194, 16.313421, 13.626307, -0.361702 +-18.0791, 5.13266, -28.532968, 4.933333, 0.095271, -0.000651, 0.000000, 1496957380.234600, 2.885543, 1.000000, 18.639528, 16.313421, 13.685817, -0.361702 +-18.1276, 5.14434, -28.533658, 4.936111, -0.041853, -0.000612, 0.000775, 1496957380.244100, 2.885475, 1.000000, 18.688889, 16.301212, 13.685817, -0.340426 +-18.176, 5.15606, -28.534348, 4.936111, -0.176817, -0.000612, 0.000000, 1496957380.253500, 2.885449, 1.000000, 18.738250, 16.301212, 13.606470, -0.340426 +-18.2245, 5.16778, -28.534994, 4.930555, -0.114791, -0.000536, 0.001553, 1496957380.264000, 2.885396, 1.000000, 18.787556, 16.301212, 13.606470, -0.297872 +-18.2729, 5.17951, -28.535545, 4.930555, -0.274425, -0.000536, 0.000000, 1496957380.274500, 2.885409, 1.000000, 18.836861, 16.301212, 13.620203, -0.297872 +-18.3214, 5.19125, -28.536057, 4.933333, -0.097478, -0.000498, 0.000776, 1496957380.284200, 2.885426, 1.000000, 18.886194, 16.313421, 13.620203, -0.276596 +-18.3698, 5.20301, -28.536474, 4.933333, -0.120508, -0.000498, 0.000000, 1496957380.293800, 2.885432, 1.000000, 18.935528, 16.313421, 13.644617, -0.276596 +-18.4182, 5.21475, -28.536805, 4.936111, -0.187928, -0.000459, 0.000775, 1496957380.304400, 2.885445, 1.000000, 18.984889, 16.264591, 13.644617, -0.255319 +-18.4665, 5.22648, -28.537131, 4.936111, -0.185021, -0.000459, 0.000000, 1496957380.313900, 2.885439, 1.000000, 19.034250, 16.264591, 13.592736, -0.255319 +-18.5149, 5.23823, -28.537403, 4.933333, -0.107273, -0.000421, 0.000776, 1496957380.324400, 2.885375, 1.000000, 19.083583, 16.264591, 13.592736, -0.234043 +-18.5632, 5.24999, -28.537641, 4.933333, -0.181176, -0.000421, 0.000000, 1496957380.334000, 2.885380, 1.000000, 19.132917, 16.264591, 13.615625, -0.234043 +-18.6116, 5.26176, -28.537937, 4.927778, -0.149091, -0.000421, 0.000000, 1496957380.344500, 2.885444, 1.000000, 19.182194, 16.179140, 13.615625, -0.234043 +-18.6599, 5.27357, -28.538147, 4.927778, 0.013429, -0.000421, 0.000000, 1496957380.354200, 2.885433, 1.000000, 19.231472, 16.179140, 13.644617, -0.234043 +-18.7082, 5.2854, -28.538431, 4.927778, -0.003619, -0.000421, 0.000000, 1496957380.363800, 2.885495, 1.000000, 19.280750, 16.276798, 13.644617, -0.234043 +-18.7566, 5.29729, -28.538692, 4.927778, 0.058504, -0.000421, 0.000000, 1496957380.374600, 2.885524, 1.000000, 19.330028, 16.276798, 13.652246, -0.234043 +-18.8049, 5.30918, -28.539002, 4.922222, -0.010222, -0.000421, 0.000000, 1496957380.384200, 2.885536, 1.000000, 19.379250, 16.301212, 13.652246, -0.234043 +-18.8531, 5.32108, -28.539288, 4.922222, -0.234541, -0.000421, 0.000000, 1496957380.393600, 2.885616, 1.000000, 19.428472, 16.301212, 13.685817, -0.234043 +-18.9014, 5.333, -28.539596, 4.916667, -0.125911, -0.000421, 0.000000, 1496957380.404700, 2.885686, 1.000000, 19.477639, 16.276798, 13.685817, -0.234043 +-18.9496, 5.3449, -28.539791, 4.916667, -0.210731, -0.000421, 0.000000, 1496957380.414700, 2.885722, 1.000000, 19.526806, 16.276798, 13.618677, -0.234043 +-18.9979, 5.35684, -28.539996, 4.911111, -0.101059, -0.000421, 0.000000, 1496957380.424100, 2.885700, 1.000000, 19.575917, 16.227970, 13.618677, -0.234043 +-19.0461, 5.36876, -28.540067, 4.911111, -0.115891, -0.000421, 0.000000, 1496957380.433600, 2.885748, 1.000000, 19.625028, 16.227970, 13.652246, -0.234043 +-19.0943, 5.38069, -28.540133, 4.913889, -0.127303, -0.000421, 0.000000, 1496957380.444200, 2.885764, 1.000000, 19.674167, 16.252384, 13.652246, -0.234043 +-19.1425, 5.39257, -28.540080, 4.913889, -0.156737, -0.000421, 0.000000, 1496957380.453800, 2.885831, 1.000000, 19.723306, 16.252384, 13.586633, -0.234043 +-19.1907, 5.40441, -28.540082, 4.908333, -0.141484, -0.000421, 0.000000, 1496957380.464300, 2.885860, 1.000000, 19.772389, 16.374456, 13.586633, -0.234043 +-19.2389, 5.4162, -28.539979, 4.908333, -0.219513, -0.000421, 0.000000, 1496957380.473800, 2.885896, 1.000000, 19.821472, 16.374456, 13.662929, -0.234043 +-19.2871, 5.42797, -28.539900, 4.902778, -0.170409, -0.000421, 0.000000, 1496957380.484300, 2.885955, 1.000000, 19.870500, 16.289005, 13.662929, -0.234043 +-19.3353, 5.43969, -28.539720, 4.902778, -0.202568, -0.000421, 0.000000, 1496957380.494500, 2.885972, 1.000000, 19.919528, 16.289005, 13.690394, -0.234043 +-19.3834, 5.45135, -28.539591, 4.900000, -0.209568, -0.000421, 0.000000, 1496957380.504300, 2.885981, 1.000000, 19.968528, 16.191349, 13.690394, -0.234043 +-19.4798, 5.47462, -28.539314, 4.900000, 0.000872, -0.000421, 0.000000, 1496957380.513800, 2.885926, 1.000000, 20.017528, 16.191349, 13.643091, -0.234043 +-19.4798, 5.47462, -28.539314, 4.900000, 0.000872, -0.000421, 0.000000, 1496957380.524300, 2.885926, 1.000000, 20.066528, 16.227970, 13.643091, -0.234043 +-19.5279, 5.48622, -28.539155, 4.900000, -0.142045, -0.000421, 0.000000, 1496957380.534300, 2.885920, 1.000000, 20.115528, 16.227970, 13.699550, -0.234043 +-19.5761, 5.49777, -28.538998, 4.891667, -0.239131, -0.000383, 0.000782, 1496957380.543900, 2.885910, 1.000000, 20.164444, 16.227970, 13.699550, -0.212766 +-19.6242, 5.50928, -28.538817, 4.891667, -0.188193, -0.000383, 0.000000, 1496957380.554500, 2.885886, 1.000000, 20.213361, 16.227970, 13.588159, -0.212766 +-19.6724, 5.5208, -28.538674, 4.886111, -0.047328, -0.000383, 0.000000, 1496957380.564100, 2.885873, 1.000000, 20.262222, 16.203556, 13.588159, -0.212766 +-19.7205, 5.53228, -28.538476, 4.886111, -0.061573, -0.000383, 0.000000, 1496957380.573500, 2.885814, 1.000000, 20.311083, 16.203556, 13.667506, -0.212766 +-19.7687, 5.54374, -28.538332, 4.886111, -0.006837, -0.000383, 0.000000, 1496957380.584100, 2.885717, 1.000000, 20.359944, 16.276798, 13.667506, -0.212766 +-19.8168, 5.55522, -28.538234, 4.886111, -0.074791, -0.000383, 0.000000, 1496957380.593500, 2.885721, 1.000000, 20.408806, 16.276798, 13.646143, -0.212766 +-19.8649, 5.56667, -28.538181, 4.883333, -0.082997, -0.000383, 0.000000, 1496957380.604100, 2.885688, 1.000000, 20.457639, 16.350042, 13.646143, -0.212766 +-19.913, 5.5781, -28.538069, 4.883333, -0.163421, -0.000383, 0.000000, 1496957380.613500, 2.885672, 1.000000, 20.506472, 16.350042, 13.647669, -0.212766 +-19.9611, 5.58951, -28.538014, 4.877778, -0.131428, -0.000383, 0.000000, 1496957380.624100, 2.885625, 1.000000, 20.555250, 16.227970, 13.647669, -0.212766 +-20.0092, 5.60093, -28.537968, 4.877778, -0.147317, -0.000383, 0.000000, 1496957380.633500, 2.885584, 1.000000, 20.604028, 16.227970, 13.667506, -0.212766 +-20.0573, 5.61235, -28.538025, 4.875000, -0.007763, -0.000383, 0.000000, 1496957380.644100, 2.885560, 1.000000, 20.652778, 16.337835, 13.667506, -0.212766 +-20.1054, 5.62377, -28.538043, 4.875000, -0.078054, -0.000383, 0.000000, 1496957380.654500, 2.885529, 1.000000, 20.701528, 16.337835, 13.661403, -0.212766 +-20.1535, 5.63518, -28.538063, 4.877778, -0.034600, -0.000383, 0.000000, 1496957380.664100, 2.885507, 1.000000, 20.750306, 16.191349, 13.661403, -0.212766 +-20.2016, 5.64656, -28.538147, 4.877778, -0.138653, -0.000383, 0.000000, 1496957380.673500, 2.885463, 1.000000, 20.799083, 16.191349, 13.690394, -0.212766 +-20.2496, 5.65795, -28.538246, 4.875000, -0.018905, -0.000383, 0.000000, 1496957380.684100, 2.885475, 1.000000, 20.847833, 16.240177, 13.690394, -0.212766 +-20.2977, 5.66934, -28.538276, 4.875000, -0.086553, -0.000383, 0.000000, 1496957380.693500, 2.885487, 1.000000, 20.896583, 16.240177, 13.588159, -0.212766 +-20.3457, 5.68076, -28.538311, 4.872222, -0.078915, -0.000421, -0.000786, 1496957380.704100, 2.885497, 1.000000, 20.945306, 16.227970, 13.588159, -0.234043 +-20.3937, 5.69212, -28.538290, 4.872222, -0.432432, -0.000421, 0.000000, 1496957380.713500, 2.885470, 1.000000, 20.994028, 16.227970, 13.633936, -0.234043 +-20.4417, 5.70352, -28.538293, 4.869444, -0.261728, -0.000421, 0.000000, 1496957380.724200, 2.885416, 1.000000, 21.042722, 16.313421, 13.633936, -0.234043 +-20.4897, 5.71494, -28.538209, 4.869444, -0.098308, -0.000421, 0.000000, 1496957380.733700, 2.885367, 1.000000, 21.091417, 16.313421, 13.627832, -0.234043 +-20.5376, 5.72635, -28.538115, 4.869444, -0.100267, -0.000459, -0.000786, 1496957380.744300, 2.885352, 1.000000, 21.140111, 16.374456, 13.627832, -0.255319 +-20.5855, 5.73782, -28.537899, 4.869444, -0.155941, -0.000459, 0.000000, 1496957380.753800, 2.885384, 1.000000, 21.188806, 16.374456, 13.664454, -0.255319 +-20.6334, 5.74927, -28.537585, 4.872222, -0.342548, -0.000421, 0.000786, 1496957380.764300, 2.885443, 1.000000, 21.237528, 16.289005, 13.664454, -0.234043 +-20.6812, 5.7607, -28.537250, 4.872222, -0.470910, -0.000421, 0.000000, 1496957380.773900, 2.885513, 1.000000, 21.286250, 16.289005, 13.611048, -0.234043 +-20.729, 5.77217, -28.536814, 4.863889, -0.288749, -0.000383, 0.000787, 1496957380.783600, 2.885563, 1.000000, 21.334889, 16.313421, 13.611048, -0.212766 +-20.7768, 5.78359, -28.536374, 4.863889, -0.261110, -0.000383, 0.000000, 1496957380.794200, 2.885567, 1.000000, 21.383528, 16.313421, 13.667506, -0.212766 +-20.8247, 5.79508, -28.536066, 4.863889, 0.031569, -0.000383, 0.000000, 1496957380.803700, 2.885655, 1.000000, 21.432167, 16.337835, 13.667506, -0.212766 +-20.8725, 5.80658, -28.535563, 4.863889, 0.119311, -0.000383, 0.000000, 1496957380.814200, 2.885657, 1.000000, 21.480806, 16.337835, 13.650721, -0.212766 +-20.9203, 5.81813, -28.535090, 4.866667, 0.013443, -0.000344, 0.000786, 1496957380.823800, 2.885716, 1.000000, 21.529472, 16.240177, 13.650721, -0.191489 +-20.968, 5.82964, -28.534375, 4.866667, -0.399924, -0.000344, 0.000000, 1496957380.834300, 2.885825, 1.000000, 21.578139, 16.240177, 13.641565, -0.191489 +-21.0157, 5.84114, -28.533770, 4.852778, -0.605082, -0.000306, 0.000789, 1496957380.843800, 2.885935, 1.000000, 21.626667, 16.252384, 13.641565, -0.170213 +-21.0633, 5.85263, -28.533117, 4.852778, -0.260669, -0.000306, 0.000000, 1496957380.854300, 2.885995, 1.000000, 21.675194, 16.252384, 13.643091, -0.170213 +-21.111, 5.86417, -28.532495, 4.841667, -0.074553, -0.000230, 0.001581, 1496957380.863900, 2.886059, 1.000000, 21.723611, 16.264591, 13.643091, -0.127660 +-21.1587, 5.87569, -28.531833, 4.841667, -0.138894, -0.000230, 0.000000, 1496957380.874600, 2.886106, 1.000000, 21.772028, 16.264591, 13.623255, -0.127660 +-21.2063, 5.88722, -28.531205, 4.836111, -0.152619, -0.000191, 0.000791, 1496957380.884200, 2.886205, 1.000000, 21.820389, 16.313421, 13.623255, -0.106383 +-21.2539, 5.89879, -28.530588, 4.836111, -0.106581, -0.000191, 0.000000, 1496957380.893800, 2.886329, 1.000000, 21.868750, 16.313421, 13.632410, -0.106383 +-21.3015, 5.91034, -28.529970, 4.836111, -0.076252, -0.000153, 0.000791, 1496957380.904800, 2.886422, 1.000000, 21.917111, 16.276798, 13.632410, -0.085106 +-21.3491, 5.92192, -28.529332, 4.836111, -0.047489, -0.000153, 0.000000, 1496957380.913600, 2.886505, 1.000000, 21.965472, 16.276798, 13.624781, -0.085106 +-21.3967, 5.93351, -28.528770, 4.836111, -0.040851, -0.000115, 0.000791, 1496957380.924100, 2.886556, 1.000000, 22.013833, 16.252384, 13.624781, -0.063830 +-21.4443, 5.94511, -28.528280, 4.836111, -0.203514, -0.000115, 0.000000, 1496957380.934700, 2.886614, 1.000000, 22.062194, 16.252384, 13.652246, -0.063830 +-21.4918, 5.95672, -28.527912, 4.830555, 0.095789, -0.000077, 0.000792, 1496957380.944200, 2.886671, 1.000000, 22.110500, 16.240177, 13.652246, -0.042553 +-21.5394, 5.96832, -28.527546, 4.830555, -0.012762, -0.000077, 0.000000, 1496957380.953800, 2.886699, 1.000000, 22.158806, 16.240177, 13.685817, -0.042553 +-21.587, 5.97992, -28.527191, 4.819445, -0.068260, -0.000038, 0.000794, 1496957380.964300, 2.886788, 1.000000, 22.207000, 16.289005, 13.685817, -0.021277 +-21.6345, 5.9915, -28.526750, 4.819445, -0.181374, -0.000038, 0.000000, 1496957380.973800, 2.886779, 1.000000, 22.255194, 16.289005, 13.615625, -0.021277 +-21.682, 6.00306, -28.526315, 4.816667, -0.275722, -0.000038, 0.000000, 1496957380.984400, 2.886859, 1.000000, 22.303361, 16.350042, 13.615625, -0.021277 +-21.7295, 6.01456, -28.525977, 4.816667, -0.278319, -0.000038, 0.000000, 1496957380.993900, 2.886836, 1.000000, 22.351528, 16.350042, 13.667506, -0.021277 +-21.777, 6.02607, -28.525496, 4.813889, -0.123897, -0.000038, 0.000000, 1496957381.004400, 2.886786, 1.000000, 22.399667, 16.264591, 13.667506, -0.021277 +-21.8245, 6.03748, -28.525319, 4.813889, -0.062625, -0.000038, 0.000000, 1496957381.014000, 2.886776, 1.000000, 22.447806, 16.264591, 13.685817, -0.021277 +-21.872, 6.04888, -28.525045, 4.813889, -0.088194, -0.000077, -0.000795, 1496957381.024500, 2.886728, 1.000000, 22.495944, 16.289005, 13.685817, -0.042553 +-21.9196, 6.0602, -28.524760, 4.813889, 0.029026, -0.000077, 0.000000, 1496957381.034100, 2.886726, 1.000000, 22.544083, 16.289005, 13.665980, -0.042553 +-21.9671, 6.07143, -28.524473, 4.808333, -0.161497, -0.000077, 0.000000, 1496957381.043600, 2.886669, 1.000000, 22.592167, 16.313421, 13.665980, -0.042553 +-22.0146, 6.08264, -28.524206, 4.808333, -0.220153, -0.000077, 0.000000, 1496957381.054100, 2.886605, 1.000000, 22.640250, 16.313421, 13.643091, -0.042553 +-22.0621, 6.09384, -28.523925, 4.808333, -0.303600, -0.000115, -0.000796, 1496957381.063500, 2.886535, 1.000000, 22.688333, 16.301212, 13.643091, -0.063830 +-22.1095, 6.10497, -28.523744, 4.808333, -0.167984, -0.000115, 0.000000, 1496957381.074100, 2.886514, 1.000000, 22.736417, 16.301212, 13.662929, -0.063830 +-22.1562, 6.1163, -28.523361, 4.808333, -0.146846, -0.000153, -0.000796, 1496957381.083500, 2.887454, 1.000000, 22.784500, 16.362249, 13.662929, -0.085106 +-22.2032, 6.12741, -28.523005, 4.808333, -0.076210, -0.000153, 0.000000, 1496957381.094100, 2.887433, 1.000000, 22.832583, 16.362249, 13.699550, -0.085106 +-22.2502, 6.13855, -28.522874, 4.805555, -0.068217, -0.000191, -0.000796, 1496957381.103600, 2.887393, 1.000000, 22.880639, 16.313421, 13.699550, -0.106383 +-22.2972, 6.14967, -28.522571, 4.805555, -0.026762, -0.000191, 0.000000, 1496957381.114100, 2.887396, 1.000000, 22.928694, 16.313421, 13.620203, -0.106383 +-22.3442, 6.1608, -28.522392, 4.805555, -0.133142, -0.000191, 0.000000, 1496957381.123500, 2.887421, 1.000000, 22.976750, 16.264591, 13.620203, -0.106383 +-22.3912, 6.17197, -28.522189, 4.805555, -0.093686, -0.000191, 0.000000, 1496957381.134100, 2.887418, 1.000000, 23.024806, 16.264591, 13.688869, -0.106383 +-22.4382, 6.1831, -28.522065, 4.811111, -0.007662, -0.000230, -0.000796, 1496957381.143600, 2.887421, 1.000000, 23.072917, 16.264591, 13.688869, -0.127660 +-22.4851, 6.19428, -28.522022, 4.811111, -0.037719, -0.000230, 0.000000, 1496957381.154200, 2.887380, 1.000000, 23.121028, 16.264591, 13.673610, -0.127660 +-22.5321, 6.20543, -28.521938, 4.802778, -0.101371, -0.000268, -0.000797, 1496957381.163700, 2.887421, 1.000000, 23.169056, 16.264591, 13.673610, -0.148936 +-22.579, 6.2166, -28.521751, 4.802778, -0.065576, -0.000268, 0.000000, 1496957381.174300, 2.887433, 1.000000, 23.217083, 16.264591, 13.643091, -0.148936 +-22.6259, 6.22775, -28.521554, 4.797222, -0.292398, -0.000306, -0.000798, 1496957381.183900, 2.887429, 1.000000, 23.265056, 16.264591, 13.643091, -0.170213 +-22.6728, 6.23892, -28.521304, 4.797222, -0.335953, -0.000306, 0.000000, 1496957381.194600, 2.887445, 1.000000, 23.313028, 16.264591, 13.633936, -0.170213 +-22.7197, 6.25007, -28.521062, 4.800000, -0.116927, -0.000344, -0.000797, 1496957381.204300, 2.887445, 1.000000, 23.361028, 16.313421, 13.633936, -0.191489 +-22.7665, 6.26122, -28.520683, 4.800000, -0.154421, -0.000344, 0.000000, 1496957381.213800, 2.887453, 1.000000, 23.409028, 16.313421, 13.739223, -0.191489 +-22.8134, 6.2723, -28.520347, 4.800000, -0.180341, -0.000383, -0.000797, 1496957381.224300, 2.887497, 1.000000, 23.457028, 16.313421, 13.739223, -0.212766 +-22.8602, 6.2834, -28.520038, 4.800000, -0.220388, -0.000383, 0.000000, 1496957381.233900, 2.887415, 1.000000, 23.505028, 16.313421, 13.652246, -0.212766 +-22.907, 6.29445, -28.519666, 4.794445, -0.185721, -0.000421, -0.000798, 1496957381.244400, 2.887435, 1.000000, 23.552972, 16.313421, 13.652246, -0.234043 +-22.9538, 6.30544, -28.519292, 4.794445, -0.284268, -0.000421, 0.000000, 1496957381.254000, 2.887383, 1.000000, 23.600917, 16.313421, 13.667506, -0.234043 +-23.0006, 6.31646, -28.518848, 4.788889, -0.133509, -0.000498, -0.001598, 1496957381.264500, 2.887315, 1.000000, 23.648806, 16.227970, 13.667506, -0.276596 +-23.0474, 6.32743, -28.518520, 4.788889, -0.270515, -0.000498, 0.000000, 1496957381.274000, 2.887281, 1.000000, 23.696694, 16.227970, 13.627832, -0.276596 +-23.0942, 6.33846, -28.517811, 4.783333, -0.136836, -0.000574, -0.001600, 1496957381.284600, 2.887230, 1.000000, 23.744528, 16.264591, 13.627832, -0.319149 +-23.1409, 6.34947, -28.517326, 4.783333, -0.268818, -0.000574, 0.000000, 1496957381.294100, 2.887168, 1.000000, 23.792361, 16.264591, 13.638514, -0.319149 +-23.1875, 6.36046, -28.516659, 4.777778, -0.445885, -0.000651, -0.001602, 1496957381.303500, 2.887162, 1.000000, 23.840139, 16.276798, 13.638514, -0.361702 +-23.2343, 6.37151, -28.515897, 4.777778, -0.121738, -0.000651, 0.000000, 1496957381.314000, 2.887108, 1.000000, 23.887917, 16.276798, 13.586633, -0.361702 +-23.2809, 6.38245, -28.515300, 4.777778, -0.166175, -0.000727, -0.001602, 1496957381.324500, 2.887065, 1.000000, 23.935694, 16.276798, 13.586633, -0.404255 +-23.3276, 6.39343, -28.514597, 4.777778, -0.248058, -0.000727, 0.000000, 1496957381.334000, 2.887039, 1.000000, 23.983472, 16.276798, 13.626307, -0.404255 +-23.3742, 6.40445, -28.513805, 4.769444, -0.101622, -0.000842, -0.002408, 1496957381.343500, 2.887013, 1.000000, 24.031167, 16.362249, 13.626307, -0.468085 +-23.4208, 6.41536, -28.513123, 4.769444, -0.243962, -0.000842, 0.000000, 1496957381.354000, 2.887083, 1.000000, 24.078861, 16.362249, 13.635462, -0.468085 +-23.4674, 6.42635, -28.512352, 4.761111, -0.281724, -0.000957, -0.002412, 1496957381.364600, 2.887041, 1.000000, 24.126472, 16.313421, 13.635462, -0.531915 +-23.5139, 6.43729, -28.511631, 4.761111, -0.271633, -0.000957, 0.000000, 1496957381.374400, 2.887030, 1.000000, 24.174083, 16.313421, 13.676661, -0.531915 +-23.5605, 6.44822, -28.511003, 4.752778, -0.251270, -0.001072, -0.002416, 1496957381.383900, 2.886981, 1.000000, 24.221611, 16.252384, 13.676661, -0.595745 +-23.607, 6.45922, -28.510466, 4.752778, 0.039134, -0.001072, 0.000000, 1496957381.394500, 2.886970, 1.000000, 24.269139, 16.252384, 13.681239, -0.595745 +-23.6535, 6.47016, -28.509942, 4.750000, -0.085290, -0.001148, -0.001612, 1496957381.404200, 2.886941, 1.000000, 24.316639, 16.252384, 13.681239, -0.638298 +-23.7, 6.48117, -28.509568, 4.750000, 0.018009, -0.001148, 0.000000, 1496957381.413800, 2.886938, 1.000000, 24.364139, 16.252384, 13.659877, -0.638298 +-23.7466, 6.49214, -28.509125, 4.750000, -0.017242, -0.001187, -0.000806, 1496957381.424300, 2.886948, 1.000000, 24.411639, 16.264591, 13.659877, -0.659574 +-23.793, 6.50311, -28.508751, 4.750000, -0.305534, -0.001187, 0.000000, 1496957381.433800, 2.886912, 1.000000, 24.459139, 16.264591, 13.659877, -0.659574 +-23.8395, 6.5141, -28.508163, 4.747222, -0.204602, -0.001225, -0.000806, 1496957381.444200, 2.886887, 1.000000, 24.506611, 16.325628, 13.659877, -0.680851 +-23.8859, 6.52505, -28.507886, 4.747222, -0.375434, -0.001225, 0.000000, 1496957381.453700, 2.886834, 1.000000, 24.554083, 16.325628, 13.632410, -0.680851 +-23.9323, 6.53606, -28.507290, 4.750000, -0.143401, -0.001263, -0.000806, 1496957381.464200, 2.886750, 1.000000, 24.601583, 16.337835, 13.632410, -0.702128 +-23.9786, 6.54707, -28.506957, 4.750000, -0.174871, -0.001263, 0.000000, 1496957381.473700, 2.886742, 1.000000, 24.649083, 16.337835, 13.662929, -0.702128 +-24.025, 6.55808, -28.506541, 4.747222, -0.144225, -0.001301, -0.000806, 1496957381.484300, 2.886722, 1.000000, 24.696556, 16.276798, 13.662929, -0.723404 +-24.0714, 6.56913, -28.506258, 4.747222, 0.021830, -0.001301, 0.000000, 1496957381.493900, 2.886727, 1.000000, 24.744028, 16.276798, 13.688869, -0.723404 +-24.1178, 6.5801, -28.505986, 4.747222, 0.005929, -0.001301, 0.000000, 1496957381.504600, 2.886701, 1.000000, 24.791500, 16.362249, 13.688869, -0.723404 +-24.1641, 6.59109, -28.505866, 4.747222, -0.080355, -0.001301, 0.000000, 1496957381.514100, 2.886594, 1.000000, 24.838972, 16.362249, 13.685817, -0.723404 +-24.2105, 6.6021, -28.505815, 4.744444, -0.063359, -0.001301, 0.000000, 1496957381.523700, 2.886544, 1.000000, 24.886417, 16.276798, 13.685817, -0.723404 +-24.2568, 6.6131, -28.505781, 4.744444, -0.170123, -0.001301, 0.000000, 1496957381.534300, 2.886417, 1.000000, 24.933861, 16.276798, 13.636988, -0.723404 +-24.3031, 6.62411, -28.505874, 4.736111, -0.116024, -0.001301, 0.000000, 1496957381.543800, 2.886402, 1.000000, 24.981222, 16.276798, 13.636988, -0.723404 +-24.3494, 6.63516, -28.505891, 4.736111, 0.047388, -0.001301, 0.000000, 1496957381.554300, 2.886304, 1.000000, 25.028583, 16.276798, 13.632410, -0.723404 +-24.3957, 6.64621, -28.506066, 4.736111, -0.121043, -0.001340, -0.000808, 1496957381.563900, 2.886266, 1.000000, 25.075944, 16.276798, 13.632410, -0.744681 +-24.442, 6.6573, -28.506095, 4.736111, -0.104736, -0.001340, 0.000000, 1496957381.574400, 2.886198, 1.000000, 25.123306, 16.276798, 13.665980, -0.744681 +-24.4882, 6.66836, -28.506327, 4.738889, -0.079226, -0.001340, 0.000000, 1496957381.583900, 2.886157, 1.000000, 25.170694, 16.313421, 13.665980, -0.744681 +-24.5345, 6.67942, -28.506300, 4.738889, -0.207677, -0.001340, 0.000000, 1496957381.594500, 2.886089, 1.000000, 25.218083, 16.313421, 13.662929, -0.744681 +-24.5807, 6.69045, -28.506466, 4.736111, -0.238442, -0.001378, -0.000808, 1496957381.603900, 2.886052, 1.000000, 25.265444, 16.362249, 13.662929, -0.765957 +-24.6269, 6.7015, -28.506507, 4.736111, -0.122224, -0.001378, 0.000000, 1496957381.614400, 2.886023, 1.000000, 25.312806, 16.362249, 13.665980, -0.765957 +-24.6731, 6.71252, -28.506545, 4.733333, -0.219600, -0.001454, -0.001617, 1496957381.624200, 2.885985, 1.000000, 25.360139, 16.276798, 13.665980, -0.808511 +-24.7193, 6.72353, -28.506589, 4.733333, -0.187263, -0.001454, 0.000000, 1496957381.633600, 2.885968, 1.000000, 25.407472, 16.276798, 13.646143, -0.808511 +-24.7654, 6.73451, -28.506584, 4.730556, -0.178153, -0.001493, -0.000809, 1496957381.644100, 2.885933, 1.000000, 25.454778, 16.325628, 13.646143, -0.829787 +-24.8116, 6.74548, -28.506525, 4.730556, -0.129103, -0.001493, 0.000000, 1496957381.653500, 2.885832, 1.000000, 25.502083, 16.325628, 13.737698, -0.829787 +-24.8577, 6.75644, -28.506409, 4.727778, -0.183768, -0.001569, -0.001619, 1496957381.664000, 2.885837, 1.000000, 25.549361, 16.264591, 13.737698, -0.872340 +-24.9038, 6.76737, -28.506301, 4.727778, -0.310000, -0.001569, 0.000000, 1496957381.674600, 2.885800, 1.000000, 25.596639, 16.264591, 13.673610, -0.872340 +-24.9499, 6.77826, -28.506037, 4.725000, -0.350318, -0.001608, -0.000810, 1496957381.684200, 2.885734, 1.000000, 25.643889, 16.240177, 13.673610, -0.893617 +-24.996, 6.78913, -28.505839, 4.725000, -0.314705, -0.001608, 0.000000, 1496957381.693600, 2.885625, 1.000000, 25.691139, 16.240177, 13.659877, -0.893617 +-25.042, 6.8, -28.505571, 4.716667, -0.179617, -0.001684, -0.001623, 1496957381.704200, 2.885568, 1.000000, 25.738306, 16.337835, 13.659877, -0.936170 +-25.0881, 6.81088, -28.505312, 4.716667, -0.014525, -0.001684, 0.000000, 1496957381.713600, 2.885496, 1.000000, 25.785472, 16.337835, 13.682765, -0.936170 +-25.1341, 6.82174, -28.505092, 4.716667, -0.178853, -0.001722, -0.000811, 1496957381.724100, 2.885396, 1.000000, 25.832639, 16.313421, 13.682765, -0.957447 +-25.1802, 6.83258, -28.504791, 4.716667, -0.102620, -0.001722, 0.000000, 1496957381.733500, 2.885376, 1.000000, 25.879806, 16.313421, 13.650721, -0.957447 +-25.2262, 6.84338, -28.504563, 4.711111, -0.154079, -0.001722, 0.000000, 1496957381.744100, 2.885290, 1.000000, 25.926917, 16.313421, 13.650721, -0.957447 +-25.2722, 6.8542, -28.504169, 4.711111, -0.161466, -0.001722, 0.000000, 1496957381.753600, 2.885145, 1.000000, 25.974028, 16.313421, 13.670558, -0.957447 +-25.3182, 6.86502, -28.503867, 4.711111, -0.093539, -0.001684, 0.000812, 1496957381.764100, 2.885071, 1.000000, 26.021139, 16.276798, 13.670558, -0.936170 +-25.3642, 6.87584, -28.503533, 4.711111, -0.149331, -0.001684, 0.000000, 1496957381.773500, 2.884923, 1.000000, 26.068250, 16.276798, 13.640039, -0.936170 +-25.4101, 6.88667, -28.503155, 4.700000, -0.388149, -0.001684, 0.000000, 1496957381.784100, 2.884780, 1.000000, 26.115250, 16.252384, 13.640039, -0.936170 +-25.456, 6.89755, -28.502857, 4.700000, -0.233598, -0.001684, 0.000000, 1496957381.793600, 2.884705, 1.000000, 26.162250, 16.252384, 13.614100, -0.936170 +-25.5019, 6.90848, -28.502445, 4.691667, 0.004266, -0.001646, 0.000816, 1496957381.804200, 2.884607, 1.000000, 26.209167, 16.337835, 13.614100, -0.914894 +-25.5478, 6.91939, -28.502156, 4.691667, -0.215189, -0.001646, 0.000000, 1496957381.813700, 2.884524, 1.000000, 26.256083, 16.337835, 13.694972, -0.914894 +-25.5936, 6.93031, -28.501835, 4.691667, -0.070309, -0.001608, 0.000816, 1496957381.824300, 2.884412, 1.000000, 26.303000, 16.252384, 13.694972, -0.893617 +-25.6396, 6.94131, -28.501586, 4.691667, 0.302563, -0.001608, 0.000000, 1496957381.833800, 2.884352, 1.000000, 26.349917, 16.252384, 13.707179, -0.893617 +-25.6855, 6.95233, -28.501183, 4.702778, 0.064999, -0.001608, 0.000000, 1496957381.844300, 2.884338, 1.000000, 26.396944, 16.240177, 13.707179, -0.893617 +-25.7313, 6.96325, -28.500905, 4.702778, -0.386571, -0.001608, 0.000000, 1496957381.853800, 2.884253, 1.000000, 26.443972, 16.240177, 13.614100, -0.893617 +-25.7771, 6.97416, -28.500584, 4.686111, -0.244402, -0.001531, 0.001634, 1496957381.864400, 2.884152, 1.000000, 26.490833, 16.252384, 13.614100, -0.851064 +-25.8229, 6.98508, -28.500231, 4.686111, -0.356347, -0.001531, 0.000000, 1496957381.874100, 2.884021, 1.000000, 26.537694, 16.252384, 13.665980, -0.851064 +-25.8686, 6.99606, -28.499901, 4.666667, -0.371913, -0.001569, -0.000820, 1496957381.884100, 2.883944, 1.000000, 26.584361, 16.240177, 13.665980, -0.872340 +-25.9144, 7.0071, -28.499612, 4.666667, 0.057022, -0.001569, 0.000000, 1496957381.894600, 2.883860, 1.000000, 26.631028, 16.240177, 13.672084, -0.872340 +-25.9602, 7.01808, -28.499208, 4.672222, -0.086777, -0.001608, -0.000819, 1496957381.904200, 2.883812, 1.000000, 26.677750, 16.276798, 13.672084, -0.893617 +-26.0059, 7.02905, -28.498915, 4.672222, -0.135446, -0.001608, 0.000000, 1496957381.913600, 2.883739, 1.000000, 26.724472, 16.276798, 13.638514, -0.893617 +-26.0517, 7.04006, -28.498549, 4.677778, 0.289899, -0.001608, 0.000000, 1496957381.924100, 2.883679, 1.000000, 26.771250, 16.350042, 13.638514, -0.893617 +-26.0974, 7.05101, -28.498288, 4.677778, -0.002314, -0.001608, 0.000000, 1496957381.933600, 2.883621, 1.000000, 26.818028, 16.350042, 13.609522, -0.893617 +-26.1432, 7.06191, -28.497811, 4.675000, -0.337165, -0.001608, 0.000000, 1496957381.944200, 2.883539, 1.000000, 26.864778, 16.350042, 13.609522, -0.893617 +-26.1889, 7.07278, -28.497610, 4.675000, -0.263976, -0.001608, 0.000000, 1496957381.953600, 2.883421, 1.000000, 26.911528, 16.350042, 13.652246, -0.893617 +-26.2345, 7.08365, -28.497163, 4.661111, -0.368885, -0.001608, 0.000000, 1496957381.964200, 2.883297, 1.000000, 26.958139, 16.276798, 13.652246, -0.893617 +-26.2802, 7.09457, -28.496804, 4.661111, -0.175778, -0.001608, 0.000000, 1496957381.973700, 2.883193, 1.000000, 27.004750, 16.276798, 13.615625, -0.893617 +-26.3258, 7.1055, -28.496404, 4.652778, -0.249419, -0.001684, -0.001645, 1496957381.984200, 2.883044, 1.000000, 27.051278, 16.276798, 13.615625, -0.936170 +-26.3713, 7.11638, -28.495878, 4.652778, -0.744707, -0.001684, 0.000000, 1496957381.994200, 2.882976, 1.000000, 27.097806, 16.276798, 13.638514, -0.936170 +-26.4168, 7.12726, -28.495528, 4.647222, -0.518563, -0.001722, -0.000824, 1496957382.003900, 2.882816, 1.000000, 27.144278, 16.325628, 13.638514, -0.957447 +-26.4623, 7.13827, -28.495163, 4.647222, 0.117175, -0.001722, 0.000000, 1496957382.014500, 2.882676, 1.000000, 27.190750, 16.325628, 13.627832, -0.957447 +-26.5079, 7.14933, -28.494705, 4.655556, 0.435287, -0.001837, -0.002466, 1496957382.024100, 2.882610, 1.000000, 27.237306, 16.276798, 13.627832, -1.021277 +-26.5534, 7.16031, -28.494301, 4.655556, 0.076708, -0.001837, 0.000000, 1496957382.033600, 2.882556, 1.000000, 27.283861, 16.276798, 13.714808, -1.021277 +-26.5989, 7.17126, -28.493864, 4.669445, -0.247117, -0.001799, 0.000820, 1496957382.044200, 2.882476, 1.000000, 27.330556, 16.227970, 13.714808, -1.000000 +-26.6444, 7.18208, -28.493453, 4.669445, -0.499190, -0.001799, 0.000000, 1496957382.053700, 2.882406, 1.000000, 27.377250, 16.227970, 13.690394, -1.000000 +-26.6899, 7.1929, -28.492988, 4.658333, -0.324410, -0.001761, 0.000822, 1496957382.064200, 2.882213, 1.000000, 27.423833, 16.252384, 13.690394, -0.978723 +-26.7354, 7.20372, -28.492615, 4.658333, -0.068122, -0.001761, 0.000000, 1496957382.074200, 2.882069, 1.000000, 27.470417, 16.252384, 13.667506, -0.978723 +-26.781, 7.21465, -28.492340, 4.652778, -0.059030, -0.001837, -0.001645, 1496957382.083700, 2.883167, 1.000000, 27.516944, 16.154726, 13.667506, -1.021277 +-26.8267, 7.22565, -28.492056, 4.652778, 0.129953, -0.001837, 0.000000, 1496957382.094300, 2.883126, 1.000000, 27.563472, 16.154726, 13.585107, -1.021277 +-26.8725, 7.2366, -28.491842, 4.650000, 0.047730, -0.001837, 0.000000, 1496957382.103800, 2.883068, 1.000000, 27.609972, 15.996033, 13.585107, -1.021277 +-26.9183, 7.24752, -28.491552, 4.650000, -0.157470, -0.001837, 0.000000, 1496957382.114400, 2.883003, 1.000000, 27.656472, 15.996033, 13.664454, -1.021277 +-26.964, 7.25842, -28.491297, 4.644444, -0.242698, -0.001799, 0.000824, 1496957382.123800, 2.882903, 1.000000, 27.702917, 15.666438, 13.664454, -1.000000 +-27.0097, 7.26931, -28.491055, 4.644444, -0.279856, -0.001799, 0.000000, 1496957382.134400, 2.882780, 1.000000, 27.749361, 15.666438, 13.629358, -1.000000 +-27.0554, 7.28019, -28.490813, 4.638889, -0.241233, -0.001761, 0.000825, 1496957382.143900, 2.882652, 1.000000, 27.795750, 15.349051, 13.629358, -0.978723 +-27.1011, 7.29112, -28.490603, 4.638889, -0.122936, -0.001761, 0.000000, 1496957382.154600, 2.882496, 1.000000, 27.842139, 15.349051, 13.685817, -0.978723 +-27.1468, 7.30203, -28.490311, 4.638889, -0.044568, -0.001761, 0.000000, 1496957382.164100, 2.882366, 1.000000, 27.888528, 15.263599, 13.685817, -0.978723 +-27.1925, 7.31295, -28.490022, 4.638889, -0.088900, -0.001761, 0.000000, 1496957382.173600, 2.882250, 1.000000, 27.934917, 15.263599, 13.656825, -0.978723 +-27.2381, 7.32386, -28.489767, 4.636111, -0.072953, -0.001722, 0.000826, 1496957382.184100, 2.882132, 1.000000, 27.981278, 15.312428, 13.656825, -0.957447 +-27.2838, 7.33479, -28.489411, 4.636111, -0.116695, -0.001722, 0.000000, 1496957382.193500, 2.882020, 1.000000, 28.027639, 15.312428, 13.667506, -0.957447 +-27.3294, 7.34567, -28.489051, 4.633333, -0.343633, -0.001722, 0.000000, 1496957382.204100, 2.881917, 1.000000, 28.073972, 15.361258, 13.667506, -0.957447 +-27.375, 7.35654, -28.488626, 4.633333, -0.306823, -0.001722, 0.000000, 1496957382.213600, 2.881840, 1.000000, 28.120306, 15.361258, 13.643091, -0.957447 +-27.4205, 7.36737, -28.488150, 4.630556, -0.467149, -0.001722, 0.000000, 1496957382.224200, 2.881663, 1.000000, 28.166611, 15.361258, 13.643091, -0.957447 +-27.466, 7.37822, -28.487619, 4.630556, -0.226713, -0.001722, 0.000000, 1496957382.233800, 2.881523, 1.000000, 28.212917, 15.361258, 13.644617, -0.957447 +-27.5116, 7.38908, -28.487144, 4.630556, -0.005747, -0.001722, 0.000000, 1496957382.244300, 2.881380, 1.000000, 28.259222, 15.324636, 13.644617, -0.957447 +-27.5572, 7.39993, -28.486548, 4.630556, 0.022360, -0.001722, 0.000000, 1496957382.253800, 2.881258, 1.000000, 28.305528, 15.324636, 13.612574, -0.957447 +-27.6026, 7.4107, -28.486050, 4.625000, -0.335197, -0.001684, 0.000828, 1496957382.264300, 2.881077, 1.000000, 28.351778, 15.288014, 13.612574, -0.936170 +-27.6481, 7.42151, -28.485521, 4.625000, -0.235858, -0.001684, 0.000000, 1496957382.273800, 2.880886, 1.000000, 28.398028, 15.288014, 13.687343, -0.936170 +-27.6936, 7.43235, -28.484971, 4.619444, -0.112043, -0.001722, -0.000829, 1496957382.284500, 2.880782, 1.000000, 28.444222, 15.288014, 13.687343, -0.957447 +-27.739, 7.44316, -28.484446, 4.619444, -0.171587, -0.001722, 0.000000, 1496957382.293900, 2.880636, 1.000000, 28.490417, 15.288014, 13.656825, -0.957447 +-27.7845, 7.45402, -28.483997, 4.613889, 0.009581, -0.001722, 0.000000, 1496957382.304400, 2.880518, 1.000000, 28.536556, 15.288014, 13.656825, -0.957447 +-27.8299, 7.46495, -28.483541, 4.613889, -0.072042, -0.001722, 0.000000, 1496957382.314000, 2.880443, 1.000000, 28.582694, 15.288014, 13.687343, -0.957447 +-27.8752, 7.47589, -28.483062, 4.611111, -0.427639, -0.001722, 0.000000, 1496957382.324400, 2.880384, 1.000000, 28.628806, 15.336843, 13.687343, -0.957447 +-27.9205, 7.48686, -28.482765, 4.611111, -0.431687, -0.001722, 0.000000, 1496957382.334000, 2.880310, 1.000000, 28.674917, 15.336843, 13.589684, -0.957447 +-27.9658, 7.49788, -28.482424, 4.602778, -0.197459, -0.001722, 0.000000, 1496957382.344500, 2.880286, 1.000000, 28.720944, 15.312428, 13.589684, -0.957447 +-28.0111, 7.50893, -28.482214, 4.602778, -0.061157, -0.001722, 0.000000, 1496957382.353700, 2.880227, 1.000000, 28.766972, 15.312428, 13.647669, -0.957447 +-28.0563, 7.52002, -28.482125, 4.594444, -0.413837, -0.001722, 0.000000, 1496957382.364000, 2.880186, 1.000000, 28.812917, 15.288014, 13.647669, -0.957447 +-28.1014, 7.53121, -28.482109, 4.594444, -0.458282, -0.001722, 0.000000, 1496957382.374300, 2.880233, 1.000000, 28.858861, 15.288014, 13.623255, -0.957447 +-28.1464, 7.54238, -28.482023, 4.591667, -0.478566, -0.001684, 0.000834, 1496957382.383800, 2.880271, 1.000000, 28.904778, 15.263599, 13.623255, -0.936170 +-28.1914, 7.55358, -28.482075, 4.591667, -0.442622, -0.001684, 0.000000, 1496957382.394300, 2.880337, 1.000000, 28.950694, 15.263599, 13.633936, -0.936170 +-28.2365, 7.56481, -28.482111, 4.608333, 0.084930, -0.001608, 0.001661, 1496957382.403800, 2.880382, 1.000000, 28.996778, 15.336843, 13.633936, -0.893617 +-28.2816, 7.57607, -28.482181, 4.608333, 0.106645, -0.001608, 0.000000, 1496957382.414400, 2.880363, 1.000000, 29.042861, 15.336843, 13.646143, -0.893617 +-28.3265, 7.58744, -28.482382, 4.625000, -0.022920, -0.001569, 0.000828, 1496957382.423900, 2.880404, 1.000000, 29.089111, 15.275806, 13.646143, -0.872340 +-28.3715, 7.59884, -28.482782, 4.625000, -0.029656, -0.001569, 0.000000, 1496957382.434600, 2.880499, 1.000000, 29.135361, 15.275806, 13.630884, -0.872340 +-28.4165, 7.61024, -28.483209, 4.613889, 0.005549, -0.001454, 0.002489, 1496957382.444200, 2.880513, 1.000000, 29.181500, 15.263599, 13.630884, -0.808511 +-28.4614, 7.6216, -28.484018, 4.613889, -0.186693, -0.001454, 0.000000, 1496957382.453800, 2.880535, 1.000000, 29.227639, 15.263599, 13.617151, -0.808511 +-28.5064, 7.63318, -28.484546, 4.605556, 0.013090, -0.001454, 0.000000, 1496957382.464300, 2.880510, 1.000000, 29.273694, 15.251392, 13.617151, -0.808511 +-28.5513, 7.64469, -28.485209, 4.605556, -0.002741, -0.001454, 0.000000, 1496957382.473800, 2.880575, 1.000000, 29.319750, 15.251392, 13.615625, -0.808511 +-28.5961, 7.65627, -28.485914, 4.605556, -0.341690, -0.001416, 0.000831, 1496957382.484300, 2.880450, 1.000000, 29.365806, 15.275806, 13.615625, -0.787234 +-28.6409, 7.66782, -28.486254, 4.605556, -0.259857, -0.001416, 0.000000, 1496957382.494100, 2.880434, 1.000000, 29.411861, 15.275806, 13.653772, -0.787234 +-28.6857, 7.67927, -28.486944, 4.605556, -0.429457, -0.001416, 0.000000, 1496957382.503600, 2.880413, 1.000000, 29.457917, 15.336843, 13.653772, -0.787234 +-28.7305, 7.69081, -28.487386, 4.605556, -0.324758, -0.001416, 0.000000, 1496957382.514000, 2.880293, 1.000000, 29.503972, 15.336843, 13.669032, -0.787234 +-28.7753, 7.70224, -28.488048, 4.605556, 0.013391, -0.001416, 0.000000, 1496957382.524500, 2.880237, 1.000000, 29.550028, 15.251392, 13.669032, -0.787234 +-28.8201, 7.71369, -28.488832, 4.605556, 0.218452, -0.001416, 0.000000, 1496957382.534500, 2.880109, 1.000000, 29.596083, 15.251392, 13.621729, -0.787234 +-28.865, 7.72505, -28.489447, 4.600000, 0.075058, -0.001454, -0.000832, 1496957382.544100, 2.880078, 1.000000, 29.642083, 15.251392, 13.621729, -0.808511 +-28.9099, 7.7365, -28.489928, 4.600000, 0.267529, -0.001454, 0.000000, 1496957382.553600, 2.879978, 1.000000, 29.688083, 15.251392, 13.643091, -0.808511 +-28.9547, 7.74784, -28.490525, 4.600000, -0.298371, -0.001454, 0.000000, 1496957382.564200, 2.879880, 1.000000, 29.734083, 15.324636, 13.643091, -0.808511 +-28.9995, 7.75915, -28.491115, 4.591667, -0.410282, -0.001454, 0.000000, 1496957382.573800, 2.879785, 1.000000, 29.780000, 15.324636, 13.623255, -0.808511 +-29.0443, 7.77054, -28.491214, 4.591667, -0.077899, -0.001454, 0.000000, 1496957382.584200, 2.879626, 1.000000, 29.825917, 15.263599, 13.623255, -0.808511 +-29.0889, 7.78165, -28.491598, 4.591667, -0.943574, -0.001531, -0.001667, 1496957382.593700, 2.879485, 1.000000, 29.871833, 15.263599, 13.601892, -0.851064 +-29.1336, 7.79294, -28.491423, 4.591667, -0.653626, -0.001531, 0.000000, 1496957382.604300, 2.879240, 1.000000, 29.917750, 15.349051, 13.601892, -0.851064 +-29.1781, 7.80403, -28.491147, 4.588889, -0.896505, -0.001646, -0.002502, 1496957382.613900, 2.879110, 1.000000, 29.963639, 15.349051, 13.636988, -0.914894 +-29.2227, 7.81501, -28.491025, 4.588889, -0.556395, -0.001646, 0.000000, 1496957382.624500, 2.878927, 1.000000, 30.009528, 15.263599, 13.636988, -0.914894 +-29.2673, 7.82608, -28.490714, 4.577778, -0.363202, -0.001761, -0.002508, 1496957382.634000, 2.878724, 1.000000, 30.055306, 15.263599, 13.734646, -0.978723 +-29.312, 7.83697, -28.490495, 4.577778, 0.307642, -0.001761, 0.000000, 1496957382.644600, 2.878639, 1.000000, 30.101083, 15.263599, 13.734646, -0.978723 +-29.3566, 7.84785, -28.490080, 4.561111, 0.206861, -0.001914, -0.003357, 1496957382.654100, 2.878405, 1.000000, 30.146694, 15.263599, 13.713283, -1.063830 +-29.4013, 7.85872, -28.489716, 4.561111, 0.252808, -0.001914, 0.000000, 1496957382.663700, 2.878298, 1.000000, 30.192306, 15.275806, 13.713283, -1.063830 +-29.446, 7.86952, -28.489313, 4.552778, -0.004634, -0.002067, -0.003363, 1496957382.674200, 2.878078, 1.000000, 30.237833, 15.275806, 13.702601, -1.148936 +-29.4906, 7.88024, -28.488744, 4.552778, -0.300536, -0.002067, 0.000000, 1496957382.683700, 2.877824, 1.000000, 30.283361, 15.251392, 13.702601, -1.148936 +-29.5352, 7.89088, -28.488257, 4.547222, -0.446762, -0.002220, -0.003367, 1496957382.694300, 2.877636, 1.000000, 30.328833, 15.251392, 13.785001, -1.234043 +-29.5798, 7.90153, -28.487693, 4.547222, -0.359216, -0.002220, 0.000000, 1496957382.703800, 2.877323, 1.000000, 30.374306, 15.275806, 13.785001, -1.234043 +-29.6243, 7.91208, -28.487230, 4.544445, -0.476918, -0.002373, -0.003369, 1496957382.714300, 2.877124, 1.000000, 30.419750, 15.275806, 13.827725, -1.319149 +-29.6689, 7.92263, -28.486651, 4.544445, -0.367339, -0.002373, 0.000000, 1496957382.723800, 2.876993, 1.000000, 30.465194, 15.263599, 13.827725, -1.319149 +-29.7134, 7.93317, -28.486091, 4.544445, -0.122366, -0.002526, -0.003369, 1496957382.734400, 2.876832, 1.000000, 30.510639, 15.263599, 13.881132, -1.404255 +-29.758, 7.9437, -28.485436, 4.544445, -0.018199, -0.002526, 0.000000, 1496957382.744000, 2.876706, 1.000000, 30.556083, 15.263599, 13.881132, -1.404255 +-29.8026, 7.9543, -28.484766, 4.533333, 0.101596, -0.002641, -0.002533, 1496957382.754500, 2.876549, 1.000000, 30.601417, 15.263599, 14.032197, -1.468085 +-29.8471, 7.96488, -28.484049, 4.533333, 0.070380, -0.002641, 0.000000, 1496957382.764100, 2.876453, 1.000000, 30.646750, 15.288014, 14.032197, -1.468085 +-29.8917, 7.97546, -28.483210, 4.525000, 0.090552, -0.002794, -0.003384, 1496957382.774600, 2.876300, 1.000000, 30.692000, 15.288014, 14.143587, -1.553192 +-29.9362, 7.98605, -28.482375, 4.525000, -0.231684, -0.002794, 0.000000, 1496957382.784300, 2.876139, 1.000000, 30.737250, 15.312428, 14.143587, -1.553192 +-29.9807, 7.99664, -28.481608, 4.522222, -0.304935, -0.002909, -0.002539, 1496957382.793800, 2.875969, 1.000000, 30.782472, 15.312428, 14.224461, -1.617021 +-30.0252, 8.00722, -28.480756, 4.513889, -0.225101, -0.003024, -0.002544, 1496957382.804300, 2.875805, 1.000000, 30.827611, 15.263599, 14.224461, -1.680851 +-30.0696, 8.0178, -28.479986, 4.513889, -0.137668, -0.003024, 0.000000, 1496957382.813800, 2.875615, 1.000000, 30.872750, 15.263599, 14.482338, -1.680851 +-30.1141, 8.02834, -28.479167, 4.513889, -0.203679, -0.003139, -0.002544, 1496957382.824300, 2.875491, 1.000000, 30.917889, 15.239185, 14.482338, -1.744681 +-30.1585, 8.03888, -28.478387, 4.513889, -0.410150, -0.003139, 0.000000, 1496957382.833900, 2.875342, 1.000000, 30.963028, 15.239185, 14.718853, -1.744681 +-30.2028, 8.04935, -28.477558, 4.513889, -0.419600, -0.003139, 0.000000, 1496957382.844400, 2.875224, 1.000000, 31.008167, 15.361258, 14.718853, -1.744681 +-30.2472, 8.05988, -28.476832, 4.508333, -0.127341, -0.003215, -0.001698, 1496957382.854300, 2.875086, 1.000000, 31.053250, 15.361258, 14.944686, -1.787234 +-30.2916, 8.07039, -28.476153, 4.508333, -0.020362, -0.003215, 0.000000, 1496957382.863800, 2.874955, 1.000000, 31.098333, 15.251392, 14.944686, -1.787234 +-30.336, 8.08095, -28.475517, 4.505556, 0.347074, -0.003292, -0.001699, 1496957382.875800, 2.874810, 1.000000, 31.143389, 15.251392, 14.991989, -1.829787 +-30.3804, 8.09158, -28.474899, 4.505556, 0.257589, -0.003407, -0.002549, 1496957382.884300, 2.874688, 1.000000, 31.188444, 15.275806, 14.991989, -1.893617 +-30.4248, 8.10221, -28.474221, 4.505556, -0.273867, -0.003407, 0.000000, 1496957382.893800, 2.874561, 1.000000, 31.233500, 15.275806, 15.020981, -1.893617 +-30.4691, 8.11286, -28.473638, 4.491667, -0.198667, -0.003445, -0.000852, 1496957382.904400, 2.874410, 1.000000, 31.278417, 15.288014, 15.020981, -1.914894 +-30.5134, 8.12356, -28.473082, 4.491667, -0.206253, -0.003445, 0.000000, 1496957382.913900, 2.874255, 1.000000, 31.323333, 15.288014, 15.103380, -1.914894 +-30.5576, 8.13439, -28.472568, 4.491667, -0.172056, -0.003445, 0.000000, 1496957382.924400, 2.874049, 1.000000, 31.368250, 15.202563, 15.103380, -1.914894 +-30.6019, 8.14532, -28.472026, 4.486111, -0.014764, -0.003483, -0.000853, 1496957382.933900, 2.873910, 1.000000, 31.413111, 15.202563, 15.342946, -1.936170 +-30.646, 8.15631, -28.471360, 4.486111, -0.392930, -0.003483, 0.000000, 1496957382.944500, 2.873846, 1.000000, 31.457972, 15.288014, 15.342946, -1.936170 +-30.6901, 8.16737, -28.470641, 4.486111, -0.450173, -0.003598, -0.002560, 1496957382.954000, 2.873761, 1.000000, 31.502833, 15.288014, 15.747311, -2.000000 +-30.7341, 8.17849, -28.469805, 4.486111, -0.423707, -0.003598, 0.000000, 1496957382.964500, 2.873681, 1.000000, 31.547694, 15.263599, 15.747311, -2.000000 +-30.7781, 8.18972, -28.468808, 4.486111, -0.400150, -0.003751, -0.003413, 1496957382.974100, 2.873609, 1.000000, 31.592556, 15.263599, 16.244755, -2.085106 +-30.8219, 8.20087, -28.467597, 4.486111, -0.668409, -0.003751, 0.000000, 1496957382.983500, 2.873553, 1.000000, 31.637417, 15.239185, 16.244755, -2.085106 +-30.8657, 8.21223, -28.466294, 4.486111, -0.630889, -0.003904, -0.003413, 1496957382.996100, 2.873449, 1.000000, 31.682278, 15.239185, 16.922255, -2.170213 +-30.9095, 8.22359, -28.464667, 4.486111, -0.676992, -0.003904, 0.000000, 1496957383.004600, 2.873458, 1.000000, 31.727139, 15.263599, 16.922255, -2.170213 +-30.9531, 8.23499, -28.463170, 4.475000, -0.696958, -0.004096, -0.004277, 1496957383.014200, 2.873416, 1.000000, 31.771889, 15.263599, 17.662317, -2.276596 +-30.9968, 8.24648, -28.461582, 4.475000, -0.299417, -0.004096, 0.000000, 1496957383.023600, 2.873401, 1.000000, 31.816639, 15.251392, 17.662317, -2.276596 +-31.0404, 8.25794, -28.460208, 4.466667, -0.140759, -0.004325, -0.005142, 1496957383.034100, 2.873425, 1.000000, 31.861306, 15.251392, 18.384069, -2.404255 +-31.084, 8.26953, -28.458719, 4.466667, 0.139603, -0.004325, 0.000000, 1496957383.043500, 2.873315, 1.000000, 31.905972, 15.251392, 18.384069, -2.404255 +-31.1277, 8.28106, -28.457378, 4.455555, 0.156217, -0.004555, -0.005155, 1496957383.054000, 2.873320, 1.000000, 31.950528, 15.336843, 18.731976, -2.531915 +-31.1713, 8.29263, -28.455958, 4.455555, 0.008896, -0.004555, 0.000000, 1496957383.063600, 2.873240, 1.000000, 31.995083, 15.226978, 18.731976, -2.531915 +-31.2149, 8.30424, -28.454455, 4.450000, -0.085469, -0.004785, -0.005162, 1496957383.074100, 2.873149, 1.000000, 32.039583, 15.226978, 18.953232, -2.659575 +-31.2583, 8.31605, -28.453049, 4.450000, -0.445528, -0.004785, 0.000000, 1496957383.083600, 2.873909, 1.000000, 32.084083, 15.263599, 18.953232, -2.659575 +-31.3019, 8.3278, -28.451593, 4.450000, -0.495942, -0.005014, -0.005162, 1496957383.094100, 2.873787, 1.000000, 32.128583, 15.263599, 19.035629, -2.787234 +-31.3454, 8.33951, -28.450288, 4.450000, -0.429217, -0.005014, 0.000000, 1496957383.104600, 2.873690, 1.000000, 32.173083, 15.361258, 19.035629, -2.787234 +-31.3888, 8.35126, -28.449087, 4.447222, -0.178561, -0.005282, -0.006026, 1496957383.114000, 2.873564, 1.000000, 32.217556, 15.361258, 19.021896, -2.936170 +-31.4323, 8.36302, -28.447800, 4.447222, -0.011147, -0.005282, 0.000000, 1496957383.124500, 2.873410, 1.000000, 32.262028, 15.190356, 19.021896, -2.936170 +-31.4758, 8.37471, -28.446746, 4.441667, 0.117240, -0.005589, -0.006895, 1496957383.134100, 2.873246, 1.000000, 32.306444, 15.190356, 18.953232, -3.106383 +-31.5194, 8.38639, -28.445613, 4.441667, 0.134837, -0.005589, 0.000000, 1496957383.143500, 2.873041, 1.000000, 32.350861, 15.214770, 18.953232, -3.106383 +-31.5629, 8.39797, -28.444721, 4.433333, 0.014110, -0.005895, -0.006909, 1496957383.154100, 2.872816, 1.000000, 32.395194, 15.214770, 18.878462, -3.276596 +-31.6065, 8.40949, -28.443886, 4.433333, 0.084752, -0.005895, 0.000000, 1496957383.163600, 2.872514, 1.000000, 32.439528, 15.263599, 18.878462, -3.276596 +-31.65, 8.42095, -28.443206, 4.425000, -0.155526, -0.006239, -0.007787, 1496957383.174200, 2.872214, 1.000000, 32.483778, 15.263599, 18.988327, -3.468085 +-31.6935, 8.43232, -28.442606, 4.425000, -0.204426, -0.006239, 0.000000, 1496957383.183800, 2.871867, 1.000000, 32.528028, 15.263599, 18.988327, -3.468085 +-31.7371, 8.44365, -28.442065, 4.425000, -0.215653, -0.006699, -0.010383, 1496957383.194400, 2.871539, 1.000000, 32.572278, 15.263599, 19.142443, -3.723404 +-31.7806, 8.45489, -28.441714, 4.425000, -0.434134, -0.006699, 0.000000, 1496957383.203900, 2.871224, 1.000000, 32.616528, 15.263599, 19.142443, -3.723404 +-31.824, 8.46605, -28.441299, 4.425000, -0.455999, -0.007158, -0.010384, 1496957383.214500, 2.870821, 1.000000, 32.660778, 15.263599, 19.392691, -3.978723 +-31.8675, 8.47715, -28.441050, 4.425000, -0.310209, -0.007158, 0.000000, 1496957383.224100, 2.870471, 1.000000, 32.705028, 15.239185, 19.392691, -3.978723 +-31.9109, 8.48821, -28.440772, 4.430555, -0.173812, -0.007618, -0.010371, 1496957383.233600, 2.870057, 1.000000, 32.749333, 15.239185, 19.725338, -4.234043 +-31.9544, 8.49925, -28.440557, 4.430555, -0.122553, -0.007618, 0.000000, 1496957383.244300, 2.869647, 1.000000, 32.793639, 15.263599, 19.725338, -4.234043 +-31.9978, 8.51021, -28.440379, 4.430555, -0.305108, -0.008154, -0.012100, 1496957383.253900, 2.869283, 1.000000, 32.837944, 15.263599, 20.004578, -4.531915 +-32.0412, 8.52113, -28.440197, 4.430555, -0.194178, -0.008154, 0.000000, 1496957383.264400, 2.868856, 1.000000, 32.882250, 15.361258, 20.004578, -4.531915 +-32.0846, 8.53205, -28.440081, 4.430555, -0.145956, -0.008614, -0.010373, 1496957383.273900, 2.868390, 1.000000, 32.926556, 15.361258, 20.163271, -4.787234 +-32.128, 8.54299, -28.439954, 4.430555, -0.108971, -0.008614, 0.000000, 1496957383.283600, 2.867993, 1.000000, 32.970861, 15.263599, 20.163271, -4.787234 +-32.1714, 8.55393, -28.439827, 4.427778, -0.237174, -0.009226, -0.013840, 1496957383.294200, 2.867564, 1.000000, 33.015139, 15.263599, 20.231937, -5.127660 +-32.2147, 8.56487, -28.439683, 4.427778, -0.277911, -0.009226, 0.000000, 1496957383.303700, 2.867091, 1.000000, 33.059417, 15.288014, 20.231937, -5.127660 +-32.258, 8.57581, -28.439563, 4.427778, -0.272694, -0.009801, -0.012976, 1496957383.314300, 2.866706, 1.000000, 33.103694, 15.288014, 20.228886, -5.446808 +-32.3012, 8.58674, -28.439440, 4.427778, -0.336309, -0.009801, 0.000000, 1496957383.323900, 2.866255, 1.000000, 33.147972, 15.251392, 20.228886, -5.446808 +-32.3444, 8.5977, -28.439328, 4.422222, -0.367489, -0.010414, -0.013860, 1496957383.334500, 2.865740, 1.000000, 33.192194, 15.251392, 20.251774, -5.787234 +-32.3876, 8.60864, -28.439222, 4.422222, -0.454576, -0.010414, 0.000000, 1496957383.344200, 2.865255, 1.000000, 33.236417, 15.263599, 20.251774, -5.787234 +-32.4307, 8.6196, -28.439235, 4.416667, -0.387583, -0.011065, -0.014746, 1496957383.353700, 2.864777, 1.000000, 33.280583, 15.263599, 20.259403, -6.148936 +-32.4738, 8.63055, -28.439254, 4.416667, -0.189165, -0.011065, 0.000000, 1496957383.364400, 2.864247, 1.000000, 33.324750, 15.312428, 20.259403, -6.148936 +-32.517, 8.64149, -28.439382, 4.413889, -0.022373, -0.011793, -0.016493, 1496957383.374000, 2.863701, 1.000000, 33.368889, 15.312428, 20.222782, -6.553192 +-32.5601, 8.65241, -28.439650, 4.413889, -0.052349, -0.011793, 0.000000, 1496957383.383500, 2.863152, 1.000000, 33.413028, 15.226978, 20.222782, -6.553192 +-32.6032, 8.66327, -28.439908, 4.411111, -0.018254, -0.012521, -0.016506, 1496957383.394000, 2.862545, 1.000000, 33.457139, 15.226978, 20.177004, -6.957447 +-32.6463, 8.67408, -28.440196, 4.411111, -0.102542, -0.012521, 0.000000, 1496957383.404800, 2.861928, 1.000000, 33.501250, 15.336843, 20.177004, -6.957447 +-32.6894, 8.68484, -28.440368, 4.402778, -0.354429, -0.013326, -0.018281, 1496957383.414300, 2.861232, 1.000000, 33.545278, 15.336843, 20.221256, -7.404255 +-32.7324, 8.69554, -28.440436, 4.402778, -0.590446, -0.013326, 0.000000, 1496957383.423800, 2.860520, 1.000000, 33.589306, 15.312428, 20.221256, -7.404255 +-32.7754, 8.70627, -28.440651, 4.400000, -0.490011, -0.014169, -0.019167, 1496957383.434300, 2.859804, 1.000000, 33.633306, 15.312428, 20.216679, -7.872340 +-32.8184, 8.71692, -28.440718, 4.400000, -0.481735, -0.014169, 0.000000, 1496957383.443900, 2.859058, 1.000000, 33.677306, 15.239185, 20.216679, -7.872340 +-32.8613, 8.7277, -28.440984, 4.394444, -0.305091, -0.015013, -0.019195, 1496957383.454500, 2.858348, 1.000000, 33.721250, 15.239185, 20.251774, -8.340425 +-32.9041, 8.73839, -28.441031, 4.394444, -0.378229, -0.015013, 0.000000, 1496957383.464100, 2.857606, 1.000000, 33.765194, 15.214770, 20.251774, -8.340425 +-32.9469, 8.74915, -28.441339, 4.386111, -0.426297, -0.015933, -0.020984, 1496957383.474600, 2.856870, 1.000000, 33.809056, 15.214770, 20.314337, -8.851064 +-32.9897, 8.75999, -28.441445, 4.386111, -0.345613, -0.015933, 0.000000, 1496957383.484200, 2.856135, 1.000000, 33.852917, 15.312428, 20.314337, -8.851064 +-33.0324, 8.77085, -28.441739, 4.380556, -0.361501, -0.016892, -0.021891, 1496957383.493800, 2.855367, 1.000000, 33.896722, 15.312428, 20.419622, -9.382978 +-33.075, 8.7818, -28.442186, 4.380556, -0.239168, -0.016892, 0.000000, 1496957383.504400, 2.854597, 1.000000, 33.940528, 15.214770, 20.419622, -9.382978 +-33.1177, 8.79284, -28.442514, 4.375000, -0.038516, -0.017890, -0.022802, 1496957383.513900, 2.853863, 1.000000, 33.984278, 15.214770, 20.363165, -9.936171 +-33.1603, 8.80391, -28.443078, 4.375000, -0.278214, -0.017890, 0.000000, 1496957383.524500, 2.853085, 1.000000, 34.028028, 15.263599, 20.363165, -9.936171 +-33.2028, 8.81512, -28.443359, 4.366667, -0.253709, -0.018888, -0.022852, 1496957383.534000, 2.852290, 1.000000, 34.071694, 15.263599, 20.315863, -10.489362 +-33.2453, 8.82635, -28.443609, 4.366667, -0.345476, -0.018888, 0.000000, 1496957383.544500, 2.851622, 1.000000, 34.115361, 15.226978, 20.315863, -10.489362 +-33.2877, 8.83765, -28.443901, 4.361111, -0.593251, -0.019963, -0.024649, 1496957383.554100, 2.850830, 1.000000, 34.158972, 15.226978, 20.340277, -11.085107 +-33.33, 8.84902, -28.444002, 4.361111, -0.456412, -0.019963, 0.000000, 1496957383.563500, 2.850016, 1.000000, 34.202583, 15.312428, 20.340277, -11.085107 +-33.3723, 8.86032, -28.444185, 4.355556, -0.637558, -0.021000, -0.023807, 1496957383.574000, 2.849239, 1.000000, 34.246139, 15.312428, 20.285343, -11.659575 +-33.4145, 8.87174, -28.444221, 4.355556, -0.444484, -0.021000, 0.000000, 1496957383.584700, 2.848350, 1.000000, 34.289694, 15.153734, 20.285343, -11.659575 +-33.4566, 8.88317, -28.444183, 4.347222, -0.457594, -0.022037, -0.023861, 1496957383.594200, 2.847476, 1.000000, 34.333167, 15.153734, 20.361639, -12.234042 +-33.4988, 8.89461, -28.444067, 4.347222, -0.406956, -0.022037, 0.000000, 1496957383.603700, 2.846626, 1.000000, 34.376639, 15.239185, 20.361639, -12.234042 +-33.5408, 8.90606, -28.443819, 4.338889, -0.393681, -0.023075, -0.023916, 1496957383.614200, 2.845670, 1.000000, 34.420028, 15.239185, 20.321966, -12.808511 +-33.5829, 8.91752, -28.443562, 4.338889, -0.454315, -0.023075, 0.000000, 1496957383.623700, 2.844746, 1.000000, 34.463417, 15.275806, 20.321966, -12.808511 +-33.6248, 8.92896, -28.443133, 4.327778, -0.519923, -0.024151, -0.024875, 1496957383.634300, 2.843701, 1.000000, 34.506694, 15.275806, 20.332647, -13.404255 +-33.6668, 8.94046, -28.442766, 4.327778, -0.434369, -0.024151, 0.000000, 1496957383.643900, 2.842673, 1.000000, 34.549972, 15.226978, 20.332647, -13.404255 +-33.7086, 8.95193, -28.442241, 4.319445, -0.556070, -0.025228, -0.024934, 1496957383.654400, 2.841616, 1.000000, 34.593167, 15.226978, 20.323492, -14.000000 +-33.7504, 8.96339, -28.441666, 4.319445, -0.608225, -0.025228, 0.000000, 1496957383.664100, 2.840589, 1.000000, 34.636361, 15.190356, 20.323492, -14.000000 +-33.7922, 8.97487, -28.441046, 4.305555, -0.605274, -0.026306, -0.025025, 1496957383.673600, 2.839549, 1.000000, 34.679417, 15.190356, 20.291447, -14.595745 +-33.8338, 8.98633, -28.440358, 4.305555, -0.674474, -0.026306, 0.000000, 1496957383.684200, 2.838422, 1.000000, 34.722472, 15.336843, 20.291447, -14.595745 +-33.8754, 8.99782, -28.439648, 4.297222, -0.534004, -0.027422, -0.025981, 1496957383.693800, 2.837297, 1.000000, 34.765444, 15.336843, 20.334173, -15.212766 +-33.917, 9.00931, -28.438936, 4.297222, -0.444840, -0.027422, 0.000000, 1496957383.704300, 2.836109, 1.000000, 34.808417, 15.226978, 20.334173, -15.212766 +-33.9585, 9.02085, -28.438188, 4.288889, -0.430304, -0.028578, -0.026943, 1496957383.713800, 2.834924, 1.000000, 34.851306, 15.226978, 20.297550, -15.851064 +-34, 9.03245, -28.437436, 4.288889, -0.364997, -0.028578, 0.000000, 1496957383.724300, 2.833673, 1.000000, 34.894194, 15.361258, 20.297550, -15.851064 +-34.0414, 9.04409, -28.436662, 4.280556, -0.378741, -0.029695, -0.026109, 1496957383.733900, 2.832446, 1.000000, 34.937000, 15.361258, 20.282291, -16.468084 +-34.0828, 9.05579, -28.435981, 4.280556, -0.366999, -0.029695, 0.000000, 1496957383.744300, 2.831206, 1.000000, 34.979806, 15.361258, 20.282291, -16.468084 +-34.1241, 9.06756, -28.435224, 4.272222, -0.293454, -0.030813, -0.026174, 1496957383.753900, 2.829941, 1.000000, 35.022528, 15.275806, 20.247196, -17.085106 +-34.1653, 9.0794, -28.434574, 4.272222, -0.315112, -0.030813, 0.000000, 1496957383.764300, 2.828678, 1.000000, 35.065250, 15.324636, 20.247196, -17.085106 +-34.2065, 9.09128, -28.433996, 4.266667, -0.248849, -0.032010, -0.028032, 1496957383.773800, 2.827347, 1.000000, 35.107917, 15.324636, 20.184633, -17.744680 +-34.2477, 9.10319, -28.433413, 4.266667, -0.267508, -0.032010, 0.000000, 1496957383.784900, 2.825961, 1.000000, 35.150583, 15.373465, 20.184633, -17.744680 +-34.2888, 9.11512, -28.432850, 4.261111, -0.326962, -0.033245, -0.028992, 1496957383.794500, 2.824568, 1.000000, 35.193194, 15.373465, 20.212101, -18.425531 +-34.3299, 9.12705, -28.432260, 4.261111, -0.450236, -0.033245, 0.000000, 1496957383.804100, 2.823131, 1.000000, 35.235806, 15.202563, 20.212101, -18.425531 +-34.3709, 9.13902, -28.431565, 4.250000, -0.567339, -0.034520, -0.029996, 1496957383.813600, 2.821686, 1.000000, 35.278306, 15.202563, 20.205997, -19.127659 +-34.4118, 9.15102, -28.430831, 4.250000, -0.570873, -0.034520, 0.000000, 1496957383.824100, 2.820221, 1.000000, 35.320806, 15.178149, 20.205997, -19.127659 +-34.4527, 9.16296, -28.430107, 4.244444, -0.603990, -0.035834, -0.030968, 1496957383.833600, 2.818727, 1.000000, 35.363250, 15.178149, 20.224308, -19.851065 +-34.4935, 9.17497, -28.429417, 4.244444, -0.472592, -0.035834, 0.000000, 1496957383.844200, 2.817224, 1.000000, 35.405694, 15.239185, 20.224308, -19.851065 +-34.5343, 9.18695, -28.428547, 4.241667, -0.328616, -0.037188, -0.031924, 1496957383.853700, 2.815666, 1.000000, 35.448111, 15.239185, 20.260929, -20.595745 +-34.575, 9.19893, -28.427717, 4.241667, -0.530544, -0.037188, 0.000000, 1496957383.864300, 2.814095, 1.000000, 35.490528, 15.300221, 20.260929, -20.595745 +-34.6157, 9.21088, -28.426870, 4.236111, -0.631578, -0.038621, -0.033821, 1496957383.873800, 2.812466, 1.000000, 35.532889, 15.300221, 20.361639, -21.382978 +-34.6563, 9.22287, -28.426006, 4.236111, -0.628330, -0.038621, 0.000000, 1496957383.884400, 2.810857, 1.000000, 35.575250, 15.361258, 20.361639, -21.382978 +-34.6968, 9.23484, -28.425183, 4.222222, -0.684905, -0.040094, -0.034881, 1496957383.893900, 2.809206, 1.000000, 35.617472, 15.361258, 20.375372, -22.191490 +-34.7372, 9.24685, -28.424260, 4.222222, -0.661060, -0.040094, 0.000000, 1496957383.904600, 2.807587, 1.000000, 35.659694, 15.263599, 20.375372, -22.191490 +-34.7776, 9.25889, -28.423489, 4.213889, -0.665116, -0.041645, -0.036825, 1496957383.914100, 2.805915, 1.000000, 35.701833, 15.263599, 20.355536, -23.042553 +-34.8179, 9.27096, -28.422539, 4.213889, -0.618827, -0.041645, 0.000000, 1496957383.923500, 2.804227, 1.000000, 35.743972, 15.239185, 20.355536, -23.042553 +-34.8581, 9.28309, -28.421804, 4.208333, -0.672976, -0.043199, -0.036912, 1496957383.934000, 2.802514, 1.000000, 35.786056, 15.239185, 20.396734, -23.893618 +-34.8982, 9.29531, -28.421064, 4.208333, -0.580232, -0.043199, 0.000000, 1496957383.944500, 2.800726, 1.000000, 35.828139, 15.434501, 20.396734, -23.893618 +-34.9382, 9.30763, -28.420349, 4.197222, -0.594147, -0.044832, -0.038903, 1496957383.954100, 2.798930, 1.000000, 35.870111, 15.434501, 20.320440, -24.787233 +-34.9781, 9.32001, -28.419808, 4.197222, -0.553294, -0.044832, 0.000000, 1496957383.963600, 2.797121, 1.000000, 35.912083, 15.214770, 20.320440, -24.787233 +-35.0179, 9.33247, -28.419265, 4.186111, -0.583909, -0.046466, -0.039052, 1496957383.974200, 2.795262, 1.000000, 35.953944, 15.214770, 20.181581, -25.680851 +-35.0577, 9.34502, -28.418834, 4.186111, -0.471552, -0.046466, 0.000000, 1496957383.983700, 2.793388, 1.000000, 35.995806, 15.263599, 20.181581, -25.680851 +-35.0973, 9.35763, -28.418377, 4.183333, -0.474232, -0.048142, -0.040057, 1496957383.994300, 2.791520, 1.000000, 36.037639, 15.263599, 20.163271, -26.595745 +-35.0973, 9.35763, -28.418377, 4.183333, -0.474232, -0.048142, 0.000000, 1496957384.003700, 2.791520, 1.000000, 36.079472, 15.214770, 20.163271, -26.595745 +-35.1764, 9.38294, -28.417493, 4.180555, -0.665156, -0.049898, -0.042004, 1496957384.014200, 2.787561, 1.000000, 36.121278, 15.214770, 20.102236, -27.553192 +-35.2158, 9.39562, -28.417124, 4.180555, -0.569347, -0.049898, 0.000000, 1496957384.023700, 2.785512, 1.000000, 36.163083, 15.263599, 20.102236, -27.553192 +-35.2552, 9.40833, -28.416709, 4.177778, -0.523898, -0.051657, -0.042090, 1496957384.034300, 2.783464, 1.000000, 36.204861, 15.263599, 19.853514, -28.510639 +-35.2945, 9.42106, -28.416383, 4.177778, -0.515351, -0.051657, 0.000000, 1496957384.043900, 2.781349, 1.000000, 36.246639, 15.251392, 19.853514, -28.510639 +-35.3338, 9.43374, -28.416099, 4.172222, -0.509061, -0.053418, -0.042207, 1496957384.054500, 2.779143, 1.000000, 36.288361, 15.251392, 19.638361, -29.468084 +-35.373, 9.44647, -28.415867, 4.172222, -0.515486, -0.053418, 0.000000, 1496957384.064100, 2.776914, 1.000000, 36.330083, 15.190356, 19.638361, -29.468084 +-35.4122, 9.45924, -28.415622, 4.166667, -0.425005, -0.055181, -0.042327, 1496957384.073700, 2.774655, 1.000000, 36.371750, 15.190356, 19.230946, -30.425531 +-35.451, 9.47356, -28.415285, 4.166667, -0.446716, -0.055181, 0.000000, 1496957384.084300, 2.775967, 1.000000, 36.413417, 15.263599, 19.230946, -30.425531 +-35.4898, 9.48766, -28.415021, 4.158333, -0.482011, -0.056908, -0.041532, 1496957384.093900, 2.773600, 1.000000, 36.455000, 15.263599, 18.538185, -31.361702 +-35.5285, 9.50178, -28.414773, 4.158333, -0.566545, -0.056908, 0.000000, 1496957384.104300, 2.771207, 1.000000, 36.496583, 15.263599, 18.538185, -31.361702 +-35.5672, 9.51598, -28.414529, 4.147222, -0.509140, -0.058599, -0.040760, 1496957384.113900, 2.768770, 1.000000, 36.538056, 15.263599, 17.712673, -32.276596 +-35.6057, 9.53022, -28.414283, 4.147222, -0.510822, -0.058599, 0.000000, 1496957384.124400, 2.766317, 1.000000, 36.579528, 15.312428, 17.712673, -32.276596 +-35.6442, 9.54452, -28.414050, 4.136111, -0.570199, -0.060252, -0.039981, 1496957384.134000, 2.763774, 1.000000, 36.620889, 15.312428, 16.713207, -33.170212 +-35.6827, 9.5589, -28.413824, 4.136111, -0.490513, -0.060252, 0.000000, 1496957384.144500, 2.761227, 1.000000, 36.662250, 15.373465, 16.713207, -33.170212 +-35.721, 9.57334, -28.413579, 4.127778, -0.542596, -0.061830, -0.038213, 1496957384.154000, 2.758682, 1.000000, 36.703528, 15.373465, 15.652704, -34.021278 +-35.7592, 9.58783, -28.413340, 4.127778, -0.571071, -0.061830, 0.000000, 1496957384.164400, 2.756099, 1.000000, 36.744806, 15.178149, 15.652704, -34.021278 +-35.7974, 9.60236, -28.413060, 4.116667, -0.662530, -0.063330, -0.036454, 1496957384.173900, 2.753373, 1.000000, 36.785972, 15.178149, 14.695964, -34.829788 +-35.8355, 9.61695, -28.412733, 4.116667, -0.605947, -0.063330, 0.000000, 1496957384.184400, 2.750698, 1.000000, 36.827139, 15.251392, 14.695964, -34.829788 +-35.8734, 9.63164, -28.412383, 4.108333, -0.619393, -0.064833, -0.036583, 1496957384.194000, 2.748007, 1.000000, 36.868222, 15.251392, 13.794156, -35.638298 +-35.9113, 9.64639, -28.412037, 4.108333, -0.593989, -0.064833, 0.000000, 1496957384.204500, 2.745284, 1.000000, 36.909306, 15.251392, 13.794156, -35.638298 +-35.9491, 9.66117, -28.411690, 4.102778, -0.553834, -0.066259, -0.034756, 1496957384.213900, 2.742491, 1.000000, 36.950333, 15.263599, 13.752956, -36.404255 +-35.9869, 9.67604, -28.411315, 4.102778, -0.369492, -0.066259, 0.000000, 1496957384.224500, 2.739670, 1.000000, 36.991361, 15.263599, 13.752956, -36.404255 +-36.0245, 9.69097, -28.410992, 4.097222, -0.360449, -0.067648, -0.033886, 1496957384.234100, 2.736841, 1.000000, 37.032333, 15.300221, 13.731594, -37.148937 +-36.0621, 9.70599, -28.410725, 4.097222, -0.425972, -0.067648, 0.000000, 1496957384.243600, 2.734065, 1.000000, 37.073306, 15.300221, 13.731594, -37.148937 +-36.0997, 9.72107, -28.410468, 4.091667, -0.354616, -0.068998, -0.033011, 1496957384.254100, 2.731150, 1.000000, 37.114222, 15.263599, 13.661403, -37.872341 +-36.1371, 9.7362, -28.410340, 4.091667, -0.338242, -0.068998, 0.000000, 1496957384.263500, 2.728281, 1.000000, 37.155139, 15.263599, 13.661403, -37.872341 +-36.1745, 9.75141, -28.410230, 4.086111, -0.281356, -0.070311, -0.032129, 1496957384.274100, 2.725339, 1.000000, 37.196000, 15.263599, 13.667506, -38.574467 +-36.2119, 9.76671, -28.410191, 4.086111, -0.191928, -0.070311, 0.000000, 1496957384.284100, 2.722368, 1.000000, 37.236861, 15.263599, 13.667506, -38.574467 +-36.2492, 9.7821, -28.410130, 4.083333, -0.278327, -0.071586, -0.031221, 1496957384.293600, 2.719341, 1.000000, 37.277694, 15.410087, 13.662929, -39.255318 +-36.2863, 9.79757, -28.410047, 4.083333, -0.419789, -0.071586, 0.000000, 1496957384.304200, 2.716329, 1.000000, 37.318528, 15.410087, 13.662929, -39.255318 +-36.3234, 9.81312, -28.409916, 4.080555, -0.530727, -0.072863, -0.031287, 1496957384.313800, 2.713322, 1.000000, 37.359333, 15.153734, 13.664454, -39.936169 +-36.3604, 9.82877, -28.409757, 4.080555, -0.456317, -0.072863, 0.000000, 1496957384.324300, 2.710235, 1.000000, 37.400139, 15.153734, 13.664454, -39.936169 +-36.3974, 9.84447, -28.409565, 4.077778, -0.410857, -0.074061, -0.029393, 1496957384.333800, 2.707200, 1.000000, 37.440917, 15.141527, 13.713283, -40.574467 +-36.4342, 9.86025, -28.409391, 4.077778, -0.341348, -0.074061, 0.000000, 1496957384.344300, 2.704044, 1.000000, 37.481694, 15.141527, 13.713283, -40.574467 +-36.471, 9.87612, -28.409232, 4.072222, -0.309981, -0.075302, -0.030457, 1496957384.353900, 2.700891, 1.000000, 37.522417, 15.312428, 13.688869, -41.234043 +-36.5077, 9.89205, -28.409073, 4.072222, -0.369648, -0.075302, 0.000000, 1496957384.364500, 2.697756, 1.000000, 37.563139, 15.312428, 13.688869, -41.234043 +-36.5444, 9.90807, -28.408953, 4.066667, -0.303248, -0.076423, -0.027585, 1496957384.374000, 2.694581, 1.000000, 37.603806, 15.239185, 13.682765, -41.829788 +-36.5809, 9.92413, -28.408863, 4.066667, -0.396637, -0.076423, 0.000000, 1496957384.384500, 2.691368, 1.000000, 37.644472, 15.239185, 13.682765, -41.829788 +-36.6174, 9.94026, -28.408829, 4.063889, -0.356848, -0.077507, -0.026653, 1496957384.394100, 2.688163, 1.000000, 37.685111, 15.263599, 13.667506, -42.404255 +-36.6539, 9.95643, -28.408782, 4.063889, -0.451715, -0.077507, 0.000000, 1496957384.404500, 2.684922, 1.000000, 37.725750, 15.263599, 13.667506, -42.404255 +-36.6902, 9.97267, -28.408813, 4.055555, -0.482053, -0.078551, -0.025751, 1496957384.414500, 2.681662, 1.000000, 37.766306, 15.214770, 13.647669, -42.957447 +-36.7264, 9.98899, -28.408808, 4.055555, -0.505485, -0.078551, 0.000000, 1496957384.423900, 2.678398, 1.000000, 37.806861, 15.214770, 13.647669, -42.957447 +-36.7626, 10.0054, -28.408882, 4.047222, -0.496507, -0.079476, -0.022854, 1496957384.434500, 2.675115, 1.000000, 37.847333, 15.288014, 13.641565, -43.446808 +-36.7986, 10.0219, -28.408929, 4.047222, -0.454277, -0.079476, 0.000000, 1496957384.444100, 2.671843, 1.000000, 37.887806, 15.288014, 13.641565, -43.446808 +-36.8346, 10.0385, -28.408861, 4.041667, -0.406602, -0.080402, -0.022912, 1496957384.453500, 2.668532, 1.000000, 37.928222, 15.239185, 13.694972, -43.936169 +-36.8705, 10.0551, -28.408786, 4.041667, -0.445877, -0.080402, 0.000000, 1496957384.464200, 2.665192, 1.000000, 37.968639, 15.239185, 13.694972, -43.936169 +-36.9062, 10.0719, -28.408593, 4.038889, -0.531576, -0.081289, -0.021955, 1496957384.473700, 2.661869, 1.000000, 38.009028, 15.239185, 13.676661, -44.404255 +-36.9419, 10.0887, -28.408410, 4.038889, -0.597792, -0.081289, 0.000000, 1496957384.484200, 2.658490, 1.000000, 38.049417, 15.239185, 13.676661, -44.404255 +-36.9774, 10.1056, -28.408201, 4.033333, -0.628377, -0.082136, -0.021009, 1496957384.493700, 2.655110, 1.000000, 38.089750, 15.263599, 13.704127, -44.851063 +-37.0128, 10.1227, -28.407820, 4.033333, -0.512731, -0.082136, 0.000000, 1496957384.504200, 2.651754, 1.000000, 38.130083, 15.263599, 13.704127, -44.851063 +-37.0833, 10.1571, -28.407114, 4.025000, -0.596084, -0.083025, -0.022079, 1496957384.513700, 2.644923, 1.000000, 38.170333, 15.300221, 13.653772, -45.319149 +-37.0833, 10.1571, -28.407114, 4.025000, -0.596084, -0.083025, 0.000000, 1496957384.524200, 2.644923, 1.000000, 38.210583, 15.300221, 13.653772, -45.319149 +-37.1183, 10.1745, -28.406526, 4.019444, -0.483225, -0.083955, -0.023142, 1496957384.533800, 2.641483, 1.000000, 38.250778, 15.190356, 13.669032, -45.808510 +-37.1532, 10.1921, -28.405924, 4.019444, -0.676606, -0.083955, 0.000000, 1496957384.544200, 2.638083, 1.000000, 38.290972, 15.190356, 13.669032, -45.808510 +-37.1879, 10.2097, -28.405060, 4.008333, -0.797825, -0.084927, -0.024244, 1496957384.553700, 2.634656, 1.000000, 38.331056, 15.239185, 13.678187, -46.319149 +-37.2225, 10.2274, -28.404153, 4.008333, -0.782844, -0.084927, 0.000000, 1496957384.564200, 2.631218, 1.000000, 38.371139, 15.239185, 13.678187, -46.319149 +-37.2569, 10.2453, -28.403197, 3.994444, -0.768835, -0.085859, -0.023344, 1496957384.573800, 2.627809, 1.000000, 38.411083, 15.275806, 13.699550, -46.808510 +-37.2912, 10.2633, -28.402101, 3.994444, -0.674832, -0.085859, 0.000000, 1496957384.584300, 2.624394, 1.000000, 38.451028, 15.275806, 13.699550, -46.808510 +-37.3254, 10.2813, -28.400970, 3.980556, -0.463644, -0.086793, -0.023454, 1496957384.593900, 2.620915, 1.000000, 38.490833, 15.495537, 13.658351, -47.297871 +-37.3596, 10.2995, -28.399761, 3.980556, -0.464706, -0.086793, 0.000000, 1496957384.604400, 2.617469, 1.000000, 38.530639, 15.495537, 13.658351, -47.297871 +-37.3936, 10.3177, -28.398427, 3.969445, -0.362313, -0.087727, -0.023549, 1496957384.614000, 2.613980, 1.000000, 38.570333, 15.678645, 13.672084, -47.787235 +-37.4275, 10.336, -28.397126, 3.969445, -0.608021, -0.087727, 0.000000, 1496957384.624500, 2.610520, 1.000000, 38.610028, 15.678645, 13.672084, -47.787235 +-37.4613, 10.3544, -28.395713, 3.955555, -0.595747, -0.088623, -0.022632, 1496957384.634100, 2.607023, 1.000000, 38.649583, 15.812924, 13.650721, -48.255318 +-37.4949, 10.3729, -28.394184, 3.955555, -0.680680, -0.088623, 0.000000, 1496957384.643600, 2.603540, 1.000000, 38.689139, 15.812924, 13.650721, -48.255318 +-37.5284, 10.3914, -28.392659, 3.941667, -0.722087, -0.089560, -0.023774, 1496957384.654200, 2.600022, 1.000000, 38.728556, 16.044861, 13.699550, -48.744682 +-37.5617, 10.4101, -28.390983, 3.941667, -0.728440, -0.089560, 0.000000, 1496957384.663600, 2.596485, 1.000000, 38.767972, 16.044861, 13.699550, -48.744682 +-37.595, 10.4288, -28.389407, 3.925000, -0.722029, -0.090498, -0.023905, 1496957384.674100, 2.592930, 1.000000, 38.807222, 16.142519, 13.662929, -49.234043 +-37.6281, 10.4477, -28.387647, 3.925000, -0.603544, -0.090498, 0.000000, 1496957384.684500, 2.589369, 1.000000, 38.846472, 16.142519, 13.662929, -49.234043 +-37.661, 10.4667, -28.385959, 3.908333, -0.611135, -0.091478, -0.025084, 1496957384.694000, 2.585795, 1.000000, 38.885556, 16.301212, 13.679713, -49.744682 +-37.6939, 10.4857, -28.384215, 3.908333, -0.561435, -0.091478, 0.000000, 1496957384.704600, 2.582199, 1.000000, 38.924639, 16.301212, 13.679713, -49.744682 +-37.7266, 10.5049, -28.382453, 3.894444, -0.415568, -0.092501, -0.026259, 1496957384.714100, 2.578603, 1.000000, 38.963583, 16.630808, 13.658351, -50.276596 +-37.7592, 10.5242, -28.380758, 3.894444, -0.527976, -0.092501, 0.000000, 1496957384.723600, 2.575021, 1.000000, 39.002528, 16.630808, 13.658351, -50.276596 +-37.7916, 10.5436, -28.378921, 3.886111, -0.560586, -0.093525, -0.026353, 1496957384.734300, 2.571377, 1.000000, 39.041389, 16.887159, 13.682765, -50.808510 +-37.8239, 10.5631, -28.377115, 3.886111, -0.616021, -0.093525, 0.000000, 1496957384.743800, 2.567668, 1.000000, 39.080250, 16.887159, 13.682765, -50.808510 +-37.8561, 10.5826, -28.375268, 3.877778, -0.688784, -0.094510, -0.025390, 1496957384.754200, 2.563974, 1.000000, 39.119028, 17.180132, 13.685817, -51.319149 +-37.8882, 10.6021, -28.373344, 3.877778, -0.679022, -0.094510, 0.000000, 1496957384.763800, 2.560236, 1.000000, 39.157806, 17.180132, 13.685817, -51.319149 +-37.9202, 10.6218, -28.371458, 3.863889, -0.628029, -0.095537, -0.026581, 1496957384.774500, 2.556466, 1.000000, 39.196444, 17.753872, 13.698024, -51.851063 +-37.9521, 10.6415, -28.369506, 3.863889, -0.535668, -0.095537, 0.000000, 1496957384.784300, 2.552648, 1.000000, 39.235083, 17.753872, 13.698024, -51.851063 +-37.9839, 10.6612, -28.367550, 3.855556, -0.474058, -0.096524, -0.025610, 1496957384.794000, 2.548864, 1.000000, 39.273639, 18.156710, 13.621729, -52.361702 +-38.0156, 10.681, -28.365553, 3.855556, -0.474442, -0.096524, 0.000000, 1496957384.804600, 2.545040, 1.000000, 39.312194, 18.156710, 13.621729, -52.361702 +-38.0472, 10.7009, -28.363631, 3.844445, -0.312753, -0.097513, -0.025721, 1496957384.814100, 2.541180, 1.000000, 39.350639, 18.474098, 13.644617, -52.872341 +-38.0787, 10.7209, -28.361724, 3.844445, -0.340342, -0.097513, 0.000000, 1496957384.823600, 2.537230, 1.000000, 39.389083, 18.474098, 13.644617, -52.872341 +-38.1101, 10.741, -28.359881, 3.825000, -0.569225, -0.098462, -0.024810, 1496957384.834200, 2.533405, 1.000000, 39.427333, 19.049362, 13.644617, -53.361702 +-38.1414, 10.761, -28.358124, 3.825000, -0.705425, -0.098462, 0.000000, 1496957384.843700, 2.529551, 1.000000, 39.465583, 19.049362, 13.644617, -53.361702 +-38.1725, 10.7812, -28.356407, 3.808333, -0.679548, -0.099412, -0.024953, 1496957384.854300, 2.525675, 1.000000, 39.503667, 19.794003, 13.699550, -53.851063 +-38.2035, 10.8015, -28.354789, 3.808333, -0.363928, -0.099412, 0.000000, 1496957384.863900, 2.521729, 1.000000, 39.541750, 19.794003, 13.699550, -53.851063 +-38.2344, 10.8219, -28.353274, 3.805556, -0.291625, -0.100405, -0.026095, 1496957384.874500, 2.517889, 1.000000, 39.579806, 20.526436, 13.638514, -54.361702 +-38.2652, 10.8424, -28.351732, 3.805556, -0.322288, -0.100405, 0.000000, 1496957384.883500, 2.513974, 1.000000, 39.617861, 20.526436, 13.638514, -54.361702 +-38.2958, 10.8631, -28.350228, 3.805556, -0.422270, -0.101317, -0.023955, 1496957384.894000, 2.510062, 1.000000, 39.655917, 21.393148, 13.678187, -54.829788 +-38.3263, 10.8838, -28.348737, 3.805556, -0.513704, -0.101317, 0.000000, 1496957384.905500, 2.506170, 1.000000, 39.693972, 21.393148, 13.678187, -54.829788 +-38.3567, 10.9046, -28.347289, 3.800000, -0.531921, -0.102147, -0.021838, 1496957384.913900, 2.502287, 1.000000, 39.731972, 22.066072, 13.662929, -55.255318 +-38.3869, 10.9255, -28.345766, 3.800000, -0.547369, -0.102147, 0.000000, 1496957384.924400, 2.498389, 1.000000, 39.769972, 22.066072, 13.662929, -55.255318 +-38.417, 10.9465, -28.344315, 3.788889, -0.524955, -0.103019, -0.023027, 1496957384.934000, 2.494495, 1.000000, 39.807861, 22.835127, 13.728542, -55.702129 +-38.447, 10.9676, -28.342794, 3.788889, -0.608917, -0.103019, 0.000000, 1496957384.944600, 2.490590, 1.000000, 39.845750, 22.835127, 13.728542, -55.702129 +-38.4768, 10.9888, -28.341316, 3.786111, -0.393044, -0.103893, -0.023075, 1496957384.954100, 2.486666, 1.000000, 39.883611, 23.286793, 13.669032, -56.148937 +-38.5065, 11.01, -28.339782, 3.786111, -0.401357, -0.103893, 0.000000, 1496957384.963600, 2.482772, 1.000000, 39.921472, 23.286793, 13.669032, -56.148937 +-38.5361, 11.0313, -28.338301, 3.780555, -0.474621, -0.104726, -0.022038, 1496957384.974100, 2.478800, 1.000000, 39.959278, 23.482109, 13.659877, -56.574467 +-38.5656, 11.0527, -28.336780, 3.780555, -0.449598, -0.104726, 0.000000, 1496957384.983500, 2.474830, 1.000000, 39.997083, 23.482109, 13.659877, -56.574467 +-38.5951, 11.0741, -28.335279, 3.772222, -0.474135, -0.105519, -0.021009, 1496957384.994100, 2.470776, 1.000000, 40.034806, 23.518730, 13.624781, -56.978722 +-38.5951, 11.0741, -28.335279, 3.772222, -0.474135, -0.105519, 0.000000, 1496957385.003500, 2.470776, 1.000000, 40.072528, 23.518730, 13.624781, -56.978722 +-38.6536, 11.1172, -28.332283, 3.766667, -0.447344, -0.106312, -0.021066, 1496957385.014000, 2.462717, 1.000000, 40.110194, 23.518730, 13.659877, -57.382980 +-38.6827, 11.1388, -28.330772, 3.766667, -0.354843, -0.106312, 0.000000, 1496957385.024500, 2.458629, 1.000000, 40.147861, 23.518730, 13.659877, -57.382980 +-38.7118, 11.1604, -28.329321, 3.766667, -0.261712, -0.107232, -0.024425, 1496957385.034000, 2.454498, 1.000000, 40.185528, 23.604181, 13.691920, -57.851063 +-38.7407, 11.1822, -28.327867, 3.766667, -0.165074, -0.107232, 0.000000, 1496957385.044500, 2.450361, 1.000000, 40.223194, 23.604181, 13.691920, -57.851063 +-38.7696, 11.204, -28.326414, 3.763889, -0.162786, -0.108112, -0.023366, 1496957385.054100, 2.446233, 1.000000, 40.260833, 23.494316, 13.640039, -58.297871 +-38.7984, 11.2259, -28.325005, 3.763889, -0.224147, -0.108112, 0.000000, 1496957385.064600, 2.441997, 1.000000, 40.298472, 23.494316, 13.640039, -58.297871 +-38.8271, 11.2478, -28.323544, 3.755556, -0.333999, -0.108992, -0.023451, 1496957385.074100, 2.437776, 1.000000, 40.336028, 23.506523, 13.609522, -58.744682 +-38.8546, 11.2718, -28.322227, 3.755556, -0.303180, -0.108992, 0.000000, 1496957385.083600, 2.440959, 1.000000, 40.373583, 23.506523, 13.609522, -58.744682 +-38.8814, 11.2967, -28.320860, 3.750000, -0.160261, -0.109790, -0.021277, 1496957385.094100, 2.436733, 1.000000, 40.411083, 23.530937, 13.679713, -59.148937 +-38.908, 11.3216, -28.319439, 3.750000, -0.155519, -0.109790, 0.000000, 1496957385.103600, 2.432515, 1.000000, 40.448583, 23.530937, 13.679713, -59.148937 +-38.9346, 11.3467, -28.318055, 3.750000, -0.165019, -0.110547, -0.020183, 1496957385.114100, 2.428242, 1.000000, 40.486083, 23.530937, 13.641565, -59.531914 +-38.961, 11.3719, -28.316547, 3.750000, -0.222525, -0.110547, 0.000000, 1496957385.123500, 2.423975, 1.000000, 40.523583, 23.530937, 13.641565, -59.531914 +-38.9873, 11.3972, -28.315005, 3.744444, -0.295444, -0.111221, -0.017988, 1496957385.134000, 2.419707, 1.000000, 40.561028, 23.494316, 13.698024, -59.872341 +-39.0134, 11.4226, -28.313415, 3.744444, -0.266886, -0.111221, 0.000000, 1496957385.144600, 2.415439, 1.000000, 40.598472, 23.494316, 13.698024, -59.872341 +-39.0394, 11.4481, -28.311683, 3.736111, -0.225928, -0.111811, -0.015791, 1496957385.154200, 2.411163, 1.000000, 40.635833, 23.469902, 13.684291, -60.170212 +-39.0653, 11.4738, -28.309971, 3.736111, -0.227489, -0.111811, 0.000000, 1496957385.163800, 2.406938, 1.000000, 40.673194, 23.469902, 13.684291, -60.170212 +-39.0911, 11.4995, -28.308119, 3.730556, -0.254935, -0.112401, -0.015830, 1496957385.174400, 2.402638, 1.000000, 40.710500, 23.469902, 13.617151, -60.468086 +-39.1167, 11.5254, -28.306218, 3.730556, -0.234288, -0.112401, 0.000000, 1496957385.184000, 2.398370, 1.000000, 40.747806, 23.469902, 13.617151, -60.468086 +-39.1422, 11.5513, -28.304276, 3.725000, -0.257750, -0.112823, -0.011333, 1496957385.194600, 2.394047, 1.000000, 40.785056, 23.482109, 13.722439, -60.680851 +-39.1675, 11.5774, -28.302227, 3.725000, -0.167185, -0.112823, 0.000000, 1496957385.204200, 2.389772, 1.000000, 40.822306, 23.482109, 13.722439, -60.680851 +-39.1927, 11.6036, -28.300202, 3.719445, -0.205131, -0.113161, -0.009086, 1496957385.213700, 2.385512, 1.000000, 40.859500, 23.482109, 13.676661, -60.851063 +-39.2178, 11.63, -28.298084, 3.719445, -0.161213, -0.113161, 0.000000, 1496957385.224200, 2.381196, 1.000000, 40.896694, 23.482109, 13.676661, -60.851063 +-39.2427, 11.6565, -28.295928, 3.711111, -0.112396, -0.113499, -0.009112, 1496957385.233700, 2.376904, 1.000000, 40.933806, 23.518730, 13.626307, -61.021278 +-39.2676, 11.6831, -28.293772, 3.711111, -0.093688, -0.113499, 0.000000, 1496957385.244300, 2.372619, 1.000000, 40.970917, 23.518730, 13.626307, -61.021278 +-39.2922, 11.7098, -28.291553, 3.705555, -0.066962, -0.113753, -0.006847, 1496957385.253800, 2.368350, 1.000000, 41.007972, 23.469902, 13.655298, -61.148937 +-39.3168, 11.7366, -28.289362, 3.705555, 0.008627, -0.113753, 0.000000, 1496957385.264300, 2.364039, 1.000000, 41.045028, 23.469902, 13.655298, -61.148937 +-39.3413, 11.7636, -28.287065, 3.702778, 0.019921, -0.114007, -0.006855, 1496957385.273800, 2.359747, 1.000000, 41.082056, 23.506523, 13.618677, -61.276596 +-39.3657, 11.7906, -28.284845, 3.702778, 0.077170, -0.114007, 0.000000, 1496957385.285600, 2.355434, 1.000000, 41.119083, 23.506523, 13.618677, -61.276596 +-39.3899, 11.8178, -28.282555, 3.700000, 0.044943, -0.114261, -0.006863, 1496957385.294100, 2.351092, 1.000000, 41.156083, 23.482109, 13.658351, -61.404255 +-39.4141, 11.8451, -28.280280, 3.700000, 0.061664, -0.114261, 0.000000, 1496957385.303600, 2.346752, 1.000000, 41.193083, 23.482109, 13.658351, -61.404255 +-39.4382, 11.8725, -28.277982, 3.700000, 0.028376, -0.114473, -0.005722, 1496957385.314100, 2.342413, 1.000000, 41.230083, 23.445488, 13.638514, -61.510639 +-39.4622, 11.8999, -28.275679, 3.700000, 0.058567, -0.114473, 0.000000, 1496957385.323600, 2.338060, 1.000000, 41.267083, 23.445488, 13.638514, -61.510639 +-39.4861, 11.9275, -28.273367, 3.700000, 0.145467, -0.114600, -0.003434, 1496957385.334200, 2.333684, 1.000000, 41.304083, 23.152514, 13.682765, -61.574467 +-39.5099, 11.9552, -28.271092, 3.700000, 0.117707, -0.114600, 0.000000, 1496957385.343700, 2.329331, 1.000000, 41.341083, 23.152514, 13.682765, -61.574467 +-39.5336, 11.983, -28.268776, 3.700000, 0.146798, -0.114727, -0.003435, 1496957385.354700, 2.324933, 1.000000, 41.378083, 23.482109, 13.662929, -61.638298 +-39.5573, 12.0109, -28.266511, 3.700000, 0.183396, -0.114727, 0.000000, 1496957385.364500, 2.320507, 1.000000, 41.415083, 23.482109, 13.662929, -61.638298 +-39.5809, 12.0389, -28.264262, 3.697222, 0.184634, -0.114854, -0.003438, 1496957385.374500, 2.316075, 1.000000, 41.452056, 23.506523, 13.665980, -61.702129 +-39.6044, 12.0669, -28.261989, 3.697222, 0.149609, -0.114854, 0.000000, 1496957385.383900, 2.311658, 1.000000, 41.489028, 23.506523, 13.665980, -61.702129 +-39.6278, 12.0951, -28.259778, 3.697222, 0.193505, -0.114896, -0.001146, 1496957385.394500, 2.307221, 1.000000, 41.526000, 23.469902, 13.641565, -61.723404 +-39.6511, 12.1234, -28.257489, 3.697222, 0.209082, -0.114896, 0.000000, 1496957385.404600, 2.302750, 1.000000, 41.562972, 23.469902, 13.641565, -61.723404 +-39.6744, 12.1518, -28.255293, 3.697222, 0.188644, -0.114896, 0.000000, 1496957385.413600, 2.298331, 1.000000, 41.599944, 23.469902, 13.641565, -61.723404 +-39.6975, 12.1803, -28.253069, 3.697222, 0.261079, -0.114896, 0.000000, 1496957385.424100, 2.293899, 1.000000, 41.636917, 23.469902, 13.638514, -61.723404 +-39.7206, 12.2089, -28.250853, 3.700000, 0.268879, -0.114896, 0.000000, 1496957385.433600, 2.289439, 1.000000, 41.673917, 23.482109, 13.626307, -61.723404 +-39.7436, 12.2377, -28.248664, 3.700000, 0.377949, -0.114896, 0.000000, 1496957385.444200, 2.285009, 1.000000, 41.710917, 23.482109, 13.626307, -61.723404 +-39.7666, 12.2665, -28.246460, 3.705555, 0.404684, -0.114896, 0.000000, 1496957385.453700, 2.280545, 1.000000, 41.747972, 23.469902, 13.640039, -61.723404 +-39.7895, 12.2955, -28.244337, 3.705555, 0.458209, -0.114896, 0.000000, 1496957385.464300, 2.276101, 1.000000, 41.785028, 23.469902, 13.640039, -61.723404 +-39.8122, 12.3247, -28.242189, 3.713889, 0.510543, -0.114854, 0.001141, 1496957385.474300, 2.271642, 1.000000, 41.822167, 23.469902, 13.604944, -61.702129 +-39.8349, 12.3539, -28.240047, 3.713889, 0.326787, -0.114854, 0.000000, 1496957385.483800, 2.267208, 1.000000, 41.859306, 23.469902, 13.604944, -61.702129 +-39.8575, 12.3832, -28.237892, 3.713889, 0.280504, -0.114811, 0.001141, 1496957385.494300, 2.262784, 1.000000, 41.896444, 23.469902, 13.621729, -61.680851 +-39.88, 12.4127, -28.235786, 3.713889, 0.288219, -0.114811, 0.000000, 1496957385.503800, 2.258346, 1.000000, 41.933583, 23.469902, 13.621729, -61.680851 +-39.9247, 12.4721, -28.231711, 3.711111, 0.393359, -0.114769, 0.001142, 1496957385.514200, 2.249521, 1.000000, 41.970694, 23.506523, 13.650721, -61.659573 +-39.9247, 12.4721, -28.231711, 3.711111, 0.513196, -0.114769, 0.000000, 1496957385.523800, 2.249521, 1.000000, 42.007806, 23.506523, 13.650721, -61.659573 +-39.9468, 12.5021, -28.229933, 3.713889, 0.754529, -0.114769, 0.000000, 1496957385.534200, 2.245153, 1.000000, 42.044944, 23.482109, 13.707179, -61.659573 +-39.9689, 12.5323, -28.228126, 3.713889, 0.688743, -0.114769, 0.000000, 1496957385.543800, 2.240779, 1.000000, 42.082083, 23.482109, 13.707179, -61.659573 +-39.9908, 12.5626, -28.226434, 3.716667, 0.601897, -0.114727, 0.001140, 1496957385.554300, 2.236402, 1.000000, 42.119250, 23.506523, 13.701076, -61.638298 +-40.0125, 12.5931, -28.224755, 3.716667, 0.485186, -0.114727, 0.000000, 1496957385.563800, 2.232015, 1.000000, 42.156417, 23.506523, 13.701076, -61.638298 +-40.0341, 12.6237, -28.223033, 3.713889, 0.325320, -0.114727, 0.000000, 1496957385.574300, 2.227692, 1.000000, 42.193556, 23.469902, 13.704127, -61.638298 +-40.0556, 12.6546, -28.221239, 3.713889, 0.342223, -0.114727, 0.000000, 1496957385.583800, 2.223342, 1.000000, 42.230694, 23.469902, 13.704127, -61.638298 +-40.0768, 12.6855, -28.219485, 3.719445, 0.056295, -0.114769, -0.001139, 1496957385.594400, 2.219006, 1.000000, 42.267889, 23.469902, 13.621729, -61.659573 +-40.098, 12.7166, -28.217555, 3.719445, 0.131400, -0.114769, 0.000000, 1496957385.604100, 2.214680, 1.000000, 42.305083, 23.469902, 13.621729, -61.659573 +-40.119, 12.7478, -28.215639, 3.725000, 0.219805, -0.114769, 0.000000, 1496957385.613500, 2.210369, 1.000000, 42.342333, 23.518730, 13.636988, -61.659573 +-40.1399, 12.7791, -28.213723, 3.725000, 0.226113, -0.114769, 0.000000, 1496957385.624000, 2.205972, 1.000000, 42.379583, 23.518730, 13.636988, -61.659573 +-40.1607, 12.8106, -28.211692, 3.730556, 0.501699, -0.114811, -0.001136, 1496957385.634600, 2.201673, 1.000000, 42.416889, 23.469902, 13.647669, -61.680851 +-40.1814, 12.8422, -28.209890, 3.730556, 0.527575, -0.114811, 0.000000, 1496957385.644200, 2.197279, 1.000000, 42.454194, 23.469902, 13.647669, -61.680851 +-40.202, 12.8739, -28.207896, 3.736111, 0.538105, -0.114854, -0.001134, 1496957385.653700, 2.192871, 1.000000, 42.491556, 23.482109, 13.640039, -61.702129 +-40.2226, 12.9058, -28.206107, 3.736111, 0.520794, -0.114854, 0.000000, 1496957385.664200, 2.188436, 1.000000, 42.528917, 23.482109, 13.640039, -61.702129 +-40.243, 12.9378, -28.204211, 3.741667, 0.569507, -0.114854, 0.000000, 1496957385.673800, 2.184086, 1.000000, 42.566333, 23.469902, 13.653772, -61.702129 +-40.2634, 12.9699, -28.202454, 3.741667, 0.488472, -0.114854, 0.000000, 1496957385.684300, 2.179637, 1.000000, 42.603750, 23.469902, 13.653772, -61.702129 +-40.2836, 13.0022, -28.200632, 3.747222, 0.407597, -0.114896, -0.001131, 1496957385.693800, 2.175249, 1.000000, 42.641222, 23.543144, 13.673610, -61.723404 +-40.3037, 13.0345, -28.198697, 3.747222, 0.243096, -0.114896, 0.000000, 1496957385.704300, 2.170853, 1.000000, 42.678694, 23.543144, 13.673610, -61.723404 +-40.3237, 13.067, -28.196902, 3.752778, 0.347794, -0.114854, 0.001129, 1496957385.713800, 2.166452, 1.000000, 42.716222, 23.469902, 13.669032, -61.702129 +-40.3436, 13.0996, -28.194939, 3.752778, 0.472698, -0.114854, 0.000000, 1496957385.724400, 2.162001, 1.000000, 42.753750, 23.469902, 13.669032, -61.702129 +-40.3634, 13.1323, -28.193098, 3.761111, 0.517160, -0.114854, 0.000000, 1496957385.733900, 2.157554, 1.000000, 42.791361, 23.555351, 13.612574, -61.702129 +-40.3831, 13.1652, -28.191157, 3.761111, 0.512653, -0.114854, 0.000000, 1496957385.744500, 2.153092, 1.000000, 42.828972, 23.555351, 13.612574, -61.702129 +-40.4027, 13.1982, -28.189285, 3.763889, 0.402637, -0.114854, 0.000000, 1496957385.754000, 2.148642, 1.000000, 42.866611, 23.701839, 13.621729, -61.702129 +-40.4221, 13.2314, -28.187390, 3.763889, 0.601001, -0.114854, 0.000000, 1496957385.764500, 2.144159, 1.000000, 42.904250, 23.701839, 13.621729, -61.702129 +-40.4415, 13.2647, -28.185464, 3.766667, 0.601088, -0.114769, 0.002250, 1496957385.774000, 2.139711, 1.000000, 42.941917, 23.738461, 13.623255, -61.659573 +-40.4607, 13.2981, -28.183671, 3.766667, 0.533953, -0.114769, 0.000000, 1496957385.784600, 2.135222, 1.000000, 42.979583, 23.738461, 13.623255, -61.659573 +-40.4799, 13.3317, -28.181784, 3.775000, 0.569216, -0.114600, 0.004489, 1496957385.794200, 2.130734, 1.000000, 43.017333, 23.726254, 13.673610, -61.574467 +-40.4989, 13.3654, -28.179971, 3.775000, 0.629582, -0.114600, 0.000000, 1496957385.803800, 2.126208, 1.000000, 43.055083, 23.726254, 13.673610, -61.574467 +-40.5178, 13.3992, -28.178187, 3.788889, 0.456793, -0.114388, 0.005589, 1496957385.814400, 2.121670, 1.000000, 43.092972, 23.665216, 13.667506, -61.468086 +-40.5365, 13.4332, -28.176380, 3.788889, 0.509226, -0.114388, 0.000000, 1496957385.824100, 2.117180, 1.000000, 43.130861, 23.665216, 13.667506, -61.468086 +-40.5552, 13.4673, -28.174612, 3.797222, 0.511310, -0.114134, 0.006689, 1496957385.833500, 2.112674, 1.000000, 43.168833, 23.726254, 13.667506, -61.340427 +-40.5737, 13.5016, -28.172908, 3.797222, 0.549744, -0.114134, 0.000000, 1496957385.844100, 2.108174, 1.000000, 43.206806, 23.726254, 13.624781, -61.340427 +-40.5922, 13.5359, -28.171211, 3.805556, 0.696851, -0.113795, 0.008895, 1496957385.853500, 2.103707, 1.000000, 43.244861, 23.726254, 13.662929, -61.170212 +-40.6106, 13.5705, -28.169574, 3.805556, 0.774894, -0.113795, 0.000000, 1496957385.864100, 2.099214, 1.000000, 43.282917, 23.726254, 13.662929, -61.170212 +-40.6288, 13.6051, -28.167949, 3.822222, 0.762550, -0.113499, 0.007745, 1496957385.873600, 2.094675, 1.000000, 43.321139, 23.701839, 13.626307, -61.021278 +-40.647, 13.64, -28.166372, 3.822222, 0.801560, -0.113499, 0.000000, 1496957385.884200, 2.090202, 1.000000, 43.359361, 23.701839, 13.626307, -61.021278 +-40.6651, 13.6749, -28.164840, 3.833333, 0.803901, -0.113119, 0.009923, 1496957385.893700, 2.085655, 1.000000, 43.397694, 23.738461, 13.658351, -60.829788 +-40.6831, 13.71, -28.163427, 3.833333, 0.742714, -0.113119, 0.000000, 1496957385.904200, 2.081164, 1.000000, 43.436028, 23.738461, 13.658351, -60.829788 +-40.701, 13.7452, -28.162017, 3.838889, 0.698958, -0.112781, 0.008803, 1496957385.913900, 2.076656, 1.000000, 43.474417, 23.726254, 13.658351, -60.659573 +-40.7187, 13.7806, -28.160615, 3.838889, 0.735496, -0.112781, 0.000000, 1496957385.924300, 2.072167, 1.000000, 43.512806, 23.726254, 13.670558, -60.659573 +-40.7364, 13.8161, -28.159372, 3.852778, 0.768327, -0.112443, 0.008766, 1496957385.933900, 2.067700, 1.000000, 43.551333, 23.738461, 13.678187, -60.489361 +-40.754, 13.8517, -28.158064, 3.852778, 0.569815, -0.112443, 0.000000, 1496957385.944500, 2.063239, 1.000000, 43.589861, 23.738461, 13.678187, -60.489361 +-40.7714, 13.8875, -28.156787, 3.866667, 0.707806, -0.112106, 0.008730, 1496957385.954100, 2.058749, 1.000000, 43.628528, 23.738461, 13.614100, -60.319149 +-40.7888, 13.9235, -28.155627, 3.866667, 0.771449, -0.112106, 0.000000, 1496957385.963500, 2.054260, 1.000000, 43.667194, 23.738461, 13.614100, -60.319149 +-40.806, 13.9595, -28.154390, 3.877778, 0.751903, -0.111768, 0.008700, 1496957385.974100, 2.049755, 1.000000, 43.705972, 23.714046, 13.708705, -60.148937 +-40.8231, 13.9957, -28.153261, 3.877778, 0.798593, -0.111768, 0.000000, 1496957385.983600, 2.045305, 1.000000, 43.744750, 23.714046, 13.708705, -60.148937 +-40.8401, 14.0321, -28.152193, 3.891667, 0.800437, -0.111473, 0.007581, 1496957385.994100, 2.040773, 1.000000, 43.783667, 23.689632, 13.601892, -60.000000 +-40.857, 14.0686, -28.151080, 3.891667, 0.763550, -0.111473, 0.000000, 1496957386.003500, 2.036288, 1.000000, 43.822583, 23.689632, 13.601892, -60.000000 +-40.8738, 14.1052, -28.150057, 3.902778, 0.696687, -0.111136, 0.008635, 1496957386.014000, 2.031862, 1.000000, 43.861611, 23.677423, 13.588159, -59.829788 +-40.8905, 14.142, -28.148937, 3.902778, 0.710457, -0.111136, 0.000000, 1496957386.024600, 2.027302, 1.000000, 43.900639, 23.677423, 13.588159, -59.829788 +-40.9071, 14.1789, -28.147901, 3.913889, 0.691511, -0.110757, 0.009681, 1496957386.034200, 2.022802, 1.000000, 43.939778, 23.665216, 13.684291, -59.638298 +-40.9236, 14.2159, -28.146858, 3.913889, 0.735889, -0.110757, 0.000000, 1496957386.043800, 2.018297, 1.000000, 43.978917, 23.665216, 13.684291, -59.638298 +-40.9399, 14.253, -28.145800, 3.925000, 0.640509, -0.110421, 0.008576, 1496957386.054300, 2.013764, 1.000000, 44.018167, 23.665216, 13.598841, -59.468086 +-40.9562, 14.2903, -28.144764, 3.925000, 0.645844, -0.110421, 0.000000, 1496957386.063800, 2.009241, 1.000000, 44.057417, 23.665216, 13.598841, -59.468086 +-40.9723, 14.3277, -28.143720, 3.936111, 0.685533, -0.110084, 0.008547, 1496957386.074300, 2.004731, 1.000000, 44.096778, 23.689632, 13.626307, -59.297871 +-40.9853, 14.3685, -28.143148, 3.936111, 0.660175, -0.110084, 0.000000, 1496957386.083800, 2.006581, 1.000000, 44.136139, 23.689632, 13.626307, -59.297871 +-40.9991, 14.4079, -28.142549, 3.947222, 0.760588, -0.109748, 0.008519, 1496957386.094400, 2.002044, 1.000000, 44.175611, 23.701839, 13.617151, -59.127659 +-41.0128, 14.4475, -28.142042, 3.947222, 0.844932, -0.109748, 0.000000, 1496957386.103900, 1.997519, 1.000000, 44.215083, 23.701839, 13.617151, -59.127659 +-41.0264, 14.4872, -28.141494, 3.958333, 0.772703, -0.109370, 0.009551, 1496957386.114500, 1.992966, 1.000000, 44.254667, 23.689632, 13.650721, -58.936169 +-41.0398, 14.5271, -28.141041, 3.958333, 0.870941, -0.109370, 0.000000, 1496957386.124100, 1.988417, 1.000000, 44.294250, 23.689632, 13.650721, -58.936169 +-41.0531, 14.5671, -28.140607, 3.972222, 0.897632, -0.109076, 0.007398, 1496957386.133600, 1.983838, 1.000000, 44.333972, 23.653009, 13.633936, -58.787235 +-41.0663, 14.6072, -28.140220, 3.972222, 0.867691, -0.109076, 0.000000, 1496957386.144200, 1.979290, 1.000000, 44.373694, 23.653009, 13.633936, -58.787235 +-41.0794, 14.6475, -28.139859, 3.986111, 0.773910, -0.108782, 0.007369, 1496957386.153700, 1.974699, 1.000000, 44.413556, 23.701839, 13.667506, -58.638298 +-41.0924, 14.6879, -28.139561, 3.986111, 0.827004, -0.108782, 0.000000, 1496957386.164300, 1.970178, 1.000000, 44.453417, 23.701839, 13.667506, -58.638298 +-41.1052, 14.7285, -28.139278, 3.997222, 0.793499, -0.108531, 0.006296, 1496957386.173800, 1.965630, 1.000000, 44.493389, 23.701839, 13.638514, -58.510639 +-41.1179, 14.7692, -28.139122, 3.997222, 0.887014, -0.108531, 0.000000, 1496957386.184400, 1.961076, 1.000000, 44.533361, 23.701839, 13.638514, -58.510639 +-41.1305, 14.8101, -28.138980, 4.008333, 0.865122, -0.108279, 0.006276, 1496957386.194100, 1.956493, 1.000000, 44.573444, 23.701839, 13.647669, -58.382980 +-41.143, 14.8511, -28.138878, 4.008333, 1.007933, -0.108279, 0.000000, 1496957386.203600, 1.951958, 1.000000, 44.613528, 23.701839, 13.647669, -58.382980 +-41.1553, 14.8922, -28.138921, 4.022222, 0.885531, -0.108112, 0.004168, 1496957386.214100, 1.947425, 1.000000, 44.653750, 23.726254, 13.618677, -58.297871 +-41.1675, 14.9335, -28.138903, 4.022222, 0.749294, -0.108112, 0.000000, 1496957386.223700, 1.942883, 1.000000, 44.693972, 23.726254, 13.618677, -58.297871 +-41.1796, 14.9749, -28.139067, 4.033333, 0.834395, -0.107860, 0.006233, 1496957386.234300, 1.938392, 1.000000, 44.734306, 23.701839, 13.611048, -58.170212 +-41.1915, 15.0165, -28.139161, 4.033333, 0.807769, -0.107860, 0.000000, 1496957386.243700, 1.933875, 1.000000, 44.774639, 23.701839, 13.611048, -58.170212 +-41.2032, 15.0582, -28.139418, 4.044445, 0.812908, -0.107651, 0.005178, 1496957386.254200, 1.929353, 1.000000, 44.815083, 23.689632, 13.615625, -58.063831 +-41.2148, 15.1001, -28.139711, 4.044445, 0.860068, -0.107651, 0.000000, 1496957386.263800, 1.924855, 1.000000, 44.855528, 23.689632, 13.615625, -58.063831 +-41.2262, 15.1421, -28.140060, 4.058333, 0.810019, -0.107399, 0.006190, 1496957386.274400, 1.920368, 1.000000, 44.896111, 23.677423, 13.644617, -57.936169 +-41.2375, 15.1842, -28.140489, 4.058333, 0.902117, -0.107399, 0.000000, 1496957386.283900, 1.915818, 1.000000, 44.936694, 23.677423, 13.644617, -57.936169 +-41.2487, 15.2265, -28.141026, 4.075000, 0.940201, -0.107148, 0.006162, 1496957386.294600, 1.911283, 1.000000, 44.977444, 23.653009, 13.673610, -57.808510 +-41.2596, 15.2689, -28.141657, 4.075000, 0.850669, -0.107148, 0.000000, 1496957386.304200, 1.906764, 1.000000, 45.018194, 23.653009, 13.673610, -57.808510 +-41.2704, 15.3115, -28.142393, 4.088889, 0.822444, -0.106856, 0.007162, 1496957386.313800, 1.902243, 1.000000, 45.059083, 23.701839, 13.673610, -57.659573 +-41.2811, 15.3542, -28.143236, 4.088889, 0.871835, -0.106856, 0.000000, 1496957386.324300, 1.897739, 1.000000, 45.099972, 23.701839, 13.598841, -57.659573 +-41.2916, 15.3971, -28.144130, 4.097222, 0.805597, -0.106521, 0.008164, 1496957386.333700, 1.893166, 1.000000, 45.140944, 23.738461, 13.598841, -57.489361 +-41.3019, 15.4401, -28.145200, 4.097222, 0.862082, -0.106521, 0.000000, 1496957386.344200, 1.888679, 1.000000, 45.181917, 23.738461, 13.607996, -57.489361 +-41.3121, 15.4832, -28.146302, 4.113889, 0.857318, -0.106187, 0.008127, 1496957386.353700, 1.884160, 1.000000, 45.223056, 23.653009, 13.607996, -57.319149 +-41.3222, 15.5264, -28.147554, 4.113889, 0.889712, -0.106187, 0.000000, 1496957386.364500, 1.879614, 1.000000, 45.264194, 23.653009, 13.621729, -57.319149 +-41.3321, 15.5698, -28.148828, 4.133333, 0.870991, -0.105769, 0.010105, 1496957386.374100, 1.875085, 1.000000, 45.305528, 23.689632, 13.621729, -57.106384 +-41.3418, 15.6134, -28.150223, 4.133333, 0.959807, -0.105769, 0.000000, 1496957386.383500, 1.870580, 1.000000, 45.346861, 23.689632, 13.656825, -57.106384 +-41.3515, 15.6571, -28.151610, 4.152778, 0.905214, -0.105352, 0.010051, 1496957386.394000, 1.866033, 1.000000, 45.388389, 23.677423, 13.656825, -56.893616 +-41.3609, 15.7009, -28.153037, 4.152778, 0.848207, -0.105352, 0.000000, 1496957386.403900, 1.861478, 1.000000, 45.429917, 23.677423, 13.600367, -56.893616 +-41.3702, 15.7448, -28.154500, 4.169445, 1.002092, -0.104809, 0.013004, 1496957386.414100, 1.856956, 1.000000, 45.471611, 23.701839, 13.621729, -56.617020 +-41.3794, 15.7889, -28.155947, 4.169445, 0.774248, -0.104809, 0.000000, 1496957386.424500, 1.852399, 1.000000, 45.513306, 23.701839, 13.621729, -56.617020 +-41.3884, 15.8331, -28.157373, 4.186111, 0.743661, -0.104184, 0.014931, 1496957386.434000, 1.847866, 1.000000, 45.555167, 23.677423, 13.621729, -56.297871 +-41.3972, 15.8774, -28.158871, 4.186111, 0.721031, -0.104184, 0.000000, 1496957386.444600, 1.843351, 1.000000, 45.597028, 23.677423, 13.611048, -56.297871 +-41.4058, 15.9219, -28.160308, 4.202778, 0.869909, -0.103560, 0.014858, 1496957386.454100, 1.838844, 1.000000, 45.639056, 23.640802, 13.611048, -55.978722 +-41.4143, 15.9664, -28.161719, 4.202778, 0.734395, -0.103560, 0.000000, 1496957386.463600, 1.834285, 1.000000, 45.681083, 23.640802, 13.643091, -55.978722 +-41.4226, 16.0112, -28.163345, 4.216667, 0.904544, -0.102853, 0.016766, 1496957386.474100, 1.829786, 1.000000, 45.723250, 23.677423, 13.643091, -55.617020 +-41.4308, 16.0561, -28.164806, 4.216667, 0.990815, -0.102853, 0.000000, 1496957386.483500, 1.825246, 1.000000, 45.765417, 23.677423, 13.611048, -55.617020 +-41.4387, 16.1011, -28.166410, 4.230556, 0.915407, -0.101981, 0.020618, 1496957386.494000, 1.820718, 1.000000, 45.807722, 23.677423, 13.611048, -55.170212 +-41.4465, 16.1463, -28.167881, 4.230556, 0.946024, -0.101981, 0.000000, 1496957386.504500, 1.816222, 1.000000, 45.850028, 23.677423, 13.640039, -55.170212 +-41.4614, 16.237, -28.170804, 4.247222, 0.751921, -0.101110, 0.020510, 1496957386.514100, 1.807347, 1.000000, 45.892500, 23.616388, 13.640039, -54.723404 +-41.4614, 16.237, -28.170804, 4.247222, 0.751921, -0.101110, 0.000000, 1496957386.524600, 1.807347, 1.000000, 45.934972, 23.616388, 13.650721, -54.723404 +-41.4685, 16.2826, -28.172171, 4.258333, 0.793272, -0.100116, 0.023345, 1496957386.534100, 1.802911, 1.000000, 45.977556, 23.677423, 13.650721, -54.212765 +-41.4754, 16.3282, -28.173378, 4.258333, 0.593339, -0.100116, 0.000000, 1496957386.543500, 1.798496, 1.000000, 46.020139, 23.677423, 13.708705, -54.212765 +-41.4821, 16.374, -28.174612, 4.269444, 0.587516, -0.099082, 0.024218, 1496957386.554100, 1.794157, 1.000000, 46.062833, 23.653009, 13.708705, -53.680851 +-41.4886, 16.4199, -28.175723, 4.269444, 0.744223, -0.099082, 0.000000, 1496957386.563500, 1.789808, 1.000000, 46.105528, 23.653009, 13.615625, -53.680851 +-41.4949, 16.466, -28.176828, 4.277778, 0.801213, -0.097967, 0.026063, 1496957386.574100, 1.785465, 1.000000, 46.148306, 23.591974, 13.615625, -53.106384 +-41.501, 16.5122, -28.177907, 4.277778, 0.921344, -0.097967, 0.000000, 1496957386.583600, 1.781134, 1.000000, 46.191083, 23.591974, 13.583581, -53.106384 +-41.507, 16.5585, -28.178813, 4.286111, 0.806260, -0.096854, 0.025969, 1496957386.594200, 1.776856, 1.000000, 46.233944, 23.518730, 13.583581, -52.531914 +-41.5127, 16.605, -28.179753, 4.286111, 0.770403, -0.096854, 0.000000, 1496957386.603700, 1.772590, 1.000000, 46.276806, 23.518730, 13.614100, -52.531914 +-41.5182, 16.6516, -28.180563, 4.297222, 0.803977, -0.095701, 0.026817, 1496957386.614100, 1.768338, 1.000000, 46.319778, 23.579767, 13.614100, -51.936169 +-41.5236, 16.6982, -28.181367, 4.297222, 0.757762, -0.095701, 0.000000, 1496957386.623600, 1.764114, 1.000000, 46.362750, 23.579767, 13.635462, -51.936169 +-41.5287, 16.7451, -28.182161, 4.305555, 0.784189, -0.094551, 0.026720, 1496957386.634100, 1.759903, 1.000000, 46.405805, 23.579767, 13.635462, -51.340427 +-41.5337, 16.792, -28.182953, 4.305555, 0.781288, -0.094551, 0.000000, 1496957386.643600, 1.755696, 1.000000, 46.448861, 23.579767, 13.630884, -51.340427 +-41.5384, 16.839, -28.183618, 4.313889, 0.782543, -0.093402, 0.026625, 1496957386.654100, 1.751526, 1.000000, 46.492000, 23.579767, 13.630884, -50.744682 +-41.543, 16.8862, -28.184445, 4.313889, 0.924602, -0.093402, 0.000000, 1496957386.663600, 1.747391, 1.000000, 46.535139, 23.579767, 13.621729, -50.744682 +-41.5474, 16.9335, -28.185049, 4.322222, 0.831281, -0.092255, 0.026530, 1496957386.674100, 1.743187, 1.000000, 46.578361, 23.567560, 13.621729, -50.148937 +-41.5516, 16.981, -28.185820, 4.322222, 0.900794, -0.092255, 0.000000, 1496957386.683600, 1.739059, 1.000000, 46.621583, 23.567560, 13.601892, -50.148937 +-41.5557, 17.0285, -28.186483, 4.333333, 0.772530, -0.091151, 0.025477, 1496957386.694100, 1.734899, 1.000000, 46.664917, 23.653009, 13.601892, -49.574467 +-41.5596, 17.0761, -28.187163, 4.333333, 0.795700, -0.091151, 0.000000, 1496957386.703600, 1.730791, 1.000000, 46.708250, 23.653009, 13.662929, -49.574467 +-41.5633, 17.1239, -28.187858, 4.344444, 0.990693, -0.090049, 0.025373, 1496957386.714200, 1.726714, 1.000000, 46.751694, 23.640802, 13.662929, -49.000000 +-41.5669, 17.1718, -28.188617, 4.344444, 0.938982, -0.090049, 0.000000, 1496957386.723700, 1.722619, 1.000000, 46.795139, 23.640802, 13.611048, -49.000000 +-41.5703, 17.2198, -28.189295, 4.358333, 0.986658, -0.088949, 0.025254, 1496957386.734200, 1.718526, 1.000000, 46.838722, 23.567560, 13.611048, -48.425533 +-41.5737, 17.2679, -28.190105, 4.358333, 0.961845, -0.088949, 0.000000, 1496957386.743700, 1.714451, 1.000000, 46.882305, 23.567560, 13.635462, -48.425533 +-41.5768, 17.3162, -28.190967, 4.372222, 0.892085, -0.087890, 0.024206, 1496957386.754200, 1.710382, 1.000000, 46.926028, 23.604181, 13.635462, -47.872341 +-41.5798, 17.3645, -28.191736, 4.372222, 0.839507, -0.087890, 0.000000, 1496957386.763600, 1.706362, 1.000000, 46.969750, 23.604181, 13.640039, -47.872341 +-41.5826, 17.4129, -28.192720, 4.383333, 0.826615, -0.086915, 0.022257, 1496957386.774100, 1.702350, 1.000000, 47.013583, 23.604181, 13.640039, -47.361702 +-41.5853, 17.4615, -28.193596, 4.383333, 0.926099, -0.086915, 0.000000, 1496957386.785900, 1.698408, 1.000000, 47.057417, 23.604181, 13.579003, -47.361702 +-41.5879, 17.5102, -28.194576, 4.397222, 0.937765, -0.085900, 0.023080, 1496957386.794400, 1.694409, 1.000000, 47.101389, 23.640802, 13.579003, -46.829788 +-41.5904, 17.559, -28.195598, 4.397222, 1.064911, -0.085900, 0.000000, 1496957386.803900, 1.690423, 1.000000, 47.145361, 23.640802, 13.586633, -46.829788 +-41.5927, 17.6079, -28.196565, 4.413889, 0.967044, -0.084927, 0.022045, 1496957386.814500, 1.686494, 1.000000, 47.189500, 23.616388, 13.586633, -46.319149 +-41.5948, 17.6569, -28.197683, 4.413889, 0.941140, -0.084927, 0.000000, 1496957386.824100, 1.682545, 1.000000, 47.233639, 23.616388, 13.662929, -46.319149 +-41.5968, 17.7061, -28.198700, 4.427778, 0.970849, -0.083995, 0.021034, 1496957386.833500, 1.678587, 1.000000, 47.277917, 23.555351, 13.662929, -45.829788 +-41.5987, 17.7553, -28.199844, 4.427778, 0.922592, -0.083995, 0.000000, 1496957386.844100, 1.674713, 1.000000, 47.322194, 23.555351, 13.658351, -45.829788 +-41.6004, 17.8047, -28.201013, 4.438889, 1.019957, -0.083106, 0.020045, 1496957386.853500, 1.670837, 1.000000, 47.366583, 23.445488, 13.658351, -45.361702 +-41.602, 17.8541, -28.202182, 4.438889, 0.941325, -0.083106, 0.000000, 1496957386.864100, 1.666880, 1.000000, 47.410972, 23.445488, 13.598841, -45.361702 +-41.6034, 17.9037, -28.203431, 4.452778, 0.938945, -0.082176, 0.020867, 1496957386.873600, 1.663070, 1.000000, 47.455500, 23.408865, 13.598841, -44.872341 +-41.6047, 17.9534, -28.204665, 4.452778, 0.971033, -0.082176, 0.000000, 1496957386.884100, 1.659195, 1.000000, 47.500028, 23.408865, 13.601892, -44.872341 +-41.6058, 18.0031, -28.205926, 4.466667, 0.872666, -0.081248, 0.020777, 1496957386.893600, 1.655377, 1.000000, 47.544694, 23.201344, 13.601892, -44.382980 +-41.6068, 18.053, -28.207178, 4.466667, 0.838687, -0.081248, 0.000000, 1496957386.904400, 1.651537, 1.000000, 47.589361, 23.201344, 13.643091, -44.382980 +-41.6077, 18.103, -28.208498, 4.477778, 0.822362, -0.080321, 0.020702, 1496957386.913600, 1.647705, 1.000000, 47.634139, 23.176928, 13.643091, -43.893616 +-41.6084, 18.153, -28.209762, 4.477778, 0.890020, -0.080321, 0.000000, 1496957386.924100, 1.643905, 1.000000, 47.678917, 23.176928, 13.708705, -43.893616 +-41.6089, 18.2032, -28.211058, 4.491667, 0.890350, -0.079315, 0.022406, 1496957386.934500, 1.640103, 1.000000, 47.723833, 23.128099, 13.708705, -43.361702 +-41.6093, 18.2535, -28.212165, 4.491667, 0.800379, -0.079315, 0.000000, 1496957386.944200, 1.636268, 1.000000, 47.768750, 23.128099, 13.626307, -43.361702 +-41.6096, 18.3038, -28.213338, 4.508333, 0.713122, -0.078310, 0.022295, 1496957386.953600, 1.632541, 1.000000, 47.813833, 23.054855, 13.626307, -42.829788 +-41.6097, 18.3542, -28.214393, 4.508333, 0.770971, -0.078310, 0.000000, 1496957386.964200, 1.628763, 1.000000, 47.858917, 23.054855, 13.618677, -42.829788 +-41.6096, 18.4047, -28.215366, 4.516667, 0.651202, -0.077226, 0.024004, 1496957386.973800, 1.625054, 1.000000, 47.904083, 23.115892, 13.618677, -42.255318 +-41.6094, 18.4553, -28.216302, 4.516667, 0.676761, -0.077226, 0.000000, 1496957386.984400, 1.621348, 1.000000, 47.949250, 23.115892, 13.630884, -42.255318 +-41.609, 18.506, -28.217219, 4.525000, 0.680396, -0.076103, 0.024815, 1496957386.993900, 1.617706, 1.000000, 47.994500, 23.054855, 13.630884, -41.659573 +-41.6083, 18.5568, -28.217994, 4.525000, 0.822372, -0.076103, 0.000000, 1496957387.004500, 1.614053, 1.000000, 48.039750, 23.054855, 13.627832, -41.659573 +-41.6076, 18.6076, -28.218814, 4.538889, 0.765055, -0.074941, 0.025587, 1496957387.014000, 1.610443, 1.000000, 48.085139, 23.042648, 13.627832, -41.042553 +-41.6066, 18.6585, -28.219424, 4.538889, 0.693544, -0.074941, 0.000000, 1496957387.023500, 1.606822, 1.000000, 48.130528, 23.042648, 13.653772, -41.042553 +-41.6054, 18.7095, -28.220056, 4.550000, 0.708860, -0.073742, 0.026369, 1496957387.034300, 1.603223, 1.000000, 48.176028, 22.810711, 13.653772, -40.404255 +-41.6041, 18.7606, -28.220693, 4.550000, 0.687106, -0.073742, 0.000000, 1496957387.043900, 1.599668, 1.000000, 48.221528, 22.810711, 13.627832, -40.404255 +-41.6026, 18.8118, -28.221178, 4.558333, 0.817563, -0.072424, 0.028911, 1496957387.054400, 1.596060, 1.000000, 48.267111, 22.554359, 13.627832, -39.702129 +-41.6008, 18.8631, -28.221685, 4.558333, 0.785228, -0.072424, 0.000000, 1496957387.063900, 1.592519, 1.000000, 48.312694, 22.554359, 13.665980, -39.702129 +-41.5989, 18.9144, -28.222067, 4.563889, 0.719516, -0.071068, 0.029706, 1496957387.074500, 1.589057, 1.000000, 48.358333, 22.383459, 13.665980, -38.978722 +-41.5942, 18.962, -28.222551, 4.563889, 0.727488, -0.071068, 0.000000, 1496957387.084100, 1.575053, 1.000000, 48.403972, 22.383459, 13.615625, -38.978722 +-41.5906, 19.009, -28.222894, 4.569445, 0.716773, -0.068919, 0.047032, 1496957387.093600, 1.571653, 1.000000, 48.449667, 22.420080, 13.615625, -37.829788 +-41.587, 19.0561, -28.223241, 4.569445, 0.649873, -0.068919, 0.000000, 1496957387.104200, 1.568224, 1.000000, 48.495361, 22.420080, 13.655298, -37.829788 +-41.5831, 19.1033, -28.223498, 4.577778, 0.706673, -0.067529, 0.030370, 1496957387.113600, 1.564835, 1.000000, 48.541139, 22.383459, 13.655298, -37.085106 +-41.579, 19.1505, -28.223761, 4.577778, 0.655944, -0.067529, 0.000000, 1496957387.124200, 1.561446, 1.000000, 48.586917, 22.383459, 13.630884, -37.085106 +-41.5747, 19.1978, -28.224039, 4.586111, 0.656674, -0.066101, 0.031134, 1496957387.133700, 1.558122, 1.000000, 48.632778, 22.359045, 13.630884, -36.319149 +-41.5702, 19.2452, -28.224332, 4.586111, 0.737841, -0.066101, 0.000000, 1496957387.144200, 1.554843, 1.000000, 48.678639, 22.359045, 13.615625, -36.319149 +-41.5655, 19.2927, -28.224694, 4.594444, 0.842692, -0.064596, 0.032755, 1496957387.153800, 1.551590, 1.000000, 48.724583, 22.359045, 13.615625, -35.510639 +-41.5606, 19.3402, -28.224989, 4.594444, 0.447814, -0.064596, 0.000000, 1496957387.164300, 1.548446, 1.000000, 48.770528, 22.359045, 13.699550, -35.510639 +-41.5555, 19.3877, -28.225411, 4.602778, 0.594469, -0.063054, 0.033504, 1496957387.173800, 1.545286, 1.000000, 48.816556, 22.346838, 13.699550, -34.680851 +-41.5503, 19.4354, -28.225875, 4.602778, 0.795074, -0.063054, 0.000000, 1496957387.184300, 1.542136, 1.000000, 48.862583, 22.346838, 13.586633, -34.680851 +-41.5448, 19.4831, -28.226371, 4.613889, 0.727714, -0.061553, 0.032517, 1496957387.193900, 1.539033, 1.000000, 48.908722, 22.359045, 13.586633, -33.872341 +-41.5391, 19.5309, -28.226925, 4.613889, 0.989992, -0.061553, 0.000000, 1496957387.204500, 1.535983, 1.000000, 48.954861, 22.359045, 13.624781, -33.872341 +-41.5332, 19.5787, -28.227548, 4.625000, 0.698617, -0.060016, 0.033244, 1496957387.214000, 1.533023, 1.000000, 49.001111, 22.395666, 13.624781, -33.042553 +-41.5271, 19.6266, -28.228154, 4.625000, 0.596307, -0.060016, 0.000000, 1496957387.224500, 1.530091, 1.000000, 49.047361, 22.395666, 13.609522, -33.042553 +-41.5208, 19.6745, -28.228888, 4.633333, 0.576490, -0.058520, 0.032286, 1496957387.234100, 1.527188, 1.000000, 49.093694, 22.359045, 13.609522, -32.234043 +-41.5143, 19.7226, -28.229679, 4.633333, 0.751471, -0.058520, 0.000000, 1496957387.243500, 1.524353, 1.000000, 49.140028, 22.359045, 13.643091, -32.234043 +-41.5077, 19.7707, -28.230541, 4.647222, 0.956195, -0.056948, 0.033836, 1496957387.253900, 1.521574, 1.000000, 49.186500, 22.346838, 13.643091, -31.382978 +-41.5009, 19.8188, -28.231499, 4.647222, 0.900220, -0.056948, 0.000000, 1496957387.264500, 1.518740, 1.000000, 49.232972, 22.346838, 13.646143, -31.382978 +-41.494, 19.8671, -28.232394, 4.663889, 0.894489, -0.055417, 0.032826, 1496957387.274000, 1.515998, 1.000000, 49.279611, 22.298008, 13.646143, -30.553192 +-41.4868, 19.9155, -28.233430, 4.663889, 0.758757, -0.055417, 0.000000, 1496957387.284600, 1.513275, 1.000000, 49.326250, 22.298008, 13.618677, -30.553192 +-41.4796, 19.9639, -28.234431, 4.677778, 0.760157, -0.053927, 0.031848, 1496957387.294100, 1.510550, 1.000000, 49.373028, 22.175936, 13.618677, -29.744680 +-41.4722, 20.0123, -28.235463, 4.677778, 0.756193, -0.053927, 0.000000, 1496957387.303600, 1.507894, 1.000000, 49.419806, 22.175936, 13.636988, -29.744680 +-41.4646, 20.0608, -28.236450, 4.683333, 0.760479, -0.052400, 0.032605, 1496957387.314200, 1.505252, 1.000000, 49.466639, 22.029449, 13.636988, -28.914894 +-41.4569, 20.1094, -28.237483, 4.683333, 0.516187, -0.052400, 0.000000, 1496957387.323700, 1.502645, 1.000000, 49.513472, 22.029449, 13.665980, -28.914894 +-41.4491, 20.158, -28.238389, 4.691667, 0.684343, -0.050953, 0.030840, 1496957387.334200, 1.500083, 1.000000, 49.560389, 22.017242, 13.665980, -28.127659 +-41.4412, 20.2067, -28.239304, 4.691667, 0.655255, -0.050953, 0.000000, 1496957387.343800, 1.497531, 1.000000, 49.607306, 22.017242, 13.640039, -28.127659 +-41.4331, 20.2555, -28.240141, 4.702778, 0.715566, -0.049508, 0.030731, 1496957387.354200, 1.494964, 1.000000, 49.654333, 22.017242, 13.640039, -27.340425 +-41.425, 20.3043, -28.240774, 4.702778, 0.574285, -0.049508, 0.000000, 1496957387.363800, 1.492479, 1.000000, 49.701361, 22.017242, 13.667506, -27.340425 +-41.4166, 20.3532, -28.241604, 4.713889, 0.636295, -0.048142, 0.028969, 1496957387.374300, 1.489998, 1.000000, 49.748500, 21.944000, 13.667506, -26.595745 +-41.4082, 20.4021, -28.242218, 4.713889, 0.637522, -0.048142, 0.000000, 1496957387.383800, 1.487519, 1.000000, 49.795639, 21.944000, 13.644617, -26.595745 +-41.3996, 20.4511, -28.242958, 4.719444, 0.721080, -0.046739, 0.029730, 1496957387.394300, 1.485102, 1.000000, 49.842833, 21.870756, 13.644617, -25.829786 +-41.3909, 20.5001, -28.243461, 4.719444, 0.703592, -0.046739, 0.000000, 1496957387.403900, 1.482698, 1.000000, 49.890028, 21.870756, 13.586633, -25.829786 +-41.3821, 20.5492, -28.244092, 4.727778, 0.633534, -0.045337, 0.029646, 1496957387.413600, 1.480336, 1.000000, 49.937306, 21.844816, 13.586633, -25.063829 +-41.3731, 20.5984, -28.244481, 4.727778, 0.653605, -0.045337, 0.000000, 1496957387.424200, 1.477996, 1.000000, 49.984583, 21.844816, 13.647669, -25.063829 +-41.364, 20.6476, -28.244886, 4.733333, 0.531107, -0.043976, 0.028760, 1496957387.433600, 1.475723, 1.000000, 50.031917, 21.858549, 13.647669, -24.319149 +-41.3548, 20.6968, -28.245265, 4.733333, 0.537458, -0.043976, 0.000000, 1496957387.444200, 1.473451, 1.000000, 50.079250, 21.858549, 13.611048, -24.319149 +-41.3455, 20.746, -28.245466, 4.733333, 0.225774, -0.042655, 0.027912, 1496957387.453800, 1.471244, 1.000000, 50.126583, 21.771572, 13.611048, -23.595745 +-41.3361, 20.7953, -28.245811, 4.733333, 0.491908, -0.042655, 0.000000, 1496957387.464300, 1.469022, 1.000000, 50.173917, 21.771572, 13.662929, -23.595745 +-41.3265, 20.8447, -28.245969, 4.733333, 0.470705, -0.041335, 0.027887, 1496957387.473800, 1.466770, 1.000000, 50.221250, 21.820402, 13.662929, -22.872341 +-41.3167, 20.8941, -28.246252, 4.733333, 0.692841, -0.041335, 0.000000, 1496957387.484300, 1.464638, 1.000000, 50.268583, 21.820402, 13.691920, -22.872341 +-41.3069, 20.9435, -28.246425, 4.736111, 0.467415, -0.040094, 0.026209, 1496957387.493800, 1.462446, 1.000000, 50.315944, 21.931791, 13.691920, -22.191490 +-41.2969, 20.9928, -28.246458, 4.736111, -0.139081, -0.040094, 0.000000, 1496957387.504300, 1.460301, 1.000000, 50.363306, 21.931791, 13.612574, -22.191490 +-41.2768, 21.0917, -28.246701, 4.752778, 0.539068, -0.038892, 0.025281, 1496957387.513800, 1.456029, 1.000000, 50.410833, 21.857023, 13.612574, -21.531916 +-41.2768, 21.0917, -28.246701, 4.752778, 0.539068, -0.038892, 0.000000, 1496957387.524300, 1.456029, 1.000000, 50.458361, 21.857023, 13.624781, -21.531916 +-41.2665, 21.1413, -28.246660, 4.780556, 0.988976, -0.037885, 0.021066, 1496957387.533800, 1.453911, 1.000000, 50.506167, 21.881437, 13.624781, -20.978724 +-41.2561, 21.1909, -28.246869, 4.780556, 0.767240, -0.037885, 0.000000, 1496957387.544300, 1.451869, 1.000000, 50.553972, 21.881437, 13.582055, -20.978724 +-41.2456, 21.2405, -28.246778, 4.800000, 0.599861, -0.036995, 0.018549, 1496957387.553900, 1.449962, 1.000000, 50.601972, 21.869230, 13.582055, -20.489361 +-41.2351, 21.2902, -28.246915, 4.800000, 0.455939, -0.036995, 0.000000, 1496957387.564400, 1.448062, 1.000000, 50.649972, 21.869230, 13.638514, -20.489361 +-41.2245, 21.3399, -28.246964, 4.802778, 0.373579, -0.036105, 0.018528, 1496957387.574300, 1.446123, 1.000000, 50.698000, 21.870756, 13.638514, -20.000000 +-41.2138, 21.3897, -28.247167, 4.802778, 0.699985, -0.036105, 0.000000, 1496957387.583800, 1.444221, 1.000000, 50.746028, 21.870756, 13.579003, -20.000000 +-41.203, 21.4396, -28.247446, 4.805555, 0.804778, -0.035486, 0.012876, 1496957387.594400, 1.442350, 1.000000, 50.794083, 21.857023, 13.579003, -19.659575 +-41.1922, 21.4895, -28.247728, 4.805555, 0.676479, -0.035486, 0.000000, 1496957387.603900, 1.440530, 1.000000, 50.842139, 21.857023, 13.667506, -19.659575 +-41.1811, 21.5394, -28.248047, 4.813889, 0.621327, -0.034984, 0.010440, 1496957387.614500, 1.438731, 1.000000, 50.890278, 22.005035, 13.667506, -19.382978 +-41.17, 21.5894, -28.248437, 4.813889, 0.649293, -0.034984, 0.000000, 1496957387.624200, 1.436924, 1.000000, 50.938417, 22.005035, 13.650721, -19.382978 +-41.1587, 21.6395, -28.248931, 4.822222, 0.787443, -0.034636, 0.007214, 1496957387.633700, 1.435180, 1.000000, 50.986639, 21.857023, 13.650721, -19.191490 +-41.1474, 21.6896, -28.249423, 4.822222, 0.586464, -0.034636, 0.000000, 1496957387.644200, 1.433468, 1.000000, 51.034861, 21.857023, 13.607996, -19.191490 +-41.1359, 21.7397, -28.250044, 4.827778, 0.559621, -0.034288, 0.007204, 1496957387.653800, 1.431747, 1.000000, 51.083139, 21.857023, 13.607996, -19.000000 +-41.1244, 21.7899, -28.250736, 4.827778, 0.539862, -0.034288, 0.000000, 1496957387.664400, 1.430021, 1.000000, 51.131417, 21.857023, 13.649195, -19.000000 +-41.1127, 21.8401, -28.251438, 4.836111, 0.533389, -0.034133, 0.003196, 1496957387.673900, 1.428381, 1.000000, 51.179778, 21.869230, 13.649195, -18.914894 +-41.1009, 21.8903, -28.252223, 4.836111, 0.605802, -0.034133, 0.000000, 1496957387.684400, 1.426696, 1.000000, 51.228139, 21.869230, 13.591210, -18.914894 +-41.0889, 21.9406, -28.253018, 4.847222, 0.588172, -0.034017, 0.002391, 1496957387.694000, 1.425077, 1.000000, 51.276611, 21.844816, 13.591210, -18.851065 +-41.0769, 21.991, -28.253802, 4.847222, 0.467934, -0.034017, 0.000000, 1496957387.704500, 1.423450, 1.000000, 51.325083, 21.844816, 13.611048, -18.851065 +-41.0648, 22.0413, -28.254622, 4.858333, 0.462557, -0.033863, 0.003181, 1496957387.713900, 1.421839, 1.000000, 51.373667, 21.870756, 13.611048, -18.765957 +-41.0525, 22.0917, -28.255375, 4.858333, 0.392555, -0.033863, 0.000000, 1496957387.724500, 1.420203, 1.000000, 51.422250, 21.870756, 13.611048, -18.765957 +-41.0402, 22.142, -28.256179, 4.869444, 0.282797, -0.033670, 0.003966, 1496957387.734000, 1.418601, 1.000000, 51.470944, 21.783779, 13.611048, -18.659575 +-41.0277, 22.1925, -28.256908, 4.869444, 0.505095, -0.033670, 0.000000, 1496957387.744600, 1.416968, 1.000000, 51.519639, 21.783779, 13.601892, -18.659575 +-41.0152, 22.2429, -28.257592, 4.877778, 0.464260, -0.033515, 0.003167, 1496957387.754100, 1.415246, 1.000000, 51.568417, 21.771572, 13.601892, -18.574469 +-41.0025, 22.2935, -28.258285, 4.877778, 0.504525, -0.033515, 0.000000, 1496957387.764600, 1.413608, 1.000000, 51.617194, 21.771572, 13.664454, -18.574469 +-40.9897, 22.344, -28.258983, 4.886111, 0.363670, -0.033438, 0.001581, 1496957387.774100, 1.411930, 1.000000, 51.666056, 21.710537, 13.664454, -18.531916 +-40.9768, 22.3945, -28.259715, 4.886111, 0.444502, -0.033438, 0.000000, 1496957387.783500, 1.410303, 1.000000, 51.714917, 21.710537, 13.620203, -18.531916 +-40.9638, 22.4451, -28.260445, 4.891667, 0.362502, -0.033284, 0.003158, 1496957387.794100, 1.408666, 1.000000, 51.763833, 21.637293, 13.620203, -18.446808 +-40.9507, 22.4956, -28.261062, 4.891667, 0.365955, -0.033284, 0.000000, 1496957387.803500, 1.407019, 1.000000, 51.812750, 21.637293, 13.594263, -18.446808 +-40.9376, 22.5462, -28.261728, 4.897222, 0.342322, -0.033168, 0.002366, 1496957387.814000, 1.405330, 1.000000, 51.861722, 21.576258, 13.594263, -18.382978 +-40.9243, 22.5969, -28.262329, 4.897222, 0.328868, -0.033168, 0.000000, 1496957387.824500, 1.403643, 1.000000, 51.910694, 21.576258, 13.612574, -18.382978 +-40.911, 22.6475, -28.262924, 4.902778, 0.285527, -0.033090, 0.001575, 1496957387.834000, 1.401956, 1.000000, 51.959722, 21.564051, 13.612574, -18.340425 +-40.8975, 22.6982, -28.263688, 4.902778, 0.480656, -0.033090, 0.000000, 1496957387.844500, 1.400274, 1.000000, 52.008750, 21.564051, 13.604944, -18.340425 +-40.8839, 22.7489, -28.264305, 4.911111, 0.591827, -0.033052, 0.000786, 1496957387.854000, 1.398550, 1.000000, 52.057861, 21.564051, 13.604944, -18.319149 +-40.8702, 22.7997, -28.264997, 4.911111, 0.513317, -0.033052, 0.000000, 1496957387.864600, 1.396829, 1.000000, 52.106972, 21.564051, 13.606470, -18.319149 +-40.8564, 22.8505, -28.265724, 4.922222, 0.503157, -0.033013, 0.000784, 1496957387.874000, 1.395178, 1.000000, 52.156194, 21.271076, 13.606470, -18.297873 +-40.8425, 22.9013, -28.266295, 4.922222, 0.496782, -0.033013, 0.000000, 1496957387.884500, 1.393527, 1.000000, 52.205417, 21.271076, 13.647669, -18.297873 +-40.8284, 22.9521, -28.266907, 4.927778, 0.407277, -0.032897, 0.002351, 1496957387.894100, 1.391817, 1.000000, 52.254694, 20.856031, 13.647669, -18.234043 +-40.8143, 23.003, -28.267531, 4.927778, 0.383818, -0.032897, 0.000000, 1496957387.903500, 1.390120, 1.000000, 52.303972, 20.856031, 13.603418, -18.234043 +-40.8, 23.0539, -28.268080, 4.938889, 0.645873, -0.032897, 0.000000, 1496957387.914600, 1.388406, 1.000000, 52.353361, 20.428778, 13.603418, -18.234043 +-40.7857, 23.1048, -28.268714, 4.938889, 0.467676, -0.032897, 0.000000, 1496957387.924100, 1.386714, 1.000000, 52.402750, 20.428778, 13.557641, -18.234043 +-40.7712, 23.1558, -28.269324, 4.944445, 0.417103, -0.032782, 0.002343, 1496957387.934600, 1.385011, 1.000000, 52.452194, 20.074770, 13.557641, -18.170214 +-40.7567, 23.2068, -28.270020, 4.944445, 0.506879, -0.032782, 0.000000, 1496957387.944200, 1.383288, 1.000000, 52.501639, 20.074770, 13.667506, -18.170214 +-40.7421, 23.2578, -28.270876, 4.955555, 0.618039, -0.032666, 0.002337, 1496957387.953800, 1.381593, 1.000000, 52.551194, 19.562065, 13.667506, -18.106382 +-40.7274, 23.3089, -28.271609, 4.955555, 0.597372, -0.032666, 0.000000, 1496957387.964300, 1.379896, 1.000000, 52.600750, 19.562065, 13.614100, -18.106382 +-40.7126, 23.3601, -28.272582, 4.966667, 0.582110, -0.032511, 0.003109, 1496957387.973800, 1.378176, 1.000000, 52.650417, 19.122606, 13.614100, -18.021276 +-40.6978, 23.4112, -28.273541, 4.966667, 0.619645, -0.032511, 0.000000, 1496957387.984300, 1.376468, 1.000000, 52.700083, 19.122606, 13.598841, -18.021276 +-40.6828, 23.4624, -28.274598, 4.972222, 0.592739, -0.032318, 0.003882, 1496957387.993900, 1.374744, 1.000000, 52.749806, 18.620584, 13.598841, -17.914894 +-40.6678, 23.5137, -28.275727, 4.972222, 0.681983, -0.032318, 0.000000, 1496957388.004400, 1.373098, 1.000000, 52.799528, 18.620584, 13.626307, -17.914894 +-40.6528, 23.565, -28.276841, 4.983333, 0.473151, -0.032048, 0.005422, 1496957388.013900, 1.371340, 1.000000, 52.849361, 17.863737, 13.626307, -17.765957 +-40.6376, 23.6163, -28.277711, 4.983333, 0.503692, -0.032048, 0.000000, 1496957388.024400, 1.369663, 1.000000, 52.899194, 17.863737, 13.571374, -17.765957 +-40.6225, 23.6676, -28.278730, 5.002778, 0.157030, -0.031662, 0.007714, 1496957388.033900, 1.367948, 1.000000, 52.949222, 16.716259, 13.571374, -17.553192 +-40.6071, 23.719, -28.279597, 5.002778, 0.408942, -0.031662, 0.000000, 1496957388.044500, 1.366201, 1.000000, 52.999250, 16.716259, 13.629358, -17.553192 +-40.5918, 23.7705, -28.280410, 5.016667, 0.542493, -0.031161, 0.009998, 1496957388.054100, 1.364531, 1.000000, 53.049417, 16.130312, 13.629358, -17.276596 +-40.5763, 23.8219, -28.281195, 5.016667, 0.395128, -0.031161, 0.000000, 1496957388.063500, 1.362785, 1.000000, 53.099583, 16.130312, 13.636988, -17.276596 +-40.5607, 23.8734, -28.281862, 5.025000, 0.578447, -0.030659, 0.009979, 1496957388.074000, 1.361174, 1.000000, 53.149833, 15.690852, 13.636988, -17.000000 +-40.5459, 23.9254, -28.282457, 5.025000, 0.540362, -0.030659, 0.000000, 1496957388.084400, 1.359292, 1.000000, 53.200083, 15.690852, 13.600367, -17.000000 +-40.5319, 23.9781, -28.283052, 5.027778, 0.339721, -0.030042, 0.012271, 1496957388.093900, 1.357707, 1.000000, 53.250361, 15.263599, 13.600367, -16.659575 +-40.5178, 24.0309, -28.283465, 5.027778, 0.321805, -0.030042, 0.000000, 1496957388.104400, 1.356050, 1.000000, 53.300639, 15.263599, 13.585107, -16.659575 +-40.5036, 24.0836, -28.283899, 5.033333, 0.331705, -0.029387, 0.013020, 1496957388.114000, 1.354391, 1.000000, 53.350972, 15.458915, 13.585107, -16.297873 +-40.4893, 24.1364, -28.284192, 5.033333, 0.213283, -0.029387, 0.000000, 1496957388.124500, 1.352740, 1.000000, 53.401306, 15.458915, 13.589684, -16.297873 +-40.4749, 24.1891, -28.284373, 5.030556, 0.178793, -0.028693, 0.013789, 1496957388.134100, 1.351108, 1.000000, 53.451611, 15.263599, 13.589684, -15.914893 +-40.4604, 24.2419, -28.284667, 5.030556, 0.179068, -0.028693, 0.000000, 1496957388.143500, 1.349521, 1.000000, 53.501917, 15.263599, 13.630884, -15.914893 +-40.4459, 24.2947, -28.284772, 5.038889, 0.447165, -0.028000, 0.013762, 1496957388.154100, 1.347924, 1.000000, 53.552306, 15.263599, 13.630884, -15.531915 +-40.4312, 24.3475, -28.284909, 5.038889, 0.245509, -0.028000, 0.000000, 1496957388.163500, 1.346390, 1.000000, 53.602694, 15.263599, 13.624781, -15.531915 +-40.4165, 24.4004, -28.285097, 5.044445, 0.272055, -0.027191, 0.016032, 1496957388.174100, 1.344852, 1.000000, 53.653139, 15.288014, 13.624781, -15.085107 +-40.4017, 24.4532, -28.285180, 5.044445, 0.457265, -0.027191, 0.000000, 1496957388.184500, 1.343344, 1.000000, 53.703583, 15.288014, 13.580529, -15.085107 +-40.3869, 24.5061, -28.285372, 5.050000, 0.282923, -0.026383, 0.016009, 1496957388.194000, 1.341825, 1.000000, 53.754083, 15.324636, 13.580529, -14.638298 +-40.3719, 24.559, -28.285395, 5.050000, 0.397730, -0.026383, 0.000000, 1496957388.204600, 1.340319, 1.000000, 53.804583, 15.324636, 13.633936, -14.638298 +-40.3568, 24.6118, -28.285413, 5.052778, 0.241392, -0.025613, 0.015233, 1496957388.214100, 1.338887, 1.000000, 53.855111, 15.336843, 13.633936, -14.212766 +-40.3416, 24.6647, -28.285148, 5.052778, 0.195655, -0.025613, 0.000000, 1496957388.223600, 1.337465, 1.000000, 53.905639, 15.336843, 13.598841, -14.212766 +-40.3263, 24.7175, -28.285155, 5.055555, -0.076998, -0.024843, 0.015220, 1496957388.234100, 1.336091, 1.000000, 53.956194, 15.288014, 13.598841, -13.787234 +-40.3108, 24.7704, -28.284849, 5.055555, 0.121142, -0.024843, 0.000000, 1496957388.243500, 1.334740, 1.000000, 54.006750, 15.288014, 13.635462, -13.787234 +-40.2953, 24.8232, -28.284824, 5.058333, 0.176833, -0.024036, 0.015967, 1496957388.254000, 1.333428, 1.000000, 54.057333, 15.300221, 13.635462, -13.340425 +-40.2797, 24.8761, -28.284576, 5.058333, 0.342926, -0.024036, 0.000000, 1496957388.264500, 1.332145, 1.000000, 54.107917, 15.300221, 13.579003, -13.340425 +-40.2639, 24.929, -28.284446, 5.061111, 0.347434, -0.023305, 0.014434, 1496957388.274200, 1.330890, 1.000000, 54.158528, 15.300221, 13.579003, -12.936171 +-40.2481, 24.9818, -28.284379, 5.061111, 0.169193, -0.023305, 0.000000, 1496957388.283700, 1.329665, 1.000000, 54.209139, 15.300221, 13.601892, -12.936171 +-40.2322, 25.0347, -28.284363, 5.063889, 0.302486, -0.022575, 0.014422, 1496957388.294200, 1.328458, 1.000000, 54.259778, 15.275806, 13.601892, -12.531915 +-40.2162, 25.0876, -28.284404, 5.063889, 0.456228, -0.022575, 0.000000, 1496957388.303700, 1.327247, 1.000000, 54.310417, 15.275806, 13.607996, -12.531915 +-40.2001, 25.1405, -28.284468, 5.066667, 0.319282, -0.021883, 0.013652, 1496957388.314200, 1.326066, 1.000000, 54.361083, 15.288014, 13.607996, -12.148936 +-40.184, 25.1934, -28.284550, 5.066667, 0.325634, -0.021883, 0.000000, 1496957388.323800, 1.324944, 1.000000, 54.411750, 15.288014, 13.612574, -12.148936 +-40.1678, 25.2463, -28.284484, 5.075000, 0.301327, -0.021153, 0.014383, 1496957388.334200, 1.323830, 1.000000, 54.462500, 15.361258, 13.612574, -11.744680 +-40.1515, 25.2992, -28.284568, 5.075000, 0.076314, -0.021153, 0.000000, 1496957388.343700, 1.322662, 1.000000, 54.513250, 15.361258, 13.612574, -11.744680 +-40.1352, 25.3521, -28.284545, 5.072222, 0.079386, -0.020462, 0.013630, 1496957388.354300, 1.321636, 1.000000, 54.563972, 15.263599, 13.612574, -11.361702 +-40.1188, 25.4051, -28.284669, 5.072222, 0.196848, -0.020462, 0.000000, 1496957388.363800, 1.320552, 1.000000, 54.614694, 15.263599, 13.653772, -11.361702 +-40.1024, 25.458, -28.284687, 5.069445, 0.267558, -0.019771, 0.013635, 1496957388.374400, 1.319467, 1.000000, 54.665389, 15.263599, 13.653772, -10.978724 +-40.0858, 25.5109, -28.284617, 5.069445, 0.141414, -0.019771, 0.000000, 1496957388.384500, 1.318451, 1.000000, 54.716083, 15.263599, 13.583581, -10.978724 +-40.0691, 25.5639, -28.284668, 5.072222, 0.288767, -0.019118, 0.012868, 1496957388.394100, 1.317462, 1.000000, 54.766806, 15.336843, 13.583581, -10.617022 +-40.0524, 25.6168, -28.284429, 5.072222, 0.037801, -0.019118, 0.000000, 1496957388.405200, 1.316438, 1.000000, 54.817528, 15.336843, 13.621729, -10.617022 +-40.0356, 25.6696, -28.284490, 5.075000, 0.134992, -0.018427, 0.013614, 1496957388.414500, 1.315450, 1.000000, 54.868278, 15.300221, 13.621729, -10.234042 +-40.0186, 25.7226, -28.284394, 5.075000, 0.157506, -0.018427, 0.000000, 1496957388.424000, 1.314459, 1.000000, 54.919028, 15.300221, 13.577477, -10.234042 +-40.0016, 25.7755, -28.284354, 5.075000, 0.252635, -0.018427, 0.000000, 1496957388.434500, 1.313498, 1.000000, 54.969778, 15.336843, 13.577477, -10.234042 +-39.9846, 25.8284, -28.284368, 5.075000, 0.176597, -0.017736, 0.013611, 1496957388.444000, 1.312547, 1.000000, 55.020528, 15.336843, 13.641565, -9.851064 +-39.9675, 25.8813, -28.284435, 5.075000, 0.168988, -0.017736, 0.000000, 1496957388.454600, 1.311576, 1.000000, 55.071278, 15.373465, 13.641565, -9.851064 +-39.9503, 25.9341, -28.284468, 5.075000, 0.106871, -0.017007, 0.014365, 1496957388.464200, 1.310653, 1.000000, 55.122028, 15.373465, 13.569848, -9.446809 +-39.9331, 25.987, -28.284637, 5.075000, 0.045889, -0.017007, 0.000000, 1496957388.473600, 1.309736, 1.000000, 55.172778, 15.324636, 13.569848, -9.446809 +-39.9158, 26.0399, -28.284674, 5.077778, -0.076528, -0.016317, 0.013598, 1496957388.484200, 1.308838, 1.000000, 55.223555, 15.324636, 13.650721, -9.063829 +-39.8985, 26.0927, -28.284876, 5.080555, 0.122055, -0.015626, 0.013589, 1496957388.493800, 1.307991, 1.000000, 55.274361, 15.312428, 13.650721, -8.680851 +-39.8812, 26.1456, -28.285121, 5.080555, 0.319397, -0.015626, 0.000000, 1496957388.504300, 1.307078, 1.000000, 55.325167, 15.312428, 13.630884, -8.680851 +-39.8637, 26.1985, -28.285382, 5.086111, 0.322589, -0.015013, 0.012064, 1496957388.513800, 1.306230, 1.000000, 55.376028, 15.300221, 13.630884, -8.340425 +-39.8463, 26.2514, -28.285744, 5.086111, 0.226022, -0.015013, 0.000000, 1496957388.524400, 1.305362, 1.000000, 55.426889, 15.300221, 13.659877, -8.340425 +-39.8287, 26.3043, -28.286107, 5.088889, 0.187810, -0.014476, 0.010548, 1496957388.533900, 1.304535, 1.000000, 55.477778, 15.336843, 13.659877, -8.042553 +-39.8111, 26.3572, -28.286542, 5.088889, 0.173945, -0.014476, 0.000000, 1496957388.544400, 1.303735, 1.000000, 55.528667, 15.336843, 13.591210, -8.042553 +-39.7934, 26.4101, -28.286960, 5.088889, 0.173559, -0.013978, 0.009794, 1496957388.554000, 1.302887, 1.000000, 55.579555, 15.288014, 13.591210, -7.765957 +-39.7757, 26.463, -28.287509, 5.088889, 0.169855, -0.013978, 0.000000, 1496957388.564600, 1.302132, 1.000000, 55.630444, 15.288014, 13.647669, -7.765957 +-39.7579, 26.5159, -28.288065, 5.088889, 0.244151, -0.013978, 0.000000, 1496957388.574100, 1.301391, 1.000000, 55.681333, 15.263599, 13.647669, -7.765957 +-39.7401, 26.5688, -28.288702, 5.097222, 0.191991, -0.013594, 0.007521, 1496957388.583600, 1.300630, 1.000000, 55.732306, 15.263599, 13.644617, -7.553192 +-39.7221, 26.6217, -28.289348, 5.097222, 0.076975, -0.013288, 0.006016, 1496957388.594200, 1.299891, 1.000000, 55.783278, 15.324636, 13.644617, -7.382979 +-39.7042, 26.6746, -28.290019, 5.097222, 0.129998, -0.013288, 0.000000, 1496957388.603600, 1.299196, 1.000000, 55.834250, 15.324636, 13.640039, -7.382979 +-39.6862, 26.7275, -28.290774, 5.097222, 0.049769, -0.013019, 0.005264, 1496957388.614200, 1.298482, 1.000000, 55.885222, 15.288014, 13.640039, -7.234043 +-39.6682, 26.7804, -28.291520, 5.097222, 0.109897, -0.013019, 0.000000, 1496957388.623700, 1.297807, 1.000000, 55.936194, 15.288014, 13.626307, -7.234043 +-39.6501, 26.8333, -28.292379, 5.102778, 0.213974, -0.012789, 0.004507, 1496957388.634200, 1.297104, 1.000000, 55.987222, 15.214770, 13.626307, -7.106383 +-39.632, 26.8862, -28.293335, 5.102778, 0.191140, -0.012789, 0.000000, 1496957388.643600, 1.296449, 1.000000, 56.038250, 15.214770, 13.632410, -7.106383 +-39.614, 26.9392, -28.294236, 5.105556, 0.178440, -0.012598, 0.003753, 1496957388.654100, 1.295729, 1.000000, 56.089306, 15.239185, 13.632410, -7.000000 +-39.5959, 26.9921, -28.295089, 5.105556, 0.234418, -0.012598, 0.000000, 1496957388.663500, 1.295071, 1.000000, 56.140361, 15.239185, 13.714808, -7.000000 +-39.5777, 27.045, -28.295839, 5.116667, 0.103050, -0.012445, 0.002996, 1496957388.674000, 1.294448, 1.000000, 56.191528, 15.263599, 13.714808, -6.914894 +-39.5596, 27.098, -28.296497, 5.116667, -0.028404, -0.012445, 0.000000, 1496957388.683500, 1.293782, 1.000000, 56.242694, 15.263599, 13.911651, -6.914894 +-39.5414, 27.1509, -28.297119, 5.113889, -0.213429, -0.012291, 0.002998, 1496957388.694100, 1.293100, 1.000000, 56.293833, 15.349051, 13.911651, -6.829787 +-39.5233, 27.2038, -28.297625, 5.113889, -0.277529, -0.012291, 0.000000, 1496957388.703600, 1.292451, 1.000000, 56.344972, 15.349051, 14.373999, -6.829787 +-39.5051, 27.2567, -28.298009, 5.111111, -0.062481, -0.012100, 0.003749, 1496957388.714100, 1.291824, 1.000000, 56.396083, 15.288014, 14.373999, -6.723404 +-39.4869, 27.3095, -28.298351, 5.111111, -0.063530, -0.012100, 0.000000, 1496957388.723600, 1.291150, 1.000000, 56.447194, 15.288014, 14.848555, -6.723404 +-39.4687, 27.3624, -28.298696, 5.113889, -0.009283, -0.011946, 0.002997, 1496957388.734200, 1.290490, 1.000000, 56.498333, 15.275806, 14.848555, -6.638298 +-39.4505, 27.4153, -28.298909, 5.113889, 0.105293, -0.011946, 0.000000, 1496957388.743700, 1.289843, 1.000000, 56.549472, 15.275806, 15.265125, -6.638298 +-39.4322, 27.4682, -28.299146, 5.113889, 0.034607, -0.011946, 0.000000, 1496957388.754200, 1.289184, 1.000000, 56.600611, 15.190356, 15.265125, -6.638298 +-39.4139, 27.5211, -28.299295, 5.113889, 0.082542, -0.011755, 0.003747, 1496957388.763700, 1.288510, 1.000000, 56.651750, 15.190356, 15.617609, -6.531915 +-39.3956, 27.5739, -28.299481, 5.113889, 0.018046, -0.011755, 0.000000, 1496957388.774200, 1.287850, 1.000000, 56.702889, 15.263599, 15.617609, -6.531915 +-39.3773, 27.6268, -28.299725, 5.111111, -0.009799, -0.011525, 0.004498, 1496957388.783700, 1.287219, 1.000000, 56.754000, 15.263599, 15.965514, -6.404255 +-39.3589, 27.6797, -28.299807, 5.111111, 0.027323, -0.011525, 0.000000, 1496957388.794300, 1.286549, 1.000000, 56.805111, 15.263599, 15.965514, -6.404255 +-39.3404, 27.7325, -28.299944, 5.108333, 0.027346, -0.011257, 0.005250, 1496957388.803900, 1.285890, 1.000000, 56.856194, 15.263599, 16.238651, -6.255319 +-39.322, 27.7854, -28.300090, 5.108333, 0.016177, -0.011257, 0.000000, 1496957388.814500, 1.285209, 1.000000, 56.907278, 15.226978, 16.238651, -6.255319 +-39.3034, 27.8382, -28.300253, 5.108333, 0.100005, -0.010988, 0.005250, 1496957388.824000, 1.284550, 1.000000, 56.958361, 15.226978, 16.533150, -6.106383 +-39.2848, 27.891, -28.300419, 5.108333, 0.023364, -0.010988, 0.000000, 1496957388.833500, 1.283913, 1.000000, 57.009444, 15.288014, 16.533150, -6.106383 +-39.2662, 27.9438, -28.300615, 5.105556, 0.089776, -0.010720, 0.005253, 1496957388.844100, 1.283286, 1.000000, 57.060500, 15.288014, 16.784924, -5.957447 +-39.2475, 27.9966, -28.300844, 5.105556, 0.106546, -0.010720, 0.000000, 1496957388.853600, 1.282684, 1.000000, 57.111555, 15.263599, 16.784924, -5.957447 +-39.2287, 28.0495, -28.301063, 5.105556, 0.211717, -0.010375, 0.006753, 1496957388.864200, 1.282072, 1.000000, 57.162611, 15.263599, 17.038223, -5.765957 +-39.21, 28.1023, -28.301354, 5.105556, 0.065141, -0.010375, 0.000000, 1496957388.873600, 1.281455, 1.000000, 57.213667, 15.312428, 17.038223, -5.765957 +-39.1912, 28.1551, -28.301636, 5.108333, 0.040900, -0.010069, 0.005999, 1496957388.884800, 1.280855, 1.000000, 57.264750, 15.312428, 17.413595, -5.595745 +-39.1724, 28.2078, -28.301996, 5.108333, -0.072164, -0.010069, 0.000000, 1496957388.894400, 1.280260, 1.000000, 57.315833, 15.263599, 17.413595, -5.595745 +-39.1535, 28.2606, -28.302488, 5.105556, 0.055050, -0.009763, 0.006002, 1496957388.903900, 1.279718, 1.000000, 57.366889, 15.263599, 17.714199, -5.425532 +-39.1346, 28.3134, -28.302969, 5.105556, 0.133377, -0.009763, 0.000000, 1496957388.915100, 1.279171, 1.000000, 57.417944, 15.275806, 17.714199, -5.425532 +-39.1156, 28.3662, -28.303616, 5.108333, 0.145260, -0.009456, 0.005999, 1496957388.924500, 1.278642, 1.000000, 57.469028, 15.275806, 18.139925, -5.255319 +-39.0966, 28.4189, -28.304224, 5.108333, 0.052848, -0.009456, 0.000000, 1496957388.934100, 1.278123, 1.000000, 57.520111, 15.239185, 18.139925, -5.255319 +-39.0776, 28.4717, -28.304994, 5.111111, 0.130496, -0.009111, 0.006744, 1496957388.944600, 1.277606, 1.000000, 57.571222, 15.239185, 18.606852, -5.063830 +-39.0585, 28.5244, -28.305832, 5.111111, 0.112122, -0.009111, 0.000000, 1496957388.954200, 1.277131, 1.000000, 57.622333, 15.251392, 18.606852, -5.063830 +-39.0393, 28.5771, -28.306739, 5.111111, 0.142746, -0.008728, 0.007493, 1496957388.963700, 1.276684, 1.000000, 57.673444, 15.251392, 18.956284, -4.851064 +-39.02, 28.6299, -28.307694, 5.111111, 0.170049, -0.008728, 0.000000, 1496957388.974200, 1.276265, 1.000000, 57.724555, 15.263599, 18.956284, -4.851064 +-39.0007, 28.6826, -28.308733, 5.119444, 0.193849, -0.008307, 0.008229, 1496957388.983600, 1.275818, 1.000000, 57.775750, 15.263599, 19.331656, -4.617021 +-38.9814, 28.7353, -28.309651, 5.119444, -0.012920, -0.008307, 0.000000, 1496957388.994000, 1.275443, 1.000000, 57.826944, 15.251392, 19.331656, -4.617021 +-38.9619, 28.788, -28.310632, 5.113889, 0.049595, -0.007848, 0.008986, 1496957389.004500, 1.275058, 1.000000, 57.878083, 15.251392, 19.497978, -4.361702 +-38.9425, 28.8407, -28.311533, 5.113889, -0.038982, -0.007848, 0.000000, 1496957389.014000, 1.274723, 1.000000, 57.929222, 15.336843, 19.497978, -4.361702 +-38.923, 28.8935, -28.312365, 5.113889, -0.167943, -0.007350, 0.009734, 1496957389.024600, 1.274327, 1.000000, 57.980361, 15.336843, 19.769588, -4.085106 +-38.9034, 28.9461, -28.313160, 5.113889, -0.100019, -0.007350, 0.000000, 1496957389.034100, 1.273960, 1.000000, 58.031500, 15.288014, 19.769588, -4.085106 +-38.8839, 28.9987, -28.313831, 5.119444, -0.051233, -0.006814, 0.010471, 1496957389.043500, 1.273617, 1.000000, 58.082694, 15.288014, 19.987793, -3.787234 +-38.8643, 29.0513, -28.314469, 5.119444, -0.081063, -0.006814, 0.000000, 1496957389.054000, 1.273249, 1.000000, 58.133889, 15.263599, 19.987793, -3.787234 +-38.8446, 29.1039, -28.315109, 5.119444, -0.032454, -0.006239, 0.011218, 1496957389.064600, 1.272937, 1.000000, 58.185083, 15.263599, 20.091555, -3.468085 +-38.8249, 29.1565, -28.315731, 5.119444, -0.085204, -0.006239, 0.000000, 1496957389.074200, 1.272586, 1.000000, 58.236278, 15.458915, 20.091555, -3.468085 +-38.8053, 29.209, -28.316222, 5.116667, -0.111713, -0.005742, 0.009727, 1496957389.083500, 1.272264, 1.000000, 58.287444, 15.458915, 20.140383, -3.191489 +-38.7857, 29.2615, -28.316727, 5.116667, -0.151103, -0.005742, 0.000000, 1496957389.094100, 1.271944, 1.000000, 58.338611, 15.349051, 20.140383, -3.191489 +-38.7661, 29.314, -28.317200, 5.113889, -0.089690, -0.005206, 0.010481, 1496957389.103600, 1.271680, 1.000000, 58.389750, 15.349051, 20.157167, -2.893617 +-38.7464, 29.3666, -28.317624, 5.113889, -0.130722, -0.005206, 0.000000, 1496957389.114100, 1.271312, 1.000000, 58.440889, 15.251392, 20.157167, -2.893617 +-38.7268, 29.4191, -28.317969, 5.113889, 0.074519, -0.004632, 0.011229, 1496957389.124600, 1.270997, 1.000000, 58.492028, 15.251392, 20.157167, -2.574468 +-38.7072, 29.4716, -28.318376, 5.113889, -0.184575, -0.004632, 0.000000, 1496957389.134100, 1.270666, 1.000000, 58.543167, 15.226978, 20.157167, -2.574468 +-38.6876, 29.5241, -28.318614, 5.108333, -0.145764, -0.004019, 0.011990, 1496957389.143500, 1.270398, 1.000000, 58.594250, 15.226978, 20.238041, -2.234043 +-38.6681, 29.5766, -28.318974, 5.108333, -0.133849, -0.004019, 0.000000, 1496957389.154100, 1.270114, 1.000000, 58.645333, 15.312428, 20.238041, -2.234043 +-38.6485, 29.6291, -28.319148, 5.105556, -0.040773, -0.003407, 0.011996, 1496957389.163600, 1.269850, 1.000000, 58.696389, 15.312428, 20.334173, -1.893617 +-38.629, 29.6816, -28.319373, 5.105556, -0.114527, -0.003407, 0.000000, 1496957389.174100, 1.269556, 1.000000, 58.747444, 15.263599, 20.334173, -1.893617 +-38.6094, 29.734, -28.319567, 5.102778, -0.089326, -0.002794, 0.012002, 1496957389.183500, 1.269350, 1.000000, 58.798472, 15.263599, 20.459297, -1.553192 +-38.59, 29.7865, -28.319672, 5.102778, -0.300233, -0.002794, 0.000000, 1496957389.194000, 1.269145, 1.000000, 58.849500, 15.263599, 20.459297, -1.553192 +-38.5705, 29.8388, -28.319785, 5.091667, -0.558474, -0.002220, 0.011276, 1496957389.204600, 1.268956, 1.000000, 58.900417, 15.263599, 20.625620, -1.234043 +-38.551, 29.8912, -28.320017, 5.091667, -0.349935, -0.002220, 0.000000, 1496957389.214100, 1.268806, 1.000000, 58.951333, 15.312428, 20.625620, -1.234043 +-38.5314, 29.9435, -28.320163, 5.083333, -0.267958, -0.001761, 0.009036, 1496957389.223600, 1.268645, 1.000000, 59.002167, 15.312428, 20.836195, -0.978723 +-38.5119, 29.9958, -28.320413, 5.083333, -0.176871, -0.001761, 0.000000, 1496957389.234200, 1.268526, 1.000000, 59.053000, 15.214770, 20.836195, -0.978723 +-38.4923, 30.048, -28.320623, 5.080555, -0.232873, -0.001187, 0.011301, 1496957389.243700, 1.268396, 1.000000, 59.103805, 15.214770, 21.033035, -0.659574 +-38.4726, 30.1002, -28.320850, 5.080555, -0.296196, -0.001187, 0.000000, 1496957389.254200, 1.268369, 1.000000, 59.154611, 15.178149, 21.033035, -0.659574 +-38.453, 30.1524, -28.320960, 5.077778, -0.409741, -0.000765, 0.008292, 1496957389.263800, 1.268329, 1.000000, 59.205389, 15.178149, 21.139849, -0.425532 +-38.4332, 30.2045, -28.321183, 5.077778, -0.344898, -0.000765, 0.000000, 1496957389.274400, 1.268305, 1.000000, 59.256167, 15.275806, 21.139849, -0.425532 +-38.4135, 30.2565, -28.321511, 5.075000, -0.338184, -0.000306, 0.009050, 1496957389.284300, 1.268291, 1.000000, 59.306917, 15.275806, 21.159685, -0.170213 +-38.3937, 30.3085, -28.321743, 5.075000, -0.218997, -0.000306, 0.000000, 1496957389.293800, 1.268325, 1.000000, 59.357667, 15.092698, 21.159685, -0.170213 +-38.3739, 30.3605, -28.322171, 5.066667, -0.357587, 0.000077, 0.007554, 1496957389.304200, 1.268390, 1.000000, 59.408333, 15.092698, 21.216145, 0.042553 +-38.3541, 30.4124, -28.322651, 5.066667, -0.298005, 0.000077, 0.000000, 1496957389.313700, 1.268474, 1.000000, 59.459000, 15.288014, 21.216145, 0.042553 +-38.3342, 30.4643, -28.323117, 5.063889, -0.077400, 0.000536, 0.009070, 1496957389.324200, 1.268543, 1.000000, 59.509639, 15.288014, 21.208515, 0.297872 +-38.3144, 30.5162, -28.323698, 5.063889, -0.227095, 0.000536, 0.000000, 1496957389.333600, 1.268626, 1.000000, 59.560278, 15.214770, 21.208515, 0.297872 +-38.2945, 30.5681, -28.324323, 5.063889, -0.224098, 0.000880, 0.006803, 1496957389.344100, 1.268703, 1.000000, 59.610917, 15.214770, 21.261921, 0.489362 +-38.2746, 30.6199, -28.325023, 5.063889, -0.082125, 0.000880, 0.000000, 1496957389.354600, 1.268819, 1.000000, 59.661555, 15.263599, 21.261921, 0.489362 +-38.2548, 30.6717, -28.325773, 5.061111, -0.198347, 0.001148, 0.005294, 1496957389.364100, 1.268952, 1.000000, 59.712167, 15.263599, 21.292439, 0.638298 +-38.2349, 30.7235, -28.326573, 5.061111, -0.194199, 0.001148, 0.000000, 1496957389.373600, 1.269082, 1.000000, 59.762778, 15.226978, 21.292439, 0.638298 +-38.2151, 30.7753, -28.327393, 5.058333, -0.186612, 0.001493, 0.006810, 1496957389.384100, 1.269156, 1.000000, 59.813361, 15.226978, 21.216145, 0.829787 +-38.1953, 30.8271, -28.328169, 5.058333, -0.374377, 0.001493, 0.000000, 1496957389.393600, 1.269279, 1.000000, 59.863944, 15.300221, 21.216145, 0.829787 +-38.1755, 30.8787, -28.329081, 5.050000, -0.467210, 0.001722, 0.004548, 1496957389.404700, 1.269385, 1.000000, 59.914444, 15.300221, 21.234455, 0.957447 +-38.1558, 30.9304, -28.329944, 5.050000, -0.328807, 0.001722, 0.000000, 1496957389.414200, 1.269486, 1.000000, 59.964944, 15.275806, 21.234455, 0.957447 +-38.1361, 30.9821, -28.330786, 5.036111, -0.465719, 0.001952, 0.004560, 1496957389.423700, 1.269600, 1.000000, 60.015305, 15.275806, 21.229877, 1.085106 +-38.1164, 31.0337, -28.331590, 5.036111, -0.438926, 0.001952, 0.000000, 1496957389.434200, 1.269674, 1.000000, 60.065667, 15.300221, 21.229877, 1.085106 +-38.0968, 31.0852, -28.332378, 5.030556, -0.604295, 0.002143, 0.003804, 1496957389.443700, 1.269782, 1.000000, 60.115972, 15.300221, 21.316854, 1.191489 +-38.0772, 31.1367, -28.333064, 5.030556, -0.470797, 0.002143, 0.000000, 1496957389.454400, 1.269863, 1.000000, 60.166278, 15.288014, 21.316854, 1.191489 +-38.0577, 31.1882, -28.333761, 5.027778, -0.563313, 0.002258, 0.002284, 1496957389.463900, 1.269944, 1.000000, 60.216555, 15.288014, 21.412985, 1.255319 +-38.0382, 31.2396, -28.334328, 5.027778, -0.449973, 0.002258, 0.000000, 1496957389.474500, 1.269995, 1.000000, 60.266833, 15.263599, 21.412985, 1.255319 +-38.0187, 31.291, -28.334828, 5.019444, -0.447980, 0.002297, 0.000763, 1496957389.483900, 1.270077, 1.000000, 60.317028, 15.263599, 21.408407, 1.276596 +-37.9992, 31.3424, -28.335357, 5.019444, -0.542795, 0.002297, 0.000000, 1496957389.494700, 1.270164, 1.000000, 60.367222, 15.275806, 21.408407, 1.276596 +-37.9798, 31.3937, -28.335748, 5.008333, -0.509335, 0.002335, 0.000764, 1496957389.504200, 1.270231, 1.000000, 60.417305, 15.275806, 21.443504, 1.297872 +-37.9604, 31.4449, -28.336137, 5.008333, -0.557842, 0.002335, 0.000000, 1496957389.513700, 1.270308, 1.000000, 60.467389, 15.300221, 21.443504, 1.297872 +-37.941, 31.4962, -28.336521, 4.997222, -0.468964, 0.002373, 0.000766, 1496957389.524300, 1.270408, 1.000000, 60.517361, 15.300221, 21.472496, 1.319149 +-37.9216, 31.5474, -28.336844, 4.997222, -0.472586, 0.002373, 0.000000, 1496957389.533700, 1.270475, 1.000000, 60.567333, 15.300221, 21.472496, 1.319149 +-37.9022, 31.5985, -28.337163, 4.988889, -0.447854, 0.002373, 0.000000, 1496957389.544200, 1.270576, 1.000000, 60.617222, 15.300221, 21.512169, 1.319149 +-37.8829, 31.6496, -28.337355, 4.988889, -0.427357, 0.002373, 0.000000, 1496957389.553900, 1.270654, 1.000000, 60.667111, 15.239185, 21.512169, 1.319149 +-37.8635, 31.7006, -28.337538, 4.980556, -0.554092, 0.002335, -0.000769, 1496957389.564400, 1.270795, 1.000000, 60.716917, 15.239185, 21.472496, 1.297872 +-37.8442, 31.7516, -28.337657, 4.980556, -0.556912, 0.002335, 0.000000, 1496957389.574200, 1.270844, 1.000000, 60.766722, 15.214770, 21.472496, 1.297872 +-37.8249, 31.8026, -28.337715, 4.969444, -0.480796, 0.002373, 0.000770, 1496957389.583700, 1.270918, 1.000000, 60.816417, 15.214770, 21.480125, 1.319149 +-37.8055, 31.8535, -28.337808, 4.969444, -0.462650, 0.002373, 0.000000, 1496957389.594200, 1.271000, 1.000000, 60.866111, 15.226978, 21.480125, 1.319149 +-37.7862, 31.9043, -28.337866, 4.955555, -0.490493, 0.002373, 0.000000, 1496957389.603800, 1.271051, 1.000000, 60.915667, 15.226978, 21.568628, 1.319149 +-37.7669, 31.9551, -28.337934, 4.955555, -0.476794, 0.002373, 0.000000, 1496957389.614400, 1.271164, 1.000000, 60.965222, 15.288014, 21.568628, 1.319149 +-37.7475, 32.0059, -28.337928, 4.941667, -0.438506, 0.002373, 0.000000, 1496957389.623900, 1.271229, 1.000000, 61.014639, 15.288014, 21.519798, 1.319149 +-37.7282, 32.0565, -28.337930, 4.941667, -0.656605, 0.002373, 0.000000, 1496957389.634500, 1.271311, 1.000000, 61.064055, 15.239185, 21.519798, 1.319149 +-37.7089, 32.1071, -28.337929, 4.933333, -0.631332, 0.002373, 0.000000, 1496957389.644100, 1.271382, 1.000000, 61.113389, 15.239185, 21.618982, 1.319149 +-37.6895, 32.1577, -28.337945, 4.933333, -0.553177, 0.002373, 0.000000, 1496957389.653600, 1.271473, 1.000000, 61.162722, 15.263599, 21.618982, 1.319149 +-37.6703, 32.2082, -28.338036, 4.919445, -0.493095, 0.002373, 0.000000, 1496957389.664300, 1.271539, 1.000000, 61.211917, 15.263599, 21.602198, 1.319149 +-37.651, 32.2587, -28.338257, 4.919445, -0.357391, 0.002373, 0.000000, 1496957389.673800, 1.271564, 1.000000, 61.261111, 15.214770, 21.602198, 1.319149 +-37.6318, 32.3092, -28.338397, 4.911111, -0.359148, 0.002373, 0.000000, 1496957389.684300, 1.271595, 1.000000, 61.310222, 15.214770, 21.635767, 1.319149 +-37.6126, 32.3596, -28.338731, 4.911111, -0.487494, 0.002373, 0.000000, 1496957389.693900, 1.271613, 1.000000, 61.359333, 15.336843, 21.635767, 1.319149 +-37.5934, 32.41, -28.338939, 4.905556, -0.336088, 0.002335, -0.000780, 1496957389.704400, 1.271624, 1.000000, 61.408389, 15.336843, 21.739529, 1.297872 +-37.5743, 32.4604, -28.339255, 4.905556, -0.327429, 0.002335, 0.000000, 1496957389.713900, 1.271706, 1.000000, 61.457444, 15.239185, 21.739529, 1.297872 +-37.5552, 32.5107, -28.339667, 4.900000, -0.397745, 0.002373, 0.000781, 1496957389.724500, 1.271692, 1.000000, 61.506444, 15.239185, 21.765469, 1.319149 +-37.5361, 32.561, -28.340057, 4.900000, -0.479476, 0.002373, 0.000000, 1496957389.734000, 1.271739, 1.000000, 61.555444, 15.263599, 21.765469, 1.319149 +-37.517, 32.6111, -28.340547, 4.888889, -0.574153, 0.002297, -0.001566, 1496957389.744500, 1.271781, 1.000000, 61.604333, 15.263599, 21.857023, 1.276596 +-37.4979, 32.6613, -28.340844, 4.888889, -0.681087, 0.002297, 0.000000, 1496957389.754000, 1.271850, 1.000000, 61.653222, 15.202563, 21.857023, 1.276596 +-37.4788, 32.7114, -28.341118, 4.875000, -0.669246, 0.002297, 0.000000, 1496957389.764500, 1.271904, 1.000000, 61.701972, 15.202563, 21.918058, 1.276596 +-37.4598, 32.7614, -28.341443, 4.875000, -0.474076, 0.002297, 0.000000, 1496957389.774100, 1.272016, 1.000000, 61.750722, 15.214770, 21.918058, 1.276596 +-37.4407, 32.8114, -28.341733, 4.866667, -0.499973, 0.002335, 0.000787, 1496957389.783600, 1.272110, 1.000000, 61.799389, 15.214770, 22.070650, 1.297872 +-37.4217, 32.8613, -28.342038, 4.866667, -0.492405, 0.002335, 0.000000, 1496957389.794100, 1.272207, 1.000000, 61.848055, 15.263599, 22.070650, 1.297872 +-37.4026, 32.9112, -28.342425, 4.861111, -0.641454, 0.002450, 0.002362, 1496957389.804600, 1.272286, 1.000000, 61.896667, 15.263599, 22.168306, 1.361702 +-37.3835, 32.961, -28.342760, 4.861111, -0.583336, 0.002450, 0.000000, 1496957389.814200, 1.272413, 1.000000, 61.945278, 15.178149, 22.168306, 1.361702 +-37.3644, 33.0107, -28.343151, 4.844444, -0.519218, 0.002488, 0.000790, 1496957389.823600, 1.272499, 1.000000, 61.993722, 15.178149, 22.185091, 1.382979 +-37.3453, 33.0604, -28.343524, 4.844444, -0.524070, 0.002488, 0.000000, 1496957389.834200, 1.272591, 1.000000, 62.042167, 15.288014, 22.185091, 1.382979 +-37.3261, 33.11, -28.343940, 4.833333, -0.581163, 0.002564, 0.001584, 1496957389.843800, 1.272712, 1.000000, 62.090500, 15.288014, 22.175936, 1.425532 +-37.307, 33.1596, -28.344213, 4.833333, -0.703003, 0.002564, 0.000000, 1496957389.854300, 1.272828, 1.000000, 62.138833, 15.336843, 22.175936, 1.425532 +-37.288, 33.2091, -28.344433, 4.825000, -0.665180, 0.002603, 0.000793, 1496957389.863800, 1.273005, 1.000000, 62.187083, 15.336843, 22.201878, 1.446808 +-37.269, 33.2585, -28.344605, 4.825000, -0.701024, 0.002603, 0.000000, 1496957389.874300, 1.273105, 1.000000, 62.235333, 15.239185, 22.201878, 1.446808 +-37.25, 33.3079, -28.344607, 4.816667, -0.696739, 0.002641, 0.000795, 1496957389.884300, 1.273251, 1.000000, 62.283500, 15.239185, 22.169832, 1.468085 +-37.2311, 33.3572, -28.344652, 4.816667, -0.708260, 0.002641, 0.000000, 1496957389.893900, 1.273280, 1.000000, 62.331667, 15.239185, 22.169832, 1.468085 +-37.2123, 33.4064, -28.344506, 4.791667, -0.969929, 0.002603, -0.000799, 1496957389.904600, 1.273407, 1.000000, 62.379583, 15.239185, 22.169832, 1.446808 +-37.1934, 33.4555, -28.344390, 4.791667, -0.941693, 0.002603, 0.000000, 1496957389.914100, 1.273532, 1.000000, 62.427500, 15.312428, 22.169832, 1.446808 +-37.1747, 33.5047, -28.344246, 4.775000, -0.644728, 0.002603, 0.000000, 1496957389.923600, 1.273668, 1.000000, 62.475250, 15.312428, 22.149996, 1.446808 +-37.156, 33.5537, -28.344056, 4.775000, -0.540990, 0.002603, 0.000000, 1496957389.934100, 1.273794, 1.000000, 62.523000, 15.263599, 22.149996, 1.446808 +-37.1373, 33.6028, -28.343941, 4.769444, -0.579376, 0.002603, 0.000000, 1496957389.944600, 1.273860, 1.000000, 62.570694, 15.263599, 22.183565, 1.446808 +-37.1186, 33.6517, -28.343792, 4.769444, -0.720147, 0.002603, 0.000000, 1496957389.954100, 1.273941, 1.000000, 62.618389, 15.214770, 22.183565, 1.446808 +-37.1, 33.7006, -28.343622, 4.755556, -0.948780, 0.002526, -0.001610, 1496957389.963600, 1.274027, 1.000000, 62.665944, 15.214770, 22.194248, 1.404255 +-37.0814, 33.7493, -28.343525, 4.755556, -0.734881, 0.002526, 0.000000, 1496957389.974200, 1.274106, 1.000000, 62.713500, 15.226978, 22.194248, 1.404255 +-37.0629, 33.798, -28.343337, 4.733333, -0.841155, 0.002450, -0.001617, 1496957389.983800, 1.274221, 1.000000, 62.760833, 15.226978, 22.171358, 1.361702 +-37.0443, 33.8467, -28.343277, 4.733333, -0.705102, 0.002450, 0.000000, 1496957389.994400, 1.274313, 1.000000, 62.808167, 15.226978, 22.171358, 1.361702 +-37.0443, 33.8467, -28.343277, 4.719444, -0.705102, 0.002450, 0.000000, 1496957390.003900, 1.274313, 1.000000, 62.855361, 15.226978, 22.178988, 1.361702 +-37.0073, 33.9438, -28.343010, 4.719444, -0.766359, 0.002450, 0.000000, 1496957390.014500, 1.274586, 1.000000, 62.902555, 15.324636, 22.178988, 1.361702 +-36.9889, 33.9921, -28.342957, 4.705555, -0.669991, 0.002450, 0.000000, 1496957390.024100, 1.274665, 1.000000, 62.949611, 15.324636, 22.220188, 1.361702 +-36.9704, 34.0405, -28.342887, 4.705555, -0.504470, 0.002450, 0.000000, 1496957390.033500, 1.274817, 1.000000, 62.996667, 15.178149, 22.220188, 1.361702 +-36.9519, 34.0888, -28.343002, 4.691667, -0.642514, 0.002450, 0.000000, 1496957390.044100, 1.274951, 1.000000, 63.043583, 15.178149, 22.195774, 1.361702 +-36.9334, 34.137, -28.343099, 4.691667, -0.633737, 0.002450, 0.000000, 1496957390.054600, 1.275043, 1.000000, 63.090500, 15.263599, 22.195774, 1.361702 +-36.9149, 34.1852, -28.343246, 4.677778, -0.597114, 0.002450, 0.000000, 1496957390.064200, 1.275141, 1.000000, 63.137278, 15.263599, 22.211033, 1.361702 +-36.8964, 34.2332, -28.343442, 4.677778, -0.765800, 0.002450, 0.000000, 1496957390.073700, 1.275244, 1.000000, 63.184055, 15.239185, 22.211033, 1.361702 +-36.878, 34.2812, -28.343699, 4.666667, -0.646135, 0.002450, 0.000000, 1496957390.084200, 1.275300, 1.000000, 63.230722, 15.239185, 22.275120, 1.361702 +-36.8596, 34.329, -28.343976, 4.666667, -0.674732, 0.002450, 0.000000, 1496957390.093900, 1.275454, 1.000000, 63.277389, 15.263599, 22.275120, 1.361702 +-36.8412, 34.3767, -28.344282, 4.655556, -0.770812, 0.002450, 0.000000, 1496957390.104400, 1.275584, 1.000000, 63.323944, 15.263599, 22.244602, 1.361702 +-36.8228, 34.4244, -28.344659, 4.655556, -0.815281, 0.002450, 0.000000, 1496957390.114000, 1.275728, 1.000000, 63.370500, 15.239185, 22.244602, 1.361702 +-36.8045, 34.472, -28.344991, 4.644444, -0.599408, 0.002488, 0.000824, 1496957390.124500, 1.275929, 1.000000, 63.416944, 15.239185, 22.314795, 1.382979 +-36.7862, 34.5196, -28.345473, 4.644444, -0.618031, 0.002488, 0.000000, 1496957390.134100, 1.276008, 1.000000, 63.463389, 15.263599, 22.314795, 1.382979 +-36.7679, 34.567, -28.345945, 4.630556, -0.847426, 0.002488, 0.000000, 1496957390.143500, 1.276128, 1.000000, 63.509694, 15.263599, 22.311741, 1.382979 +-36.7496, 34.6144, -28.346473, 4.630556, -0.551689, 0.002488, 0.000000, 1496957390.154000, 1.276289, 1.000000, 63.556000, 15.263599, 22.311741, 1.382979 +-36.7313, 34.6617, -28.347114, 4.613889, -0.795590, 0.002526, 0.000830, 1496957390.164600, 1.276444, 1.000000, 63.602139, 15.263599, 22.328527, 1.404255 +-36.713, 34.709, -28.347643, 4.613889, -0.492441, 0.002526, 0.000000, 1496957390.174200, 1.276662, 1.000000, 63.648278, 15.202563, 22.328527, 1.404255 +-36.6946, 34.7561, -28.348385, 4.605556, -0.757619, 0.002603, 0.001662, 1496957390.183800, 1.276824, 1.000000, 63.694333, 15.202563, 22.391088, 1.446808 +-36.6764, 34.8032, -28.348932, 4.605556, -0.865896, 0.002603, 0.000000, 1496957390.194300, 1.277001, 1.000000, 63.740389, 15.275806, 22.391088, 1.446808 +-36.6581, 34.8502, -28.349682, 4.594444, -0.765695, 0.002756, 0.003332, 1496957390.203900, 1.277128, 1.000000, 63.786333, 15.275806, 22.482643, 1.531915 +-36.6397, 34.8972, -28.350382, 4.594444, -0.693731, 0.002756, 0.000000, 1496957390.214400, 1.277299, 1.000000, 63.832278, 15.275806, 22.482643, 1.531915 +-36.6215, 34.944, -28.351099, 4.580555, -0.704812, 0.002794, 0.000836, 1496957390.224000, 1.277454, 1.000000, 63.878083, 15.275806, 22.502480, 1.553192 +-36.6032, 34.9908, -28.351972, 4.580555, -0.576717, 0.002794, 0.000000, 1496957390.234600, 1.277621, 1.000000, 63.923889, 15.300221, 22.502480, 1.553192 +-36.5849, 35.0376, -28.352693, 4.569445, -0.727665, 0.002871, 0.001675, 1496957390.244200, 1.277760, 1.000000, 63.969583, 15.300221, 22.526894, 1.595745 +-36.5667, 35.0842, -28.353447, 4.569445, -0.788811, 0.002871, 0.000000, 1496957390.253700, 1.278000, 1.000000, 64.015278, 15.202563, 22.526894, 1.595745 +-36.5485, 35.1308, -28.354128, 4.550000, -0.702691, 0.002986, 0.002524, 1496957390.264200, 1.278158, 1.000000, 64.060778, 15.202563, 22.546730, 1.659575 +-36.5303, 35.1773, -28.354745, 4.550000, -0.906830, 0.002986, 0.000000, 1496957390.273800, 1.278335, 1.000000, 64.106278, 15.239185, 22.546730, 1.659575 +-36.5122, 35.2237, -28.355342, 4.533333, -0.938648, 0.003139, 0.003377, 1496957390.284300, 1.278460, 1.000000, 64.151611, 15.239185, 22.616922, 1.744681 +-36.4941, 35.27, -28.355994, 4.533333, -0.843927, 0.003139, 0.000000, 1496957390.293800, 1.278620, 1.000000, 64.196944, 15.373465, 22.616922, 1.744681 +-36.4761, 35.3163, -28.356548, 4.519444, -0.752601, 0.003215, 0.001694, 1496957390.304300, 1.278782, 1.000000, 64.242139, 15.373465, 22.705425, 1.787234 +-36.4581, 35.3626, -28.357057, 4.519444, -0.704409, 0.003215, 0.000000, 1496957390.313800, 1.278974, 1.000000, 64.287333, 15.153734, 22.705425, 1.787234 +-36.4401, 35.4087, -28.357553, 4.505556, -0.833847, 0.003292, 0.001699, 1496957390.324400, 1.279137, 1.000000, 64.332389, 15.153734, 22.757305, 1.829787 +-36.4222, 35.4547, -28.357793, 4.505556, -0.992898, 0.003292, 0.000000, 1496957390.333900, 1.279332, 1.000000, 64.377444, 15.226978, 22.757305, 1.829787 +-36.4043, 35.5006, -28.358190, 4.486111, -1.118181, 0.003445, 0.003413, 1496957390.344500, 1.279505, 1.000000, 64.422305, 15.226978, 22.847334, 1.914894 +-36.3864, 35.5465, -28.358377, 4.486111, -1.019637, 0.003445, 0.000000, 1496957390.354000, 1.279736, 1.000000, 64.467167, 15.214770, 22.847334, 1.914894 +-36.3685, 35.5922, -28.358589, 4.469444, -0.957600, 0.003598, 0.003426, 1496957390.364600, 1.279922, 1.000000, 64.511861, 15.214770, 22.926680, 2.000000 +-36.3507, 35.6379, -28.358706, 4.469444, -0.836267, 0.003598, 0.000000, 1496957390.374200, 1.280150, 1.000000, 64.556555, 15.288014, 22.926680, 2.000000 +-36.3328, 35.6835, -28.358736, 4.450000, -0.849757, 0.003713, 0.002581, 1496957390.383900, 1.280409, 1.000000, 64.601055, 15.288014, 23.004501, 2.063830 +-36.315, 35.729, -28.358739, 4.450000, -0.913308, 0.003713, 0.000000, 1496957390.394600, 1.280633, 1.000000, 64.645555, 15.312428, 23.004501, 2.063830 +-36.2972, 35.7744, -28.358610, 4.430555, -0.922457, 0.003828, 0.002592, 1496957390.404200, 1.280878, 1.000000, 64.689861, 15.312428, 23.068590, 2.127660 +-36.2795, 35.8197, -28.358453, 4.430555, -1.107301, 0.003828, 0.000000, 1496957390.414700, 1.281146, 1.000000, 64.734167, 15.263599, 23.068590, 2.127660 +-36.2618, 35.865, -28.358234, 4.413889, -1.009223, 0.003942, 0.002602, 1496957390.424200, 1.281307, 1.000000, 64.778305, 15.263599, 23.135729, 2.191489 +-36.2442, 35.9101, -28.358060, 4.413889, -1.003671, 0.003942, 0.000000, 1496957390.433700, 1.281530, 1.000000, 64.822444, 15.239185, 23.135729, 2.191489 +-36.2266, 35.9552, -28.357848, 4.394444, -0.818496, 0.004096, 0.003484, 1496957390.444300, 1.281728, 1.000000, 64.866389, 15.239185, 23.073168, 2.276596 +-36.2091, 36.0003, -28.357707, 4.394444, -0.659114, 0.004096, 0.000000, 1496957390.453800, 1.281908, 1.000000, 64.910333, 15.263599, 23.073168, 2.276596 +-36.1917, 36.0452, -28.357492, 4.377778, -0.922493, 0.004172, 0.001749, 1496957390.464300, 1.282050, 1.000000, 64.954111, 15.263599, 23.074694, 2.319149 +-36.1743, 36.0901, -28.357375, 4.377778, -0.870337, 0.004172, 0.000000, 1496957390.473800, 1.282232, 1.000000, 64.997889, 15.275806, 23.074694, 2.319149 +-36.157, 36.1349, -28.357250, 4.352778, -1.036865, 0.004249, 0.001759, 1496957390.484300, 1.282343, 1.000000, 65.041417, 15.275806, 23.106737, 2.361702 +-36.1397, 36.1796, -28.357273, 4.352778, -0.830652, 0.004249, 0.000000, 1496957390.493900, 1.282474, 1.000000, 65.084944, 15.275806, 23.106737, 2.361702 +-36.1225, 36.2242, -28.357208, 4.330555, -0.797629, 0.004287, 0.000884, 1496957390.504400, 1.282616, 1.000000, 65.128250, 15.275806, 23.007553, 2.382979 +-36.1054, 36.2688, -28.357277, 4.330555, -0.900299, 0.004287, 0.000000, 1496957390.513900, 1.282681, 1.000000, 65.171555, 15.239185, 23.007553, 2.382979 +-36.0884, 36.3133, -28.357206, 4.311111, -0.904752, 0.004364, 0.001776, 1496957390.524400, 1.282823, 1.000000, 65.214667, 15.239185, 23.096056, 2.425532 +-36.0714, 36.3577, -28.357184, 4.311111, -1.153371, 0.004364, 0.000000, 1496957390.534000, 1.282943, 1.000000, 65.257778, 15.263599, 23.096056, 2.425532 +-36.0545, 36.402, -28.357188, 4.294445, -0.904016, 0.004364, 0.000000, 1496957390.543500, 1.283039, 1.000000, 65.300722, 15.263599, 23.102160, 2.425532 +-36.0376, 36.4462, -28.357184, 4.294445, -0.971788, 0.004364, 0.000000, 1496957390.554200, 1.283176, 1.000000, 65.343667, 15.239185, 23.102160, 2.425532 +-36.0207, 36.4903, -28.357393, 4.272222, -1.065115, 0.004364, 0.000000, 1496957390.563800, 1.283244, 1.000000, 65.386389, 15.239185, 23.210499, 2.425532 +-36.0039, 36.5344, -28.357409, 4.272222, -0.973287, 0.004364, 0.000000, 1496957390.574300, 1.283394, 1.000000, 65.429111, 15.239185, 23.210499, 2.425532 +-35.9871, 36.5782, -28.357619, 4.244444, -1.278113, 0.004325, -0.000902, 1496957390.583900, 1.283507, 1.000000, 65.471555, 15.239185, 23.262379, 2.404255 +-35.9703, 36.622, -28.357805, 4.244444, -1.032180, 0.004325, 0.000000, 1496957390.594500, 1.283666, 1.000000, 65.514000, 15.263599, 23.262379, 2.404255 +-35.9535, 36.6657, -28.358119, 4.227778, -1.046288, 0.004325, 0.000000, 1496957390.604100, 1.283822, 1.000000, 65.556278, 15.263599, 23.414968, 2.404255 +-35.9367, 36.7093, -28.358305, 4.227778, -1.013416, 0.004325, 0.000000, 1496957390.613500, 1.283989, 1.000000, 65.598555, 15.263599, 23.414968, 2.404255 +-35.9199, 36.7527, -28.358700, 4.213889, -1.033217, 0.004287, -0.000908, 1496957390.624100, 1.284165, 1.000000, 65.640694, 15.263599, 23.514153, 2.382979 +-35.9031, 36.7961, -28.359007, 4.213889, -1.052605, 0.004287, 0.000000, 1496957390.634600, 1.284390, 1.000000, 65.682833, 15.263599, 23.514153, 2.382979 +-35.8863, 36.8393, -28.359397, 4.191667, -1.109201, 0.004249, -0.000913, 1496957390.644200, 1.284616, 1.000000, 65.724750, 15.263599, 23.581293, 2.361702 +-35.8695, 36.8824, -28.359807, 4.191667, -1.030584, 0.004249, 0.000000, 1496957390.653800, 1.284862, 1.000000, 65.766667, 15.263599, 23.581293, 2.361702 +-35.8528, 36.9255, -28.360290, 4.177778, -1.098866, 0.004249, 0.000000, 1496957390.664300, 1.285059, 1.000000, 65.808444, 15.263599, 23.537041, 2.361702 +-35.8361, 36.9684, -28.360737, 4.177778, -0.937592, 0.004249, 0.000000, 1496957390.673800, 1.285299, 1.000000, 65.850222, 15.288014, 23.537041, 2.361702 +-35.8194, 37.0112, -28.361126, 4.161111, -1.003535, 0.004249, 0.000000, 1496957390.684300, 1.285523, 1.000000, 65.891833, 15.288014, 23.628595, 2.361702 +-35.8027, 37.054, -28.361587, 4.161111, -1.028392, 0.004249, 0.000000, 1496957390.693900, 1.285764, 1.000000, 65.933444, 15.251392, 23.628595, 2.361702 +-35.7861, 37.0966, -28.361916, 4.138889, -1.138287, 0.004249, 0.000000, 1496957390.704500, 1.286029, 1.000000, 65.974833, 15.251392, 23.674372, 2.361702 +-35.7694, 37.1391, -28.362300, 4.138889, -1.216318, 0.004249, 0.000000, 1496957390.714100, 1.286244, 1.000000, 66.016222, 15.214770, 23.674372, 2.361702 +-35.7529, 37.1815, -28.362597, 4.113889, -1.185366, 0.004249, 0.000000, 1496957390.724500, 1.286482, 1.000000, 66.057361, 15.214770, 23.703365, 2.361702 +-35.7364, 37.2238, -28.362896, 4.113889, -1.176423, 0.004249, 0.000000, 1496957390.734000, 1.286704, 1.000000, 66.098500, 15.214770, 23.703365, 2.361702 +-35.7198, 37.2659, -28.363079, 4.094444, -1.199286, 0.004249, 0.000000, 1496957390.744500, 1.286854, 1.000000, 66.139444, 15.239185, 23.697262, 2.361702 +-35.7034, 37.3079, -28.363358, 4.094444, -1.341713, 0.004249, 0.000000, 1496957390.754100, 1.287085, 1.000000, 66.180389, 15.239185, 23.697262, 2.361702 +-35.6869, 37.3499, -28.363578, 4.063889, -1.265246, 0.004287, 0.000942, 1496957390.764600, 1.287285, 1.000000, 66.221028, 15.165942, 23.715572, 2.382979 +-35.6706, 37.3917, -28.363688, 4.063889, -1.283141, 0.004287, 0.000000, 1496957390.774200, 1.287408, 1.000000, 66.261667, 15.165942, 23.715572, 2.382979 +-35.6542, 37.4333, -28.363824, 4.038889, -1.409569, 0.004364, 0.001896, 1496957390.783600, 1.287585, 1.000000, 66.302055, 15.263599, 23.852903, 2.425532 +-35.6379, 37.4748, -28.363843, 4.038889, -1.389771, 0.004364, 0.000000, 1496957390.794100, 1.287836, 1.000000, 66.342444, 15.263599, 23.852903, 2.425532 +-35.6216, 37.5162, -28.363948, 4.013889, -1.492280, 0.004402, 0.000954, 1496957390.803500, 1.287985, 1.000000, 66.382583, 15.214770, 23.901731, 2.446809 +-35.6053, 37.5574, -28.364018, 4.013889, -1.369206, 0.004402, 0.000000, 1496957390.814100, 1.288165, 1.000000, 66.422722, 15.214770, 23.901731, 2.446809 +-35.5891, 37.5986, -28.363887, 3.994444, -1.254246, 0.004478, 0.001917, 1496957390.823500, 1.288380, 1.000000, 66.462667, 15.239185, 23.852903, 2.489362 +-35.573, 37.6396, -28.364000, 3.994444, -1.239043, 0.004478, 0.000000, 1496957390.834100, 1.288548, 1.000000, 66.502611, 15.239185, 23.852903, 2.489362 +-35.5568, 37.6804, -28.363729, 3.972222, -1.479880, 0.004555, 0.001927, 1496957390.843600, 1.288741, 1.000000, 66.542333, 15.239185, 23.854429, 2.531915 +-35.5407, 37.7212, -28.363703, 3.972222, -1.242166, 0.004555, 0.000000, 1496957390.854100, 1.288892, 1.000000, 66.582055, 15.239185, 23.854429, 2.531915 +-35.5247, 37.7618, -28.363561, 3.947222, -1.397074, 0.004555, 0.000000, 1496957390.863500, 1.289103, 1.000000, 66.621528, 15.263599, 23.849852, 2.531915 +-35.5086, 37.8023, -28.363397, 3.947222, -1.216457, 0.004555, 0.000000, 1496957390.874000, 1.289310, 1.000000, 66.661000, 15.263599, 23.849852, 2.531915 +-35.4926, 37.8427, -28.363332, 3.916667, -1.306894, 0.004555, 0.000000, 1496957390.883600, 1.289489, 1.000000, 66.700167, 15.251392, 23.810177, 2.531915 +-35.4767, 37.8829, -28.363200, 3.916667, -1.469585, 0.004555, 0.000000, 1496957390.894200, 1.289718, 1.000000, 66.739333, 15.251392, 23.810177, 2.531915 +-35.4608, 37.923, -28.363120, 3.886111, -1.273247, 0.004517, -0.000985, 1496957390.903800, 1.289848, 1.000000, 66.778194, 15.349051, 23.839170, 2.510638 +-35.4449, 37.963, -28.363021, 3.886111, -1.498526, 0.004517, 0.000000, 1496957390.914300, 1.290068, 1.000000, 66.817055, 15.263599, 23.839170, 2.510638 +-35.4292, 38.0029, -28.362882, 3.861111, -1.352002, 0.004402, -0.002974, 1496957390.924200, 1.290258, 1.000000, 66.855667, 15.263599, 23.883421, 2.446809 +-35.4135, 38.0426, -28.362892, 3.861111, -1.472077, 0.004402, 0.000000, 1496957390.933800, 1.290440, 1.000000, 66.894278, 15.263599, 23.883421, 2.446809 +-35.3979, 38.0822, -28.362760, 3.830555, -1.475709, 0.004325, -0.001999, 1496957390.944300, 1.290582, 1.000000, 66.932583, 15.336843, 23.941406, 2.404255 +-35.3823, 38.1216, -28.362785, 3.830555, -1.409785, 0.004325, 0.000000, 1496957390.953800, 1.290796, 1.000000, 66.970889, 15.336843, 23.941406, 2.404255 +-35.3669, 38.1609, -28.362797, 3.805556, -1.477384, 0.004287, -0.001006, 1496957390.964400, 1.290977, 1.000000, 67.008944, 15.263599, 23.920042, 2.382979 +-35.3515, 38.2001, -28.362795, 3.805556, -1.416657, 0.004287, 0.000000, 1496957390.974000, 1.291184, 1.000000, 67.047000, 15.263599, 23.920042, 2.382979 +-35.3361, 38.2391, -28.362752, 3.777778, -1.537247, 0.004287, 0.000000, 1496957390.984500, 1.291371, 1.000000, 67.084778, 15.288014, 23.949036, 2.382979 +-35.3207, 38.278, -28.362832, 3.777778, -1.501922, 0.004287, 0.000000, 1496957390.994100, 1.291548, 1.000000, 67.122555, 15.288014, 23.949036, 2.382979 +-35.3054, 38.3168, -28.362805, 3.752778, -1.383150, 0.004287, 0.000000, 1496957391.005100, 1.291787, 1.000000, 67.160083, 15.239185, 23.927671, 2.382979 +-35.2901, 38.3554, -28.362921, 3.752778, -1.530167, 0.004287, 0.000000, 1496957391.014600, 1.291996, 1.000000, 67.197611, 15.239185, 23.927671, 2.382979 +-35.2749, 38.3938, -28.362943, 3.722222, -1.463380, 0.004287, 0.000000, 1496957391.024200, 1.292132, 1.000000, 67.234833, 15.239185, 23.894102, 2.382979 +-35.2596, 38.4321, -28.362927, 3.722222, -1.425570, 0.004287, 0.000000, 1496957391.033700, 1.292370, 1.000000, 67.272055, 15.239185, 23.894102, 2.382979 +-35.2444, 38.4702, -28.362985, 3.700000, -1.431426, 0.004325, 0.001035, 1496957391.044300, 1.292540, 1.000000, 67.309055, 15.214770, 23.871214, 2.404255 +-35.2292, 38.5083, -28.363058, 3.700000, -1.494657, 0.004325, 0.000000, 1496957391.053800, 1.292738, 1.000000, 67.346055, 15.214770, 23.871214, 2.404255 +-35.214, 38.5461, -28.363017, 3.675000, -1.486526, 0.004325, 0.000000, 1496957391.064300, 1.292904, 1.000000, 67.382805, 15.263599, 23.894102, 2.404255 +-35.199, 38.5838, -28.363099, 3.675000, -1.460029, 0.004325, 0.000000, 1496957391.073900, 1.292988, 1.000000, 67.419555, 15.263599, 23.894102, 2.404255 +-35.1842, 38.6212, -28.363055, 3.647222, -1.347962, 0.004364, 0.001050, 1496957391.084400, 1.293142, 1.000000, 67.456028, 15.300221, 23.828489, 2.425532 +-35.1694, 38.6584, -28.363046, 3.647222, -1.458715, 0.004364, 0.000000, 1496957391.094000, 1.293309, 1.000000, 67.492500, 15.300221, 23.828489, 2.425532 +-35.1546, 38.6955, -28.363027, 3.616667, -1.514912, 0.004402, 0.001058, 1496957391.103500, 1.293475, 1.000000, 67.528667, 15.239185, 23.860533, 2.446809 +-35.1399, 38.7325, -28.362945, 3.616667, -1.611880, 0.004402, 0.000000, 1496957391.114100, 1.293644, 1.000000, 67.564833, 15.239185, 23.860533, 2.446809 +-35.1252, 38.7693, -28.362965, 3.586111, -1.520312, 0.004402, 0.000000, 1496957391.123500, 1.293795, 1.000000, 67.600694, 15.239185, 23.866636, 2.446809 +-35.1106, 38.806, -28.362970, 3.586111, -1.303104, 0.004402, 0.000000, 1496957391.134100, 1.293985, 1.000000, 67.636555, 15.239185, 23.866636, 2.446809 +-35.096, 38.8426, -28.362910, 3.563889, -1.357621, 0.004402, 0.000000, 1496957391.143500, 1.294146, 1.000000, 67.672194, 15.263599, 23.883421, 2.446809 +-35.0815, 38.8791, -28.363034, 3.563889, -1.359912, 0.004402, 0.000000, 1496957391.154100, 1.294288, 1.000000, 67.707833, 15.263599, 23.883421, 2.446809 +-35.067, 38.9154, -28.363093, 3.530555, -1.404024, 0.004364, -0.001084, 1496957391.163500, 1.294468, 1.000000, 67.743139, 15.226978, 23.820860, 2.425532 +-35.0525, 38.9515, -28.363203, 3.530555, -1.479797, 0.004364, 0.000000, 1496957391.174000, 1.294656, 1.000000, 67.778444, 15.226978, 23.820860, 2.425532 +-35.0381, 38.9876, -28.363382, 3.494444, -1.397125, 0.004325, -0.001095, 1496957391.184500, 1.294858, 1.000000, 67.813389, 15.263599, 23.849852, 2.404255 +-35.0237, 39.0234, -28.363539, 3.494444, -1.404958, 0.004325, 0.000000, 1496957391.194100, 1.295073, 1.000000, 67.848333, 15.263599, 23.849852, 2.404255 +-35.0092, 39.0591, -28.363754, 3.469445, -1.532293, 0.004287, -0.001103, 1496957391.203500, 1.295256, 1.000000, 67.883028, 15.361258, 23.826963, 2.382979 +-34.9948, 39.0947, -28.364049, 3.469445, -1.373798, 0.004287, 0.000000, 1496957391.214000, 1.295442, 1.000000, 67.917722, 15.361258, 23.826963, 2.382979 +-34.9805, 39.1302, -28.364335, 3.438889, -1.396048, 0.004249, -0.001113, 1496957391.224500, 1.295639, 1.000000, 67.952111, 15.226978, 23.871214, 2.361702 +-34.9661, 39.1655, -28.364678, 3.438889, -1.322447, 0.004249, 0.000000, 1496957391.234000, 1.295776, 1.000000, 67.986500, 15.226978, 23.871214, 2.361702 +-34.9519, 39.2006, -28.365140, 3.411111, -1.407405, 0.004210, -0.001122, 1496957391.244400, 1.295967, 1.000000, 68.020611, 15.202563, 23.877317, 2.340425 +-34.9376, 39.2357, -28.365519, 3.411111, -1.466174, 0.004210, 0.000000, 1496957391.254000, 1.296166, 1.000000, 68.054722, 15.202563, 23.877317, 2.340425 +-34.9234, 39.2706, -28.365996, 3.383333, -1.400584, 0.004172, -0.001131, 1496957391.264400, 1.296333, 1.000000, 68.088555, 15.251392, 23.860533, 2.319149 +-34.9093, 39.3053, -28.366596, 3.383333, -1.324279, 0.004172, 0.000000, 1496957391.274000, 1.296492, 1.000000, 68.122389, 15.251392, 23.860533, 2.319149 +-34.8952, 39.34, -28.367066, 3.361111, -1.301980, 0.004134, -0.001139, 1496957391.284500, 1.296691, 1.000000, 68.156000, 15.275806, 23.886473, 2.297872 +-34.8812, 39.3745, -28.367649, 3.361111, -1.419199, 0.004134, 0.000000, 1496957391.294000, 1.296832, 1.000000, 68.189611, 15.275806, 23.886473, 2.297872 +-34.8672, 39.4089, -28.368214, 3.333333, -1.519525, 0.004019, -0.003445, 1496957391.304400, 1.296978, 1.000000, 68.222944, 15.349051, 23.869688, 2.234043 +-34.8533, 39.4431, -28.368732, 3.333333, -1.466177, 0.004019, 0.000000, 1496957391.313900, 1.297124, 1.000000, 68.256278, 15.349051, 23.869688, 2.234043 +-34.8395, 39.4772, -28.369290, 3.302778, -1.421304, 0.003904, -0.003477, 1496957391.324400, 1.297283, 1.000000, 68.289305, 15.226978, 23.881895, 2.170213 +-34.8257, 39.5112, -28.369742, 3.302778, -1.476573, 0.003904, 0.000000, 1496957391.334000, 1.297403, 1.000000, 68.322333, 15.226978, 23.881895, 2.170213 +-34.812, 39.545, -28.370279, 3.275000, -1.495913, 0.003828, -0.002338, 1496957391.344600, 1.297561, 1.000000, 68.355083, 15.263599, 23.932249, 2.127660 +-34.7983, 39.5787, -28.370716, 3.275000, -1.603079, 0.003828, 0.000000, 1496957391.354200, 1.297635, 1.000000, 68.387833, 15.263599, 23.932249, 2.127660 +-34.7847, 39.6122, -28.371146, 3.247222, -1.475360, 0.003713, -0.003536, 1496957391.363700, 1.297705, 1.000000, 68.420305, 15.239185, 23.964294, 2.063830 +-34.7712, 39.6456, -28.371501, 3.247222, -1.667717, 0.003713, 0.000000, 1496957391.374200, 1.297820, 1.000000, 68.452778, 15.239185, 23.964294, 2.063830 +-34.7577, 39.6788, -28.371913, 3.213889, -1.794209, 0.003560, -0.004764, 1496957391.384200, 1.297890, 1.000000, 68.484917, 15.239185, 23.991760, 1.978723 +-34.7442, 39.7119, -28.372226, 3.213889, -1.473576, 0.003560, 0.000000, 1496957391.393800, 1.297966, 1.000000, 68.517055, 15.239185, 23.991760, 1.978723 +-34.7308, 39.7448, -28.372486, 3.186111, -1.574373, 0.003445, -0.003604, 1496957391.404600, 1.298095, 1.000000, 68.548917, 15.239185, 24.081789, 1.914894 +-34.7174, 39.7776, -28.372823, 3.186111, -1.466307, 0.003445, 0.000000, 1496957391.413700, 1.298159, 1.000000, 68.580778, 15.239185, 24.081789, 1.914894 +-34.7041, 39.8103, -28.373047, 3.166667, -1.376471, 0.003368, -0.002418, 1496957391.424200, 1.298276, 1.000000, 68.612444, 15.324636, 24.052795, 1.872340 +-34.6909, 39.8428, -28.373327, 3.166667, -1.579452, 0.003368, 0.000000, 1496957391.433700, 1.298346, 1.000000, 68.644111, 15.324636, 24.052795, 1.872340 +-34.6777, 39.8752, -28.373589, 3.138889, -1.386003, 0.003215, -0.004878, 1496957391.444200, 1.298399, 1.000000, 68.675500, 15.239185, 24.026855, 1.787234 +-34.6645, 39.9075, -28.373873, 3.138889, -1.438128, 0.003215, 0.000000, 1496957391.453800, 1.298494, 1.000000, 68.706889, 15.239185, 24.026855, 1.787234 +-34.6514, 39.9396, -28.374087, 3.108333, -1.510324, 0.003062, -0.004926, 1496957391.464400, 1.298607, 1.000000, 68.737972, 15.214770, 24.065004, 1.702128 +-34.6383, 39.9715, -28.374347, 3.108333, -1.504305, 0.003062, 0.000000, 1496957391.473900, 1.298689, 1.000000, 68.769055, 15.214770, 24.065004, 1.702128 +-34.6252, 40.0033, -28.374563, 3.077778, -1.566918, 0.002832, -0.007462, 1496957391.484500, 1.298769, 1.000000, 68.799833, 15.263599, 24.046692, 1.574468 +-34.6122, 40.0349, -28.374712, 3.077778, -1.591618, 0.002832, 0.000000, 1496957391.494100, 1.298879, 1.000000, 68.830611, 15.263599, 24.046692, 1.574468 +-34.6122, 40.0349, -28.374712, 3.050000, -1.591618, 0.002641, -0.006275, 1496957391.503800, 1.298879, 1.000000, 68.861111, 15.202563, 24.093996, 1.468085 +-34.5732, 40.129, -28.374949, 3.050000, -1.522712, 0.002641, 0.000000, 1496957391.514200, 1.299175, 1.000000, 68.891611, 15.202563, 24.093996, 1.468085 +-34.5732, 40.129, -28.374949, 3.019444, -1.522712, 0.002450, -0.006338, 1496957391.523700, 1.299175, 1.000000, 68.921805, 15.251392, 24.040588, 1.361702 +-34.5603, 40.16, -28.374920, 3.019444, -1.487497, 0.002450, 0.000000, 1496957391.534200, 1.299292, 1.000000, 68.952000, 15.251392, 24.040588, 1.361702 +-34.5474, 40.1909, -28.374938, 2.988889, -1.663896, 0.002258, -0.006403, 1496957391.543800, 1.299422, 1.000000, 68.981889, 15.190356, 24.016174, 1.255319 +-34.5346, 40.2216, -28.374847, 2.988889, -1.626098, 0.002258, 0.000000, 1496957391.554400, 1.299504, 1.000000, 69.011778, 15.190356, 24.016174, 1.255319 +-34.5218, 40.2522, -28.374764, 2.958333, -1.646396, 0.002029, -0.007763, 1496957391.563900, 1.299585, 1.000000, 69.041361, 15.263599, 23.984131, 1.127660 +-34.5091, 40.2826, -28.374603, 2.958333, -1.554771, 0.002029, 0.000000, 1496957391.574500, 1.299678, 1.000000, 69.070944, 15.263599, 23.984131, 1.127660 +-34.4964, 40.3129, -28.374389, 2.925000, -1.564749, 0.001799, -0.007851, 1496957391.584100, 1.299776, 1.000000, 69.100194, 15.288014, 24.048218, 1.000000 +-34.4837, 40.343, -28.374178, 2.925000, -1.665747, 0.001799, 0.000000, 1496957391.593500, 1.299846, 1.000000, 69.129444, 15.288014, 24.048218, 1.000000 +-34.4711, 40.373, -28.373829, 2.891667, -1.691216, 0.001531, -0.009266, 1496957391.604100, 1.299915, 1.000000, 69.158361, 15.214770, 24.034485, 0.851064 +-34.4586, 40.4028, -28.373582, 2.891667, -1.680913, 0.001531, 0.000000, 1496957391.614500, 1.300012, 1.000000, 69.187278, 15.214770, 24.034485, 0.851064 +-34.4461, 40.4325, -28.373251, 2.861111, -1.480015, 0.001378, -0.005351, 1496957391.624000, 1.300025, 1.000000, 69.215889, 15.239185, 23.974976, 0.765957 +-34.4337, 40.462, -28.372999, 2.861111, -1.504657, 0.001378, 0.000000, 1496957391.634600, 1.300097, 1.000000, 69.244500, 15.239185, 23.974976, 0.765957 +-34.4214, 40.4915, -28.372748, 2.833333, -1.390722, 0.001301, -0.002702, 1496957391.644200, 1.300147, 1.000000, 69.272833, 15.251392, 23.947510, 0.723404 +-34.4091, 40.5208, -28.372563, 2.833333, -1.398170, 0.001301, 0.000000, 1496957391.653600, 1.300138, 1.000000, 69.301167, 15.251392, 23.947510, 0.723404 +-34.3969, 40.5499, -28.372361, 2.802778, -1.352806, 0.001187, -0.004097, 1496957391.664200, 1.300158, 1.000000, 69.329194, 15.251392, 23.932249, 0.659574 +-34.3847, 40.579, -28.372160, 2.802778, -1.380383, 0.001187, 0.000000, 1496957391.673700, 1.300151, 1.000000, 69.357222, 15.251392, 23.932249, 0.659574 +-34.3726, 40.6078, -28.372026, 2.775000, -1.437690, 0.001187, 0.000000, 1496957391.684400, 1.300171, 1.000000, 69.384972, 15.263599, 23.916990, 0.659574 +-34.3605, 40.6366, -28.371960, 2.775000, -1.368965, 0.001187, 0.000000, 1496957391.694000, 1.300181, 1.000000, 69.412722, 15.263599, 23.916990, 0.659574 +-34.3484, 40.6652, -28.371941, 2.747222, -1.347186, 0.001148, -0.001393, 1496957391.704600, 1.300151, 1.000000, 69.440194, 15.202563, 23.918516, 0.638298 +-34.3363, 40.6938, -28.371922, 2.747222, -1.254468, 0.001148, 0.000000, 1496957391.714200, 1.300194, 1.000000, 69.467667, 15.202563, 23.918516, 0.638298 +-34.3243, 40.7221, -28.371890, 2.722222, -1.376859, 0.001148, 0.000000, 1496957391.723800, 1.300164, 1.000000, 69.494889, 15.251392, 23.935301, 0.638298 +-34.3123, 40.7503, -28.371888, 2.722222, -1.337751, 0.001148, 0.000000, 1496957391.734400, 1.300131, 1.000000, 69.522111, 15.251392, 23.935301, 0.638298 +-34.3003, 40.7784, -28.371901, 2.694444, -1.497562, 0.001148, 0.000000, 1496957391.743900, 1.300162, 1.000000, 69.549055, 15.178149, 23.950562, 0.638298 +-34.2883, 40.8063, -28.371985, 2.694444, -1.604106, 0.001148, 0.000000, 1496957391.754500, 1.300177, 1.000000, 69.576000, 15.178149, 23.950562, 0.638298 +-34.2764, 40.8341, -28.371939, 2.663889, -1.464011, 0.001148, 0.000000, 1496957391.764100, 1.300240, 1.000000, 69.602639, 15.226978, 23.930723, 0.638298 +-34.2645, 40.8616, -28.371979, 2.663889, -1.574669, 0.001148, 0.000000, 1496957391.774600, 1.300198, 1.000000, 69.629278, 15.226978, 23.930723, 0.638298 +-34.2526, 40.8891, -28.371916, 2.636111, -1.541849, 0.001148, 0.000000, 1496957391.784000, 1.300262, 1.000000, 69.655639, 15.263599, 23.918516, 0.638298 +-34.2407, 40.9164, -28.371944, 2.636111, -1.512061, 0.001148, 0.000000, 1496957391.794500, 1.300217, 1.000000, 69.682000, 15.263599, 23.918516, 0.638298 +-34.2289, 40.9436, -28.371900, 2.605556, -1.528082, 0.001110, -0.001469, 1496957391.804100, 1.300290, 1.000000, 69.708055, 15.263599, 23.965820, 0.617021 +-34.2172, 40.9706, -28.371835, 2.605556, -1.550388, 0.001110, 0.000000, 1496957391.813600, 1.300304, 1.000000, 69.734111, 15.263599, 23.965820, 0.617021 +-34.2054, 40.9974, -28.371828, 2.577778, -1.664372, 0.001072, -0.001485, 1496957391.824200, 1.300343, 1.000000, 69.759889, 15.263599, 23.999390, 0.595745 +-34.1937, 41.0241, -28.371758, 2.577778, -1.654684, 0.001072, 0.000000, 1496957391.833700, 1.300439, 1.000000, 69.785667, 15.263599, 23.999390, 0.595745 +-34.182, 41.0506, -28.371772, 2.547222, -1.621675, 0.001072, 0.000000, 1496957391.844200, 1.300480, 1.000000, 69.811139, 15.239185, 23.956665, 0.595745 +-34.1704, 41.077, -28.371659, 2.547222, -1.564918, 0.001072, 0.000000, 1496957391.853800, 1.300553, 1.000000, 69.836611, 15.239185, 23.956665, 0.595745 +-34.1588, 41.1031, -28.371691, 2.516667, -1.623453, 0.001033, -0.001521, 1496957391.864300, 1.300633, 1.000000, 69.861778, 15.251392, 23.947510, 0.574468 +-34.1472, 41.1292, -28.371632, 2.516667, -1.512595, 0.001033, 0.000000, 1496957391.873800, 1.300732, 1.000000, 69.886944, 15.251392, 23.947510, 0.574468 +-34.1356, 41.1551, -28.371606, 2.486111, -1.621976, 0.000995, -0.001540, 1496957391.884500, 1.300770, 1.000000, 69.911805, 15.251392, 23.971924, 0.553191 +-34.124, 41.1808, -28.371558, 2.486111, -1.612980, 0.000995, 0.000000, 1496957391.894000, 1.300918, 1.000000, 69.936667, 15.251392, 23.971924, 0.553191 +-34.1125, 41.2064, -28.371488, 2.458333, -1.655830, 0.000957, -0.001557, 1496957391.903900, 1.300998, 1.000000, 69.961250, 15.239185, 23.904783, 0.531915 +-34.101, 41.2318, -28.371442, 2.458333, -1.646250, 0.000957, 0.000000, 1496957391.914600, 1.301064, 1.000000, 69.985833, 15.239185, 23.904783, 0.531915 +-34.0895, 41.257, -28.371370, 2.427778, -1.641498, 0.000957, 0.000000, 1496957391.924100, 1.301175, 1.000000, 70.010111, 15.263599, 23.971924, 0.531915 +-34.078, 41.2821, -28.371261, 2.427778, -1.596028, 0.000957, 0.000000, 1496957391.933500, 1.301270, 1.000000, 70.034389, 15.263599, 23.971924, 0.531915 +-34.0667, 41.307, -28.371158, 2.400000, -1.644329, 0.000957, 0.000000, 1496957391.944100, 1.301348, 1.000000, 70.058389, 15.239185, 23.988708, 0.531915 +-34.0553, 41.3318, -28.371081, 2.400000, -1.635655, 0.000957, 0.000000, 1496957391.953600, 1.301399, 1.000000, 70.082389, 15.239185, 23.988708, 0.531915 +-34.044, 41.3564, -28.370961, 2.369444, -1.663385, 0.000957, 0.000000, 1496957391.964200, 1.301437, 1.000000, 70.106083, 15.239185, 23.947510, 0.531915 +-34.0327, 41.3808, -28.370809, 2.369444, -1.608527, 0.000957, 0.000000, 1496957391.973700, 1.301517, 1.000000, 70.129778, 15.239185, 23.947510, 0.531915 +-34.0215, 41.4052, -28.370681, 2.338889, -1.600162, 0.000957, 0.000000, 1496957391.984200, 1.301597, 1.000000, 70.153167, 15.214770, 23.871214, 0.531915 +-34.0103, 41.4293, -28.370559, 2.338889, -1.615762, 0.000957, 0.000000, 1496957391.993800, 1.301577, 1.000000, 70.176555, 15.214770, 23.871214, 0.531915 +-33.9992, 41.4533, -28.370492, 2.305556, -1.547862, 0.000957, 0.000000, 1496957392.004800, 1.301623, 1.000000, 70.199611, 15.263599, 23.871214, 0.531915 +-33.9881, 41.4772, -28.370396, 2.305556, -1.540084, 0.000957, 0.000000, 1496957392.014400, 1.301628, 1.000000, 70.222667, 15.263599, 23.871214, 0.531915 +-33.9771, 41.5008, -28.370330, 2.275000, -1.586256, 0.000957, 0.000000, 1496957392.024000, 1.301636, 1.000000, 70.245417, 15.239185, 23.871214, 0.531915 +-33.9661, 41.5244, -28.370277, 2.275000, -1.584655, 0.000957, 0.000000, 1496957392.034500, 1.301616, 1.000000, 70.268167, 15.239185, 23.871214, 0.531915 +-33.9552, 41.5478, -28.370255, 2.241667, -1.520244, 0.000957, 0.000000, 1496957392.044100, 1.301642, 1.000000, 70.290583, 15.202563, 23.820860, 0.531915 +-33.9443, 41.5711, -28.370269, 2.241667, -1.504842, 0.000957, 0.000000, 1496957392.053500, 1.301627, 1.000000, 70.313000, 15.202563, 23.820860, 0.531915 +-33.9334, 41.5942, -28.370276, 2.208333, -1.527613, 0.000957, 0.000000, 1496957392.064100, 1.301607, 1.000000, 70.335083, 15.288014, 23.860533, 0.531915 +-33.9228, 41.617, -28.370324, 2.208333, -1.594978, 0.000957, 0.000000, 1496957392.074700, 1.301512, 1.000000, 70.357167, 15.288014, 23.860533, 0.531915 +-33.9121, 41.6397, -28.370411, 2.180556, -1.498458, 0.000957, 0.000000, 1496957392.084200, 1.301502, 1.000000, 70.378972, 15.239185, 23.813231, 0.531915 +-33.9015, 41.6623, -28.370498, 2.180556, -1.528850, 0.000957, 0.000000, 1496957392.093700, 1.301500, 1.000000, 70.400778, 15.239185, 23.813231, 0.531915 +-33.8908, 41.6847, -28.370593, 2.150000, -1.495159, 0.000957, 0.000000, 1496957392.104300, 1.301506, 1.000000, 70.422278, 15.263599, 23.849852, 0.531915 +-33.8803, 41.7069, -28.370723, 2.150000, -1.539514, 0.000957, 0.000000, 1496957392.113900, 1.301534, 1.000000, 70.443778, 15.263599, 23.849852, 0.531915 +-33.8697, 41.729, -28.370906, 2.116667, -1.547036, 0.000919, -0.001808, 1496957392.124300, 1.301534, 1.000000, 70.464944, 15.312428, 23.817808, 0.510638 +-33.8591, 41.7509, -28.371115, 2.116667, -1.468065, 0.000919, 0.000000, 1496957392.133800, 1.301583, 1.000000, 70.486111, 15.312428, 23.817808, 0.510638 +-33.8486, 41.7727, -28.371372, 2.086111, -1.519473, 0.000919, 0.000000, 1496957392.144300, 1.301628, 1.000000, 70.506972, 15.263599, 23.814756, 0.510638 +-33.8381, 41.7944, -28.371597, 2.086111, -1.448328, 0.000919, 0.000000, 1496957392.153900, 1.301684, 1.000000, 70.527833, 15.263599, 23.814756, 0.510638 +-33.8276, 41.8159, -28.371819, 2.058333, -1.533573, 0.000919, 0.000000, 1496957392.164500, 1.301737, 1.000000, 70.548417, 15.226978, 23.851377, 0.510638 +-33.8172, 41.8372, -28.372101, 2.058333, -1.584159, 0.000919, 0.000000, 1496957392.174500, 1.301827, 1.000000, 70.569000, 15.226978, 23.851377, 0.510638 +-33.8068, 41.8584, -28.372341, 2.030555, -1.518032, 0.000880, -0.001885, 1496957392.184100, 1.301923, 1.000000, 70.589305, 15.239185, 23.801022, 0.489362 +-33.7964, 41.8794, -28.372599, 2.030555, -1.502940, 0.000880, 0.000000, 1496957392.193600, 1.301997, 1.000000, 70.609611, 15.239185, 23.801022, 0.489362 +-33.786, 41.9003, -28.372848, 2.000000, -1.546060, 0.000842, -0.001914, 1496957392.204100, 1.302075, 1.000000, 70.629611, 15.263599, 23.801022, 0.468085 +-33.7757, 41.9211, -28.373006, 2.000000, -1.529523, 0.000842, 0.000000, 1496957392.213600, 1.302154, 1.000000, 70.649611, 15.263599, 23.712521, 0.468085 +-33.7654, 41.9417, -28.373212, 1.975000, -1.519672, 0.000842, 0.000000, 1496957392.224100, 1.302230, 1.000000, 70.669361, 15.202563, 23.712521, 0.468085 +-33.7552, 41.9621, -28.373309, 1.975000, -1.567981, 0.000842, 0.000000, 1496957392.233600, 1.302223, 1.000000, 70.689111, 15.202563, 23.674372, 0.468085 +-33.7451, 41.9824, -28.373469, 1.941667, -1.614212, 0.000804, -0.001971, 1496957392.244200, 1.302275, 1.000000, 70.708528, 15.239185, 23.604181, 0.446809 +-33.735, 42.0025, -28.373517, 1.941667, -1.618876, 0.000804, 0.000000, 1496957392.253600, 1.302332, 1.000000, 70.727944, 15.239185, 23.604181, 0.446809 +-33.725, 42.0225, -28.373586, 1.911111, -1.679836, 0.000765, -0.002003, 1496957392.264200, 1.302350, 1.000000, 70.747055, 15.251392, 23.604181, 0.425532 +-33.715, 42.0424, -28.373657, 1.911111, -1.617690, 0.000765, 0.000000, 1496957392.273700, 1.302402, 1.000000, 70.766167, 15.251392, 23.543144, 0.425532 +-33.7051, 42.0621, -28.373707, 1.880556, -1.561191, 0.000727, -0.002035, 1496957392.284300, 1.302401, 1.000000, 70.784972, 15.226978, 23.472954, 0.404255 +-33.6952, 42.0816, -28.373739, 1.880556, -1.549950, 0.000727, 0.000000, 1496957392.293800, 1.302393, 1.000000, 70.803778, 15.226978, 23.472954, 0.404255 +-33.6855, 42.101, -28.373737, 1.852778, -1.552874, 0.000689, -0.002066, 1496957392.304300, 1.302420, 1.000000, 70.822305, 15.251392, 23.474480, 0.382979 +-33.6757, 42.1203, -28.373736, 1.852778, -1.553636, 0.000689, 0.000000, 1496957392.313700, 1.302414, 1.000000, 70.840833, 15.251392, 23.474480, 0.382979 +-33.666, 42.1394, -28.373701, 1.822222, -1.551574, 0.000651, -0.002100, 1496957392.324200, 1.302412, 1.000000, 70.859055, 15.190356, 23.332571, 0.361702 +-33.6564, 42.1584, -28.373688, 1.822222, -1.684731, 0.000651, 0.000000, 1496957392.333800, 1.302407, 1.000000, 70.877278, 15.190356, 23.332571, 0.361702 +-33.6468, 42.1771, -28.373682, 1.788889, -1.641212, 0.000651, 0.000000, 1496957392.344400, 1.302367, 1.000000, 70.895167, 15.178149, 23.324942, 0.361702 +-33.6373, 42.1958, -28.373661, 1.788889, -1.537957, 0.000651, 0.000000, 1496957392.353900, 1.302364, 1.000000, 70.913055, 15.178149, 23.324942, 0.361702 +-33.6278, 42.2143, -28.373689, 1.758333, -1.577620, 0.000651, 0.000000, 1496957392.364400, 1.302376, 1.000000, 70.930639, 15.288014, 23.352407, 0.361702 +-33.6183, 42.2326, -28.373683, 1.758333, -1.666916, 0.000651, 0.000000, 1496957392.373900, 1.302379, 1.000000, 70.948222, 15.288014, 23.352407, 0.361702 +-33.6088, 42.2508, -28.373678, 1.727778, -1.663328, 0.000612, -0.002215, 1496957392.384100, 1.302364, 1.000000, 70.965500, 15.226978, 23.324942, 0.340426 +-33.5994, 42.2688, -28.373717, 1.727778, -1.641463, 0.000612, 0.000000, 1496957392.394100, 1.302396, 1.000000, 70.982778, 15.226978, 23.324942, 0.340426 +-33.5901, 42.2866, -28.373712, 1.694444, -1.648102, 0.000574, -0.002259, 1496957392.404800, 1.302379, 1.000000, 70.999722, 15.226978, 23.299000, 0.319149 +-33.5807, 42.3043, -28.373750, 1.694444, -1.701818, 0.000574, 0.000000, 1496957392.413800, 1.302385, 1.000000, 71.016667, 15.226978, 23.299000, 0.319149 +-33.5714, 42.3217, -28.373766, 1.661111, -1.771555, 0.000498, -0.004608, 1496957392.424900, 1.302394, 1.000000, 71.033278, 15.263599, 23.271534, 0.276596 +-33.5621, 42.3391, -28.373790, 1.661111, -1.752357, 0.000498, 0.000000, 1496957392.434500, 1.302341, 1.000000, 71.049889, 15.263599, 23.271534, 0.276596 +-33.5529, 42.3562, -28.373835, 1.630556, -1.680161, 0.000383, -0.007042, 1496957392.444200, 1.302356, 1.000000, 71.066194, 15.263599, 23.271534, 0.212766 +-33.5437, 42.3732, -28.373839, 1.630556, -1.683567, 0.000383, 0.000000, 1496957392.453800, 1.302352, 1.000000, 71.082500, 15.263599, 23.256275, 0.212766 +-33.5345, 42.39, -28.373860, 1.602778, -1.720764, 0.000268, -0.007164, 1496957392.464300, 1.302408, 1.000000, 71.098528, 15.214770, 23.256275, 0.148936 +-33.5254, 42.4067, -28.373868, 1.602778, -1.755470, 0.000268, 0.000000, 1496957392.473800, 1.302381, 1.000000, 71.114555, 15.214770, 23.208973, 0.148936 +-33.5164, 42.4232, -28.373879, 1.575000, -1.672482, 0.000153, -0.007290, 1496957392.484300, 1.302398, 1.000000, 71.130305, 15.214770, 23.208973, 0.085106 +-33.5074, 42.4395, -28.373896, 1.575000, -1.633738, 0.000153, 0.000000, 1496957392.493700, 1.302440, 1.000000, 71.146055, 15.214770, 23.173876, 0.085106 +-33.4985, 42.4557, -28.373894, 1.547222, -1.644181, 0.000077, -0.004948, 1496957392.504900, 1.302412, 1.000000, 71.161528, 15.263599, 23.173876, 0.042553 +-33.4896, 42.4718, -28.373873, 1.547222, -1.657257, 0.000077, 0.000000, 1496957392.514400, 1.302445, 1.000000, 71.177000, 15.263599, 23.121996, 0.042553 +-33.4808, 42.4877, -28.373881, 1.516667, -1.655676, 0.000000, -0.005047, 1496957392.524000, 1.302440, 1.000000, 71.192167, 15.239185, 23.121996, 0.000000 +-33.472, 42.5034, -28.373857, 1.516667, -1.650400, 0.000000, 0.000000, 1496957392.533700, 1.302435, 1.000000, 71.207333, 15.239185, 23.064013, 0.000000 +-33.4633, 42.519, -28.373829, 1.486111, -1.588023, -0.000115, -0.007726, 1496957392.544200, 1.302429, 1.000000, 71.222194, 15.263599, 23.064013, -0.063830 +-33.4547, 42.5344, -28.373769, 1.486111, -1.637876, -0.000115, 0.000000, 1496957392.553800, 1.302470, 1.000000, 71.237055, 15.263599, 23.010605, -0.063830 +-33.4461, 42.5497, -28.373670, 1.455556, -1.628685, -0.000153, -0.002630, 1496957392.564400, 1.302424, 1.000000, 71.251611, 15.239185, 23.010605, -0.085106 +-33.4375, 42.5648, -28.373557, 1.455556, -1.621503, -0.000153, 0.000000, 1496957392.574200, 1.302460, 1.000000, 71.266167, 15.239185, 22.893110, -0.085106 +-33.4289, 42.5797, -28.373405, 1.422222, -1.617968, -0.000153, 0.000000, 1496957392.583700, 1.302458, 1.000000, 71.280389, 15.239185, 22.893110, -0.085106 +-33.4204, 42.5945, -28.373202, 1.422222, -1.607407, -0.000153, 0.000000, 1496957392.594200, 1.302467, 1.000000, 71.294611, 15.239185, 22.830549, -0.085106 +-33.4119, 42.6091, -28.372985, 1.388889, -1.643469, -0.000153, 0.000000, 1496957392.603800, 1.302468, 1.000000, 71.308500, 15.239185, 22.830549, -0.085106 +-33.4034, 42.6236, -28.372696, 1.388889, -1.679817, -0.000153, 0.000000, 1496957392.614300, 1.302466, 1.000000, 71.322389, 15.239185, 22.833601, -0.085106 +-33.3949, 42.6379, -28.372408, 1.358333, -1.711030, -0.000153, 0.000000, 1496957392.623800, 1.302482, 1.000000, 71.335972, 15.263599, 22.833601, -0.085106 +-33.3865, 42.652, -28.372055, 1.358333, -1.705272, -0.000153, 0.000000, 1496957392.634200, 1.302510, 1.000000, 71.349555, 15.263599, 22.798504, -0.085106 +-33.378, 42.6659, -28.371651, 1.327778, -1.700876, -0.000115, 0.002883, 1496957392.643900, 1.302504, 1.000000, 71.362833, 15.239185, 22.798504, -0.063830 +-33.3696, 42.6798, -28.371229, 1.327778, -1.600191, -0.000115, 0.000000, 1496957392.654500, 1.302548, 1.000000, 71.376111, 15.239185, 22.740520, -0.063830 +-33.3613, 42.6934, -28.370808, 1.297222, -1.537401, -0.000115, 0.000000, 1496957392.664100, 1.302593, 1.000000, 71.389083, 15.214770, 22.740520, -0.063830 +-33.3529, 42.7069, -28.370386, 1.297222, -1.427754, -0.000115, 0.000000, 1496957392.673500, 1.302592, 1.000000, 71.402055, 15.214770, 22.716106, -0.063830 +-33.3445, 42.7203, -28.369948, 1.266667, -1.347413, -0.000077, 0.003022, 1496957392.684200, 1.302628, 1.000000, 71.414722, 15.202563, 22.716106, -0.042553 +-33.3362, 42.7336, -28.369528, 1.266667, -1.333698, -0.000077, 0.000000, 1496957392.693800, 1.302644, 1.000000, 71.427389, 15.202563, 22.626078, -0.042553 +-33.328, 42.7467, -28.369101, 1.236111, -1.325946, -0.000038, 0.003096, 1496957392.704300, 1.302610, 1.000000, 71.439750, 15.239185, 22.626078, -0.021277 +-33.3197, 42.7597, -28.368717, 1.236111, -1.343958, -0.000038, 0.000000, 1496957392.713900, 1.302620, 1.000000, 71.452111, 15.239185, 22.575724, -0.021277 +-33.3115, 42.7726, -28.368315, 1.208333, -1.253810, 0.000000, 0.003168, 1496957392.724400, 1.302636, 1.000000, 71.464194, 15.275806, 22.575724, 0.000000 +-33.3034, 42.7854, -28.367985, 1.208333, -1.245619, 0.000000, 0.000000, 1496957392.734000, 1.302628, 1.000000, 71.476278, 15.275806, 22.519264, 0.000000 +-33.2952, 42.798, -28.367673, 1.177778, -1.164646, 0.000000, 0.000000, 1496957392.744600, 1.302625, 1.000000, 71.488055, 15.239185, 22.519264, 0.000000 +-33.2871, 42.8106, -28.367437, 1.177778, -1.069663, 0.000000, 0.000000, 1496957392.754100, 1.302663, 1.000000, 71.499833, 15.239185, 22.432287, 0.000000 +-33.279, 42.8231, -28.367226, 1.150000, -0.978902, 0.000077, 0.006656, 1496957392.763600, 1.302638, 1.000000, 71.511333, 15.263599, 22.432287, 0.042553 +-33.2709, 42.8355, -28.367024, 1.150000, -0.926059, 0.000077, 0.000000, 1496957392.774100, 1.302649, 1.000000, 71.522833, 15.263599, 22.386511, 0.042553 +-33.2628, 42.8477, -28.366869, 1.127778, -0.917845, 0.000115, 0.003394, 1496957392.783600, 1.302657, 1.000000, 71.534111, 15.202563, 22.386511, 0.063830 +-33.2548, 42.8599, -28.366751, 1.127778, -0.982880, 0.000115, 0.000000, 1496957392.794200, 1.302638, 1.000000, 71.545389, 15.202563, 22.362097, 0.063830 +-33.2467, 42.872, -28.366648, 1.105556, -0.952472, 0.000230, 0.010386, 1496957392.803600, 1.302643, 1.000000, 71.556444, 15.300221, 22.362097, 0.127660 +-33.2387, 42.884, -28.366579, 1.105556, -0.917578, 0.000230, 0.000000, 1496957392.814100, 1.302598, 1.000000, 71.567500, 15.300221, 22.313269, 0.127660 +-33.2307, 42.8959, -28.366512, 1.083333, -0.928055, 0.000268, 0.003533, 1496957392.823500, 1.302619, 1.000000, 71.578333, 15.239185, 22.313269, 0.148936 +-33.2227, 42.9077, -28.366462, 1.083333, -0.911404, 0.000268, 0.000000, 1496957392.834100, 1.302622, 1.000000, 71.589167, 15.239185, 22.238499, 0.148936 +-33.2147, 42.9194, -28.366415, 1.058333, -0.931599, 0.000344, 0.007233, 1496957392.843500, 1.302622, 1.000000, 71.599750, 15.288014, 22.238499, 0.191489 +-33.2068, 42.9311, -28.366332, 1.058333, -0.936599, 0.000344, 0.000000, 1496957392.854100, 1.302671, 1.000000, 71.610333, 15.288014, 22.331579, 0.191489 +-33.1989, 42.9426, -28.366275, 1.038889, -1.007213, 0.000421, 0.007368, 1496957392.863500, 1.302645, 1.000000, 71.620722, 15.190356, 22.331579, 0.234043 +-33.191, 42.954, -28.366154, 1.038889, -1.024371, 0.000421, 0.000000, 1496957392.874000, 1.302654, 1.000000, 71.631111, 15.190356, 22.348364, 0.234043 +-33.1832, 42.9654, -28.366052, 1.016667, -1.013801, 0.000498, 0.007529, 1496957392.884600, 1.302622, 1.000000, 71.641278, 15.214770, 22.348364, 0.276596 +-33.1754, 42.9766, -28.365906, 1.016667, -0.951138, 0.000498, 0.000000, 1496957392.894200, 1.302615, 1.000000, 71.651444, 15.214770, 22.319372, 0.276596 +-33.1676, 42.9878, -28.365748, 0.997222, -0.932257, 0.000536, 0.003838, 1496957392.904100, 1.302629, 1.000000, 71.661417, 15.263599, 22.319372, 0.297872 +-33.1599, 42.9989, -28.365607, 0.997222, -0.929525, 0.000536, 0.000000, 1496957392.914000, 1.302584, 1.000000, 71.671389, 15.263599, 22.352942, 0.297872 +-33.1521, 43.0099, -28.365417, 0.975000, -0.935643, 0.000574, 0.003926, 1496957392.924700, 1.302596, 1.000000, 71.681139, 15.214770, 22.352942, 0.319149 +-33.1445, 43.0208, -28.365239, 0.975000, -0.987337, 0.000574, 0.000000, 1496957392.934200, 1.302593, 1.000000, 71.690889, 15.214770, 22.345312, 0.319149 +-33.1368, 43.0316, -28.365040, 0.952778, -0.995588, 0.000612, 0.004017, 1496957392.943800, 1.302593, 1.000000, 71.700417, 15.239185, 22.345312, 0.340426 +-33.1291, 43.0423, -28.364823, 0.952778, -0.999544, 0.000612, 0.000000, 1496957392.954400, 1.302580, 1.000000, 71.709944, 15.239185, 22.343786, 0.340426 +-33.1215, 43.0529, -28.364585, 0.933333, -0.971890, 0.000651, 0.004101, 1496957392.963900, 1.302581, 1.000000, 71.719278, 15.214770, 22.343786, 0.361702 +-33.1139, 43.0634, -28.364325, 0.933333, -0.979438, 0.000651, 0.000000, 1496957392.974500, 1.302582, 1.000000, 71.728611, 15.214770, 22.392614, 0.361702 +-33.1063, 43.0738, -28.364069, 0.913889, -1.001874, 0.000651, 0.000000, 1496957392.984100, 1.302588, 1.000000, 71.737750, 15.263599, 22.392614, 0.361702 +-33.0987, 43.0841, -28.363802, 0.913889, -0.984041, 0.000651, 0.000000, 1496957392.994600, 1.302597, 1.000000, 71.746889, 15.263599, 22.429235, 0.361702 +-33.0912, 43.0943, -28.363521, 0.894444, -0.980900, 0.000689, 0.004279, 1496957393.004200, 1.302598, 1.000000, 71.755833, 15.214770, 22.429235, 0.382979 +-33.0836, 43.1045, -28.363227, 0.894444, -0.951155, 0.000689, 0.000000, 1496957393.014300, 1.302605, 1.000000, 71.764778, 15.214770, 22.401770, 0.382979 +-33.0761, 43.1145, -28.362948, 0.875000, -0.937545, 0.000689, 0.000000, 1496957393.023800, 1.302626, 1.000000, 71.773528, 15.226978, 22.401770, 0.382979 +-33.0686, 43.1245, -28.362653, 0.875000, -0.938948, 0.000689, 0.000000, 1496957393.034300, 1.302654, 1.000000, 71.782278, 15.226978, 22.366674, 0.382979 +-33.0611, 43.1343, -28.362366, 0.855556, -0.952019, 0.000689, 0.000000, 1496957393.043800, 1.302660, 1.000000, 71.790833, 15.288014, 22.366674, 0.382979 +-33.0536, 43.1441, -28.362079, 0.855556, -0.930472, 0.000689, 0.000000, 1496957393.054400, 1.302659, 1.000000, 71.799389, 15.288014, 22.323950, 0.382979 +-33.0462, 43.1537, -28.361791, 0.836111, -0.938226, 0.000689, 0.000000, 1496957393.064000, 1.302685, 1.000000, 71.807750, 15.263599, 22.323950, 0.382979 +-33.0392, 43.163, -28.361530, 0.836111, -0.955961, 0.000689, 0.000000, 1496957393.074500, 1.302504, 1.000000, 71.816111, 15.263599, 22.406347, 0.382979 +-33.0329, 43.1718, -28.361186, 0.819444, -0.932255, 0.000689, 0.000000, 1496957393.084100, 1.302500, 1.000000, 71.824305, 15.275806, 22.406347, 0.382979 +-33.0265, 43.1805, -28.360867, 0.819444, -0.944301, 0.000689, 0.000000, 1496957393.094600, 1.302519, 1.000000, 71.832500, 15.275806, 22.394140, 0.382979 +-33.0203, 43.1891, -28.360555, 0.802778, -0.979257, 0.000689, 0.000000, 1496957393.104200, 1.302511, 1.000000, 71.840528, 15.226978, 22.394140, 0.382979 +-33.014, 43.1976, -28.360257, 0.802778, -0.948465, 0.000689, 0.000000, 1496957393.113700, 1.302500, 1.000000, 71.848555, 15.226978, 22.442970, 0.382979 +-33.0078, 43.2061, -28.359972, 0.783333, -0.902945, 0.000689, 0.000000, 1496957393.124200, 1.302504, 1.000000, 71.856389, 15.288014, 22.442970, 0.382979 +-33.0016, 43.2145, -28.359690, 0.783333, -0.879281, 0.000689, 0.000000, 1496957393.133600, 1.302471, 1.000000, 71.864222, 15.288014, 22.438393, 0.382979 +-32.9954, 43.2227, -28.359430, 0.763889, -0.893682, 0.000689, 0.000000, 1496957393.144300, 1.302456, 1.000000, 71.871861, 15.239185, 22.438393, 0.382979 +-32.9892, 43.2309, -28.359176, 0.763889, -0.868199, 0.000689, 0.000000, 1496957393.153800, 1.302460, 1.000000, 71.879500, 15.239185, 22.412451, 0.382979 +-32.9831, 43.239, -28.358927, 0.747222, -0.910601, 0.000727, 0.005122, 1496957393.164300, 1.302446, 1.000000, 71.886972, 15.263599, 22.412451, 0.404255 +-32.977, 43.247, -28.358688, 0.747222, -0.859987, 0.000727, 0.000000, 1496957393.173800, 1.302412, 1.000000, 71.894444, 15.263599, 22.444496, 0.404255 +-32.9708, 43.255, -28.358435, 0.730556, -0.857703, 0.000727, 0.000000, 1496957393.184400, 1.302390, 1.000000, 71.901750, 15.165942, 22.444496, 0.404255 +-32.9647, 43.2628, -28.358223, 0.730556, -0.893491, 0.000727, 0.000000, 1496957393.193900, 1.302363, 1.000000, 71.909055, 15.165942, 22.481117, 0.404255 +-32.9586, 43.2705, -28.357982, 0.713889, -0.880616, 0.000727, 0.000000, 1496957393.204400, 1.302366, 1.000000, 71.916194, 15.190356, 22.481117, 0.404255 +-32.9526, 43.2782, -28.357758, 0.713889, -0.875985, 0.000727, 0.000000, 1496957393.213900, 1.302375, 1.000000, 71.923333, 15.190356, 22.453651, 0.404255 +-32.9465, 43.2858, -28.357542, 0.694444, -0.878341, 0.000765, 0.005512, 1496957393.224600, 1.302363, 1.000000, 71.930278, 15.263599, 22.453651, 0.425532 +-32.9404, 43.2933, -28.357316, 0.694444, -0.883640, 0.000765, 0.000000, 1496957393.234100, 1.302378, 1.000000, 71.937222, 15.263599, 22.473488, 0.425532 +-32.9344, 43.3007, -28.357098, 0.680556, -0.870169, 0.000804, 0.005624, 1496957393.243500, 1.302345, 1.000000, 71.944028, 15.251392, 22.473488, 0.446809 +-32.9283, 43.308, -28.356877, 0.680556, -0.871561, 0.000804, 0.000000, 1496957393.254000, 1.302355, 1.000000, 71.950833, 15.251392, 22.413977, 0.446809 +-32.9223, 43.3152, -28.356666, 0.661111, -0.853475, 0.000804, 0.000000, 1496957393.264500, 1.302376, 1.000000, 71.957444, 15.153734, 22.413977, 0.446809 +-32.9163, 43.3224, -28.356450, 0.661111, -0.841764, 0.000804, 0.000000, 1496957393.274100, 1.302403, 1.000000, 71.964055, 15.153734, 22.400244, 0.446809 +-32.9104, 43.3294, -28.356228, 0.647222, -0.852978, 0.000804, 0.000000, 1496957393.283500, 1.302380, 1.000000, 71.970528, 15.251392, 22.400244, 0.446809 +-32.9044, 43.3364, -28.355996, 0.647222, -0.869265, 0.000804, 0.000000, 1496957393.294000, 1.302390, 1.000000, 71.977000, 15.251392, 22.403296, 0.446809 +-32.8985, 43.3433, -28.355756, 0.627778, -0.892852, 0.000804, 0.000000, 1496957393.304600, 1.302414, 1.000000, 71.983278, 15.202563, 22.403296, 0.446809 +-32.8926, 43.3501, -28.355499, 0.627778, -0.900244, 0.000804, 0.000000, 1496957393.314200, 1.302430, 1.000000, 71.989555, 15.202563, 22.426184, 0.446809 +-32.8867, 43.3568, -28.355240, 0.613889, -0.911929, 0.000804, 0.000000, 1496957393.323700, 1.302438, 1.000000, 71.995694, 15.226978, 22.426184, 0.446809 +-32.8808, 43.3634, -28.354946, 0.613889, -0.943057, 0.000804, 0.000000, 1496957393.334200, 1.302481, 1.000000, 72.001833, 15.226978, 22.389563, 0.446809 +-32.8749, 43.37, -28.354663, 0.597222, -0.938666, 0.000842, 0.006409, 1496957393.343800, 1.302493, 1.000000, 72.007805, 15.239185, 22.389563, 0.468085 +-32.8691, 43.3764, -28.354362, 0.597222, -0.937774, 0.000842, 0.000000, 1496957393.354300, 1.302517, 1.000000, 72.013778, 15.239185, 22.284275, 0.468085 +-32.8633, 43.3828, -28.354051, 0.583333, -0.911622, 0.000880, 0.006561, 1496957393.364100, 1.302589, 1.000000, 72.019611, 15.239185, 22.284275, 0.489362 +-32.8575, 43.389, -28.353745, 0.583333, -0.903748, 0.000880, 0.000000, 1496957393.374600, 1.302584, 1.000000, 72.025444, 15.239185, 22.272068, 0.489362 +-32.8517, 43.3952, -28.353419, 0.566667, -0.896049, 0.000919, 0.006754, 1496957393.384100, 1.302602, 1.000000, 72.031111, 15.214770, 22.272068, 0.510638 +-32.846, 43.4013, -28.353106, 0.566667, -0.907715, 0.000919, 0.000000, 1496957393.393600, 1.302608, 1.000000, 72.036778, 15.214770, 22.191196, 0.510638 +-32.8402, 43.4073, -28.352774, 0.547222, -0.911000, 0.000919, 0.000000, 1496957393.404500, 1.302642, 1.000000, 72.042250, 15.214770, 22.191196, 0.510638 +-32.8345, 43.4132, -28.352448, 0.547222, -0.912424, 0.000919, 0.000000, 1496957393.414200, 1.302640, 1.000000, 72.047722, 15.214770, 22.146944, 0.510638 +-32.8288, 43.419, -28.352106, 0.533333, -0.916648, 0.000957, 0.007177, 1496957393.424200, 1.302623, 1.000000, 72.053055, 15.263599, 22.146944, 0.531915 +-32.8231, 43.4247, -28.351769, 0.533333, -0.934052, 0.000957, 0.000000, 1496957393.433800, 1.302631, 1.000000, 72.058389, 15.263599, 22.121004, 0.531915 +-32.8175, 43.4304, -28.351431, 0.516667, -0.913690, 0.000995, 0.007408, 1496957393.444300, 1.302674, 1.000000, 72.063555, 15.226978, 22.121004, 0.553191 +-32.8119, 43.4359, -28.351095, 0.516667, -0.938778, 0.000995, 0.000000, 1496957393.453800, 1.302672, 1.000000, 72.068722, 15.226978, 22.053864, 0.553191 +-32.8063, 43.4414, -28.350758, 0.500000, -0.921988, 0.001033, 0.007655, 1496957393.464400, 1.302659, 1.000000, 72.073722, 15.239185, 22.053864, 0.574468 +-32.8007, 43.4468, -28.350415, 0.500000, -0.932469, 0.001033, 0.000000, 1496957393.473900, 1.302664, 1.000000, 72.078722, 15.239185, 22.035553, 0.574468 +-32.7952, 43.4521, -28.350100, 0.488889, -0.932700, 0.001072, 0.007829, 1496957393.484500, 1.302646, 1.000000, 72.083611, 15.239185, 22.035553, 0.595745 +-32.7896, 43.4573, -28.349760, 0.488889, -0.914499, 0.001072, 0.000000, 1496957393.494000, 1.302649, 1.000000, 72.088500, 15.239185, 22.001984, 0.595745 +-32.7841, 43.4624, -28.349437, 0.469444, -0.900908, 0.001110, 0.008153, 1496957393.504700, 1.302642, 1.000000, 72.093194, 15.288014, 22.001984, 0.617021 +-32.7732, 43.4723, -28.348803, 0.469444, -0.898046, 0.001110, 0.000000, 1496957393.514200, 1.302623, 1.000000, 72.097889, 15.288014, 22.018768, 0.617021 +-32.7732, 43.4723, -28.348803, 0.452778, -0.898046, 0.001072, -0.008453, 1496957393.523500, 1.302623, 1.000000, 72.102417, 15.288014, 22.018768, 0.595745 +-32.7678, 43.4772, -28.348499, 0.452778, -0.871138, 0.001072, 0.000000, 1496957393.534100, 1.302610, 1.000000, 72.106944, 15.288014, 21.997406, 0.595745 +-32.7624, 43.482, -28.348189, 0.441667, -0.880719, 0.001072, 0.000000, 1496957393.543600, 1.302641, 1.000000, 72.111361, 15.288014, 21.997406, 0.595745 +-32.757, 43.4867, -28.347887, 0.441667, -0.877043, 0.001072, 0.000000, 1496957393.554200, 1.302610, 1.000000, 72.115778, 15.288014, 21.994354, 0.595745 +-32.7516, 43.4913, -28.347588, 0.425000, -0.857724, 0.001072, 0.000000, 1496957393.563800, 1.302607, 1.000000, 72.120028, 15.251392, 21.994354, 0.595745 +-32.7463, 43.4958, -28.347292, 0.425000, -0.857215, 0.001072, 0.000000, 1496957393.574300, 1.302624, 1.000000, 72.124278, 15.251392, 21.939423, 0.595745 +-32.741, 43.5002, -28.346993, 0.405556, -0.831548, 0.001072, 0.000000, 1496957393.583900, 1.302610, 1.000000, 72.128333, 15.190356, 21.939423, 0.595745 +-32.7356, 43.5046, -28.346693, 0.405556, -0.814614, 0.001072, 0.000000, 1496957393.594500, 1.302616, 1.000000, 72.132389, 15.190356, 21.915007, 0.595745 +-32.7303, 43.5088, -28.346390, 0.391667, -0.805647, 0.001072, 0.000000, 1496957393.604100, 1.302580, 1.000000, 72.136305, 15.226978, 21.915007, 0.595745 +-32.7251, 43.5131, -28.346090, 0.391667, -0.793771, 0.001072, 0.000000, 1496957393.614600, 1.302660, 1.000000, 72.140222, 15.226978, 21.884489, 0.595745 +-32.7198, 43.5172, -28.345780, 0.383333, -0.768954, 0.001072, 0.000000, 1496957393.624200, 1.302618, 1.000000, 72.144055, 15.239185, 21.884489, 0.595745 +-32.7145, 43.5212, -28.345470, 0.383333, -0.757988, 0.001072, 0.000000, 1496957393.633700, 1.302639, 1.000000, 72.147889, 15.239185, 21.792934, 0.595745 +-32.7093, 43.5252, -28.345156, 0.366667, -0.748126, 0.001072, 0.000000, 1496957393.644200, 1.302642, 1.000000, 72.151555, 15.239185, 21.792934, 0.595745 +-32.704, 43.5291, -28.344835, 0.366667, -0.739334, 0.001072, 0.000000, 1496957393.653800, 1.302629, 1.000000, 72.155222, 15.239185, 21.713589, 0.595745 +-32.6988, 43.533, -28.344513, 0.347222, -0.748105, 0.001072, 0.000000, 1496957393.664300, 1.302665, 1.000000, 72.158694, 15.275806, 21.713589, 0.595745 +-32.6936, 43.5367, -28.344177, 0.347222, -0.740239, 0.001072, 0.000000, 1496957393.673800, 1.302639, 1.000000, 72.162167, 15.275806, 21.669336, 0.595745 +-32.6884, 43.5404, -28.343837, 0.336111, -0.732508, 0.001072, 0.000000, 1496957393.684300, 1.302706, 1.000000, 72.165528, 15.251392, 21.669336, 0.595745 +-32.6833, 43.5441, -28.343496, 0.336111, -0.723972, 0.001072, 0.000000, 1496957393.693800, 1.302704, 1.000000, 72.168889, 15.251392, 21.666285, 0.595745 +-32.6781, 43.5476, -28.343148, 0.327778, -0.717167, 0.001072, 0.000000, 1496957393.704400, 1.302741, 1.000000, 72.172167, 15.190356, 21.666285, 0.595745 +-32.673, 43.5511, -28.342791, 0.327778, -0.699762, 0.001072, 0.000000, 1496957393.713900, 1.302737, 1.000000, 72.175444, 15.190356, 21.602198, 0.595745 +-32.6679, 43.5545, -28.342430, 0.316667, -0.704782, 0.001072, 0.000000, 1496957393.724500, 1.302733, 1.000000, 72.178611, 15.251392, 21.602198, 0.595745 +-32.6628, 43.5579, -28.342069, 0.316667, -0.685256, 0.001072, 0.000000, 1496957393.734100, 1.302779, 1.000000, 72.181778, 15.251392, 21.564051, 0.595745 +-32.6577, 43.5611, -28.341701, 0.302778, -0.680183, 0.001072, 0.000000, 1496957393.743500, 1.302777, 1.000000, 72.184805, 15.239185, 21.564051, 0.595745 +-32.6526, 43.5644, -28.341334, 0.302778, -0.653266, 0.001072, 0.000000, 1496957393.754000, 1.302787, 1.000000, 72.187833, 15.239185, 21.521324, 0.595745 +-32.6475, 43.5675, -28.340960, 0.208333, -0.637846, 0.001072, 0.000000, 1496957393.764500, 1.302797, 1.000000, 72.189917, 15.275806, 21.521324, 0.595745 +-32.6425, 43.5707, -28.340592, 0.208333, -0.635314, 0.001072, 0.000000, 1496957393.774000, 1.302755, 1.000000, 72.192000, 15.275806, 21.507591, 0.595745 +-32.6375, 43.5737, -28.340226, 0.000000, -0.633437, 0.001072, 0.000000, 1496957393.783500, 1.302783, 1.000000, 72.192000, 15.275806, 21.507591, 0.595745 +-32.6325, 43.5767, -28.339857, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.794400, 1.302779, 1.000000, 72.192000, 15.275806, 21.460289, 0.595745 +-32.6275, 43.5796, -28.339487, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.803800, 1.302739, 1.000000, 72.192000, 15.226978, 21.460289, 0.595745 +-32.6225, 43.5825, -28.339124, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.814500, 1.302778, 1.000000, 72.192000, 15.226978, 21.571680, 0.595745 +-32.6176, 43.5853, -28.338764, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.824100, 1.302775, 1.000000, 72.192000, 15.239185, 21.571680, 0.595745 +-32.6126, 43.5881, -28.338400, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.833500, 1.302738, 1.000000, 72.192000, 15.239185, 21.510643, 0.595745 +-32.6077, 43.5908, -28.338046, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.844200, 1.302728, 1.000000, 72.192000, 15.226978, 21.510643, 0.595745 +-32.6028, 43.5935, -28.337698, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.853700, 1.302715, 1.000000, 72.192000, 15.226978, 21.510643, 0.595745 +-32.5979, 43.5961, -28.337350, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.864300, 1.302694, 1.000000, 72.192000, 15.288014, 21.510643, 0.595745 +-32.593, 43.5986, -28.337003, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.873800, 1.302681, 1.000000, 72.192000, 15.288014, 21.539635, 0.595745 +-32.5881, 43.6011, -28.336655, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.884400, 1.302691, 1.000000, 72.192000, 15.239185, 21.539635, 0.595745 +-32.5832, 43.6036, -28.336310, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.893900, 1.302688, 1.000000, 72.192000, 15.239185, 21.448082, 0.595745 +-32.5783, 43.606, -28.335964, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.905800, 1.302673, 1.000000, 72.192000, 15.239185, 21.448082, 0.595745 +-32.5734, 43.6083, -28.335613, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.914800, 1.302633, 1.000000, 72.192000, 15.239185, 21.477074, 0.595745 +-32.5686, 43.6107, -28.335259, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.923700, 1.302652, 1.000000, 72.192000, 15.239185, 21.477074, 0.595745 +-32.5637, 43.6129, -28.334894, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.934400, 1.302642, 1.000000, 72.192000, 15.239185, 21.556419, 0.595745 +-32.5589, 43.6151, -28.334530, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.944000, 1.302618, 1.000000, 72.192000, 15.214770, 21.556419, 0.595745 +-32.554, 43.6173, -28.334156, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.954600, 1.302655, 1.000000, 72.192000, 15.214770, 21.557945, 0.595745 +-32.5492, 43.6194, -28.333775, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.964200, 1.302654, 1.000000, 72.192000, 15.239185, 21.557945, 0.595745 +-32.5443, 43.6215, -28.333389, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.973700, 1.302654, 1.000000, 72.192000, 15.239185, 21.583887, 0.595745 +-32.5395, 43.6235, -28.333000, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.984200, 1.302699, 1.000000, 72.192000, 15.239185, 21.583887, 0.595745 +-32.5347, 43.6255, -28.332609, 0.000000, 0.000000, 0.001072, 0.000000, 1496957393.993800, 1.302673, 1.000000, 72.192000, 15.239185, 21.593042, 0.595745 +-32.5299, 43.6274, -28.332208, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.004500, 1.302662, 1.000000, 72.192000, 15.239185, 21.593042, 0.595745 +-32.5251, 43.6293, -28.331811, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.014600, 1.302703, 1.000000, 72.192000, 15.239185, 21.609827, 0.595745 +-32.5203, 43.6311, -28.331410, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.024200, 1.302684, 1.000000, 72.192000, 15.288014, 21.609827, 0.595745 +-32.5156, 43.6329, -28.331010, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.033600, 1.302706, 1.000000, 72.192000, 15.288014, 21.536583, 0.595745 +-32.5108, 43.6346, -28.330612, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.044200, 1.302716, 1.000000, 72.192000, 15.226978, 21.536583, 0.595745 +-32.5061, 43.6363, -28.330210, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.053600, 1.302737, 1.000000, 72.192000, 15.226978, 21.550316, 0.595745 +-32.5013, 43.638, -28.329814, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.064100, 1.302720, 1.000000, 72.192000, 15.239185, 21.550316, 0.595745 +-32.4974, 43.6391, -28.329429, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.073500, 1.302391, 1.000000, 72.192000, 15.239185, 21.532005, 0.595745 +-32.4941, 43.6397, -28.329019, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.084200, 1.302386, 1.000000, 72.192000, 15.178149, 21.532005, 0.595745 +-32.4909, 43.6403, -28.328621, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.093700, 1.302361, 1.000000, 72.192000, 15.178149, 21.596094, 0.595745 +-32.4877, 43.6408, -28.328229, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.104300, 1.302346, 1.000000, 72.192000, 15.251392, 21.596094, 0.595745 +-32.4844, 43.6413, -28.327850, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.113800, 1.302335, 1.000000, 72.192000, 15.251392, 21.623560, 0.595745 +-32.4812, 43.6418, -28.327494, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.124300, 1.302357, 1.000000, 72.192000, 15.239185, 21.623560, 0.595745 +-32.478, 43.6423, -28.327144, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.133900, 1.302338, 1.000000, 72.192000, 15.239185, 21.588465, 0.595745 +-32.4747, 43.6428, -28.326810, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.144500, 1.302370, 1.000000, 72.192000, 15.239185, 21.588465, 0.595745 +-32.4715, 43.6433, -28.326491, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.154100, 1.302366, 1.000000, 72.192000, 15.202563, 21.554893, 0.595745 +-32.4683, 43.6437, -28.326183, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.163600, 1.302314, 1.000000, 72.192000, 15.239185, 21.554893, 0.595745 +-32.465, 43.6442, -28.325887, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.174100, 1.302353, 1.000000, 72.192000, 15.239185, 21.565577, 0.595745 +-32.4618, 43.6447, -28.325597, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.183600, 1.302340, 1.000000, 72.192000, 15.239185, 21.565577, 0.595745 +-32.4586, 43.6452, -28.325314, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.194100, 1.302379, 1.000000, 72.192000, 15.239185, 21.625086, 0.595745 +-32.4553, 43.6457, -28.325039, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.203600, 1.302391, 1.000000, 72.192000, 15.251392, 21.625086, 0.595745 +-32.452, 43.6462, -28.324754, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.214100, 1.302372, 1.000000, 72.192000, 15.251392, 21.615931, 0.595745 +-32.4488, 43.6467, -28.324472, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.223500, 1.302356, 1.000000, 72.192000, 15.263599, 21.615931, 0.595745 +-32.4455, 43.6473, -28.324195, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.234000, 1.302361, 1.000000, 72.192000, 15.263599, 21.634241, 0.595745 +-32.4422, 43.6478, -28.323907, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.243500, 1.302346, 1.000000, 72.192000, 15.263599, 21.634241, 0.595745 +-32.4389, 43.6484, -28.323610, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.254100, 1.302348, 1.000000, 72.192000, 15.239185, 21.629663, 0.595745 +-32.4356, 43.649, -28.323309, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.263600, 1.302357, 1.000000, 72.192000, 15.239185, 21.629663, 0.595745 +-32.4323, 43.6497, -28.322989, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.274200, 1.302346, 1.000000, 72.192000, 15.239185, 21.634241, 0.595745 +-32.4289, 43.6503, -28.322661, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.283700, 1.302338, 1.000000, 72.192000, 15.251392, 21.634241, 0.595745 +-32.4256, 43.651, -28.322314, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.294200, 1.302377, 1.000000, 72.192000, 15.251392, 21.666285, 0.595745 +-32.4223, 43.6517, -28.321954, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.303600, 1.302358, 1.000000, 72.192000, 15.300221, 21.666285, 0.595745 +-32.4189, 43.6524, -28.321581, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.314100, 1.302354, 1.000000, 72.192000, 15.300221, 21.707485, 0.595745 +-32.4156, 43.6532, -28.321183, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.323600, 1.302379, 1.000000, 72.192000, 15.214770, 21.707485, 0.595745 +-32.4122, 43.6539, -28.320769, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.334200, 1.302405, 1.000000, 72.192000, 15.214770, 21.779202, 0.595745 +-32.4089, 43.6547, -28.320339, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.343700, 1.302332, 1.000000, 72.192000, 15.263599, 21.779202, 0.595745 +-32.4055, 43.6554, -28.319892, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.354200, 1.302359, 1.000000, 72.192000, 15.263599, 21.876860, 0.595745 +-32.4022, 43.6562, -28.319429, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.363700, 1.302374, 1.000000, 72.192000, 15.239185, 21.876860, 0.595745 +-32.3988, 43.657, -28.318952, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.374400, 1.302401, 1.000000, 72.192000, 15.239185, 21.905851, 0.595745 +-32.3955, 43.6578, -28.318462, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.384400, 1.302370, 1.000000, 72.192000, 15.239185, 21.905851, 0.595745 +-32.3921, 43.6586, -28.317963, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.394000, 1.302354, 1.000000, 72.192000, 15.263599, 21.950104, 0.595745 +-32.3887, 43.6593, -28.317460, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.405700, 1.302348, 1.000000, 72.192000, 15.190356, 21.950104, 0.595745 +-32.3854, 43.6601, -28.316952, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.415000, 1.302359, 1.000000, 72.192000, 15.190356, 22.072176, 0.595745 +-32.382, 43.6608, -28.316438, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.424100, 1.302344, 1.000000, 72.192000, 15.263599, 22.072176, 0.595745 +-32.3786, 43.6616, -28.315934, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.433500, 1.302343, 1.000000, 72.192000, 15.263599, 22.198826, 0.595745 +-32.3753, 43.6623, -28.315435, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.444100, 1.302337, 1.000000, 72.192000, 15.214770, 22.198826, 0.595745 +-32.3719, 43.663, -28.314940, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.453500, 1.302313, 1.000000, 72.192000, 15.214770, 22.325476, 0.595745 +-32.3686, 43.6637, -28.314457, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.464100, 1.302298, 1.000000, 72.192000, 15.324636, 22.325476, 0.595745 +-32.3652, 43.6644, -28.313986, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.473500, 1.302303, 1.000000, 72.192000, 15.324636, 22.433813, 0.595745 +-32.3618, 43.6651, -28.313535, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.484100, 1.302293, 1.000000, 72.192000, 15.324636, 22.433813, 0.595745 +-32.3585, 43.6658, -28.313090, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.493600, 1.302279, 1.000000, 72.192000, 15.275806, 22.584879, 0.595745 +-32.3551, 43.6665, -28.312660, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.504400, 1.302290, 1.000000, 72.192000, 15.251392, 22.584879, 0.595745 +-32.3484, 43.6678, -28.311845, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.514000, 1.302292, 1.000000, 72.192000, 15.251392, 22.688641, 0.595745 +-32.3484, 43.6678, -28.311845, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.524500, 1.302292, 1.000000, 72.192000, 15.239185, 22.688641, 0.595745 +-32.345, 43.6685, -28.311457, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.534000, 1.302273, 1.000000, 72.192000, 15.239185, 22.850386, 0.595745 +-32.3417, 43.6691, -28.311077, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.544600, 1.302328, 1.000000, 72.192000, 15.239185, 22.850386, 0.595745 +-32.3383, 43.6697, -28.310707, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.554500, 1.302313, 1.000000, 72.192000, 15.239185, 22.981613, 0.595745 +-32.3349, 43.6703, -28.310344, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.563900, 1.302272, 1.000000, 72.192000, 15.263599, 22.981613, 0.595745 +-32.3316, 43.671, -28.309984, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.574500, 1.302314, 1.000000, 72.192000, 15.263599, 23.042648, 0.595745 +-32.3282, 43.6716, -28.309622, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.584100, 1.302298, 1.000000, 72.192000, 15.288014, 23.042648, 0.595745 +-32.3248, 43.6722, -28.309256, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.594500, 1.302291, 1.000000, 72.192000, 15.288014, 23.190662, 0.595745 +-32.3214, 43.6729, -28.308888, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.604100, 1.302310, 1.000000, 72.192000, 15.202563, 23.190662, 0.595745 +-32.3181, 43.6735, -28.308515, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.613600, 1.302333, 1.000000, 72.192000, 15.202563, 23.215076, 0.595745 +-32.3147, 43.6741, -28.308126, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.623700, 1.302339, 1.000000, 72.192000, 15.226978, 23.215076, 0.595745 +-32.3113, 43.6747, -28.307728, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.634200, 1.302333, 1.000000, 72.192000, 15.226978, 23.334097, 0.595745 +-32.3079, 43.6754, -28.307319, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.643800, 1.302339, 1.000000, 72.192000, 15.239185, 23.334097, 0.595745 +-32.3046, 43.676, -28.306900, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.654300, 1.302339, 1.000000, 72.192000, 15.239185, 23.508049, 0.595745 +-32.3012, 43.6767, -28.306461, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.663900, 1.302376, 1.000000, 72.192000, 15.214770, 23.508049, 0.595745 +-32.2978, 43.6773, -28.306015, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.674500, 1.302350, 1.000000, 72.192000, 15.214770, 23.569086, 0.595745 +-32.2944, 43.6779, -28.305561, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.684100, 1.302341, 1.000000, 72.192000, 15.288014, 23.569086, 0.595745 +-32.291, 43.6786, -28.305096, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.693600, 1.302356, 1.000000, 72.192000, 15.288014, 23.639277, 0.595745 +-32.2876, 43.6793, -28.304620, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.704200, 1.302366, 1.000000, 72.192000, 15.251392, 23.639277, 0.595745 +-32.2842, 43.6799, -28.304139, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.713600, 1.302361, 1.000000, 72.192000, 15.251392, 23.738461, 0.595745 +-32.2808, 43.6806, -28.303656, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.724100, 1.302364, 1.000000, 72.192000, 15.214770, 23.738461, 0.595745 +-32.2774, 43.6812, -28.303168, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.733600, 1.302379, 1.000000, 72.192000, 15.214770, 23.823912, 0.595745 +-32.274, 43.6819, -28.302685, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.744100, 1.302356, 1.000000, 72.192000, 15.190356, 23.823912, 0.595745 +-32.2706, 43.6826, -28.302197, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.753500, 1.302371, 1.000000, 72.192000, 15.190356, 23.953613, 0.595745 +-32.2672, 43.6833, -28.301714, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.764000, 1.302379, 1.000000, 72.192000, 15.214770, 23.953613, 0.595745 +-32.2637, 43.6839, -28.301240, 0.000000, 0.000000, 0.001110, 0.000000, 1496957394.774600, 1.302373, 1.000000, 72.192000, 15.214770, 24.103151, 0.617021 +-32.2603, 43.6846, -28.300767, 0.000000, 0.000000, 0.001110, 0.000000, 1496957394.784100, 1.302375, 1.000000, 72.192000, 15.239185, 24.103151, 0.617021 +-32.2569, 43.6853, -28.300300, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.793500, 1.302380, 1.000000, 72.192000, 15.239185, 24.165712, 0.595745 +-32.2535, 43.686, -28.299835, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.804100, 1.302374, 1.000000, 72.192000, 15.239185, 24.165712, 0.595745 +-32.25, 43.6866, -28.299382, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.813500, 1.302382, 1.000000, 72.192000, 15.239185, 24.274052, 0.595745 +-32.2466, 43.6873, -28.298930, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.824300, 1.302376, 1.000000, 72.192000, 15.275806, 24.274052, 0.595745 +-32.2432, 43.688, -28.298482, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.833800, 1.302380, 1.000000, 72.192000, 15.275806, 24.350348, 0.595745 +-32.2397, 43.6886, -28.298037, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.844300, 1.302374, 1.000000, 72.192000, 15.263599, 24.350348, 0.595745 +-32.2363, 43.6893, -28.297592, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.853900, 1.302361, 1.000000, 72.192000, 15.263599, 24.530403, 0.595745 +-32.2329, 43.69, -28.297157, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.864400, 1.302368, 1.000000, 72.192000, 15.251392, 24.530403, 0.595745 +-32.2294, 43.6906, -28.296718, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.873900, 1.302346, 1.000000, 72.192000, 15.251392, 24.693676, 0.595745 +-32.226, 43.6913, -28.296279, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.885200, 1.302373, 1.000000, 72.192000, 15.312428, 24.693676, 0.595745 +-32.2225, 43.6919, -28.295843, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.893900, 1.302349, 1.000000, 72.192000, 15.312428, 24.831007, 0.595745 +-32.2191, 43.6925, -28.295407, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.904400, 1.302354, 1.000000, 72.192000, 15.214770, 24.831007, 0.595745 +-32.2157, 43.6931, -28.294967, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.914600, 1.302371, 1.000000, 72.192000, 15.214770, 25.049210, 0.595745 +-32.2122, 43.6938, -28.294525, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.925100, 1.302334, 1.000000, 72.192000, 15.239185, 25.049210, 0.595745 +-32.2088, 43.6944, -28.294084, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.933600, 1.302324, 1.000000, 72.192000, 15.239185, 25.172808, 0.595745 +-32.2053, 43.695, -28.293642, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.944300, 1.302356, 1.000000, 72.192000, 15.226978, 25.172808, 0.595745 +-32.2019, 43.6956, -28.293197, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.953800, 1.302334, 1.000000, 72.192000, 15.226978, 25.181963, 0.595745 +-32.1985, 43.6962, -28.292748, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.964300, 1.302345, 1.000000, 72.192000, 15.275806, 25.181963, 0.595745 +-32.195, 43.6968, -28.292301, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.973800, 1.302351, 1.000000, 72.192000, 15.275806, 25.174334, 0.595745 +-32.1916, 43.6974, -28.291852, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.984500, 1.302339, 1.000000, 72.192000, 15.226978, 25.174334, 0.595745 +-32.1881, 43.6981, -28.291399, 0.000000, 0.000000, 0.001072, 0.000000, 1496957394.994100, 1.302325, 1.000000, 72.192000, 15.226978, 25.127031, 0.595745 +-32.1847, 43.6987, -28.290944, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.004900, 1.302315, 1.000000, 72.192000, 15.214770, 25.127031, 0.595745 +-32.1812, 43.6993, -28.290490, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.013500, 1.302306, 1.000000, 72.192000, 15.214770, 25.142290, 0.595745 +-32.1778, 43.6999, -28.290034, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.024100, 1.302340, 1.000000, 72.192000, 15.251392, 25.142290, 0.595745 +-32.1743, 43.7005, -28.289577, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.034600, 1.302338, 1.000000, 72.192000, 15.251392, 25.180437, 0.595745 +-32.1709, 43.7011, -28.289119, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.044200, 1.302325, 1.000000, 72.192000, 15.214770, 25.180437, 0.595745 +-32.1674, 43.7017, -28.288657, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.053700, 1.302355, 1.000000, 72.192000, 15.214770, 25.127031, 0.595745 +-32.1639, 43.7023, -28.288199, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.064200, 1.302355, 1.000000, 72.192000, 15.263599, 25.127031, 0.595745 +-32.1618, 43.7022, -28.287748, 0.000000, 0.000000, 0.001110, 0.000000, 1496957395.073600, 1.301754, 1.000000, 72.192000, 15.263599, 25.157549, 0.617021 +-32.1609, 43.7014, -28.287256, 0.000000, 0.000000, 0.001110, 0.000000, 1496957395.084200, 1.301784, 1.000000, 72.192000, 15.263599, 25.157549, 0.617021 +-32.16, 43.7006, -28.286762, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.093700, 1.301791, 1.000000, 72.192000, 15.239185, 25.156023, 0.595745 +-32.1591, 43.6998, -28.286272, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.104200, 1.301781, 1.000000, 72.192000, 15.251392, 25.156023, 0.595745 +-32.1582, 43.699, -28.285780, 0.000000, 0.000000, 0.001110, 0.000000, 1496957395.113800, 1.301807, 1.000000, 72.192000, 15.251392, 25.192646, 0.617021 +-32.1573, 43.6983, -28.285282, 0.000000, 0.000000, 0.001110, 0.000000, 1496957395.124300, 1.301811, 1.000000, 72.192000, 15.202563, 25.192646, 0.617021 +-32.1564, 43.6975, -28.284787, 0.000000, 0.000000, 0.001110, 0.000000, 1496957395.134200, 1.301808, 1.000000, 72.192000, 15.202563, 25.116350, 0.617021 +-32.1555, 43.6967, -28.284293, 0.000000, 0.000000, 0.001110, 0.000000, 1496957395.143700, 1.301805, 1.000000, 72.192000, 15.202563, 25.116350, 0.617021 +-32.1546, 43.6959, -28.283796, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.154300, 1.301790, 1.000000, 72.192000, 15.214770, 25.142290, 0.595745 +-32.1537, 43.6952, -28.283300, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.163800, 1.301766, 1.000000, 72.192000, 15.251392, 25.142290, 0.595745 +-32.1528, 43.6944, -28.282799, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.174300, 1.301753, 1.000000, 72.192000, 15.251392, 25.107195, 0.595745 +-32.1519, 43.6936, -28.282301, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.183800, 1.301813, 1.000000, 72.192000, 15.165942, 25.107195, 0.595745 +-32.151, 43.6928, -28.281804, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.194400, 1.301779, 1.000000, 72.192000, 15.165942, 25.056839, 0.595745 +-32.15, 43.692, -28.281303, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.204000, 1.301788, 1.000000, 72.192000, 15.214770, 25.056839, 0.595745 +-32.1491, 43.6912, -28.280805, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.214600, 1.301780, 1.000000, 72.192000, 15.214770, 25.101091, 0.595745 +-32.1482, 43.6904, -28.280304, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.224300, 1.301743, 1.000000, 72.192000, 15.251392, 25.101091, 0.595745 +-32.1473, 43.6896, -28.279809, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.233800, 1.301757, 1.000000, 72.192000, 15.251392, 25.052261, 0.595745 +-32.1464, 43.6888, -28.279306, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.244300, 1.301751, 1.000000, 72.192000, 15.214770, 25.052261, 0.595745 +-32.1455, 43.688, -28.278807, 0.000000, 0.000000, 0.001110, 0.000000, 1496957395.253900, 1.301738, 1.000000, 72.192000, 15.214770, 25.081255, 0.617021 +-32.1446, 43.6872, -28.278308, 0.000000, 0.000000, 0.001110, 0.000000, 1496957395.264400, 1.301733, 1.000000, 72.192000, 15.165942, 25.081255, 0.617021 +-32.1436, 43.6864, -28.277814, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.274000, 1.301731, 1.000000, 72.192000, 15.165942, 25.008011, 0.595745 +-32.1427, 43.6856, -28.277315, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.284500, 1.301717, 1.000000, 72.192000, 15.226978, 25.008011, 0.595745 +-32.1418, 43.6848, -28.276815, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.294000, 1.301723, 1.000000, 72.192000, 15.226978, 24.942398, 0.595745 +-32.1409, 43.6839, -28.276318, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.304500, 1.301737, 1.000000, 72.192000, 15.263599, 24.942398, 0.595745 +-32.14, 43.6831, -28.275820, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.314100, 1.301741, 1.000000, 72.192000, 15.263599, 24.936293, 0.595745 +-32.139, 43.6823, -28.275325, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.323500, 1.301732, 1.000000, 72.192000, 15.288014, 24.936293, 0.595745 +-32.1381, 43.6815, -28.274826, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.334100, 1.301724, 1.000000, 72.192000, 15.288014, 24.983597, 0.595745 +-32.1372, 43.6806, -28.274334, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.344600, 1.301719, 1.000000, 72.192000, 15.202563, 24.983597, 0.595745 +-32.1363, 43.6798, -28.273839, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.354200, 1.301747, 1.000000, 72.192000, 15.202563, 24.975967, 0.595745 +-32.1353, 43.6789, -28.273346, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.363600, 1.301721, 1.000000, 72.192000, 15.092698, 24.975967, 0.595745 +-32.1344, 43.6781, -28.272853, 0.000000, 0.000000, 0.001110, 0.000000, 1496957395.374200, 1.301737, 1.000000, 72.192000, 15.092698, 24.974442, 0.617021 +-32.1335, 43.6773, -28.272358, 0.000000, 0.000000, 0.001110, 0.000000, 1496957395.383900, 1.301708, 1.000000, 72.192000, 15.239185, 24.974442, 0.617021 +-32.1326, 43.6764, -28.271864, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.394500, 1.301703, 1.000000, 72.192000, 15.239185, 24.930189, 0.595745 +-32.1317, 43.6756, -28.271370, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.404100, 1.301726, 1.000000, 72.192000, 15.239185, 24.930189, 0.595745 +-32.1307, 43.6747, -28.270876, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.413600, 1.301733, 1.000000, 72.192000, 15.239185, 24.919508, 0.595745 +-32.1298, 43.6739, -28.270376, 0.000000, 0.000000, 0.001072, 0.000000, 1496957395.424500, 1.301696, 1.000000, 72.192000, 15.214770, 24.919508, 0.595745 diff --git a/apollo_planning/include/apollo_planning/common/base_types.h b/apollo_planning/include/apollo_planning/common/base_types.h new file mode 100644 index 0000000..3c9fdac --- /dev/null +++ b/apollo_planning/include/apollo_planning/common/base_types.h @@ -0,0 +1,85 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_PLANNING_COMMON_BASE_TYPES_H_ +#define MODULES_PLANNING_COMMON_BASE_TYPES_H_ + +/** + * @namespace apollo::planning + * @brief apollo::planning + */ +namespace apollo { +namespace planning { + +/** + * @class PathPoint + * @brief PathPoint is a data structure class + * for discretized path representation. + */ +class PathPoint { + public: + /// x coordinate + double x = 0.0; + /// y coordinate + double y = 0.0; + /// z coordinate + double z = 0.0; + /// derivative direction on the x-y plane + double theta = 0.0; + /// curvature on the x-y planning + double kappa = 0.0; + /// accumulated distance from beginning of the path + double s = 0.0; +}; + +/** + * @class TrajectoryPoint + * @brief TrajectoryPoint is a data structure class + * for discretized trajectory representation. + * It inherits the variables from base class PathPoint. + */ +class TrajectoryPoint : public PathPoint { + public: + /// relative time from beginning of the trajectory + double relative_time = 0.0; + /// linear velocity + double v = 0.0; + /// linear acceleration + double a = 0.0; + /// curvature change rate w.r.t. time + double dkappa = 0.0; +}; + +} // namespace planning +} // namespace apollo + +#endif /* MODULES_PLANNING_COMMON_BASE_TYPES_H_ */ diff --git a/apollo_planning/include/apollo_planning/common/planning_gflags.h b/apollo_planning/include/apollo_planning/common/planning_gflags.h new file mode 100644 index 0000000..5173256 --- /dev/null +++ b/apollo_planning/include/apollo_planning/common/planning_gflags.h @@ -0,0 +1,45 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_PLANNING_COMMON_PLANNING_GFLAGS_H_ +#define MODULES_PLANNING_COMMON_PLANNING_GFLAGS_H_ + +#include + +DECLARE_double(planning_loop_rate); +DECLARE_string(rtk_trajectory_filename); +DECLARE_uint64(rtk_trajectory_backward); +DECLARE_uint64(rtk_trajectory_forward); +DECLARE_double(replanning_threshold); +DECLARE_double(trajectory_resolution); + +#endif /* MODULES_PLANNING_COMMON_PLANNING_GFLAGS_H_ */ diff --git a/apollo_planning/include/apollo_planning/planner/planner.h b/apollo_planning/include/apollo_planning/planner/planner.h new file mode 100644 index 0000000..f6c919f --- /dev/null +++ b/apollo_planning/include/apollo_planning/planner/planner.h @@ -0,0 +1,79 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_PLANNING_PLANNER_PLANNER_H_ +#define MODULES_PLANNING_PLANNER_PLANNER_H_ + +#include + +#include "apollo_common/vehicle_state/vehicle_state.h" +#include "apollo_planning/common/base_types.h" + +/** + * @namespace apollo::planning + * @brief apollo::planning + */ +namespace apollo { +namespace planning { + +/** + * @class Planner + * @brief Planner is a base class for specific planners. + * It contains a pure virtual function Plan which must be implemented in + * derived class. + */ +class Planner { + public: + /** + * @brief Constructor + */ + Planner() = default; + + /** + * @brief Destructor + */ + virtual ~Planner() = default; + + /** + * @brief Compute a trajectory for execution. + * @param start_point The trajectory point where planning starts + * @param discretized_trajectory The computed trajectory + * @return true if planning succeeds; false otherwise. + */ + virtual bool Plan(const TrajectoryPoint& start_point, + std::vector* discretized_trajectory) = 0; +}; + +} // namespace planning +} // namespace apollo + +#endif /* MODULES_PLANNING_PLANNER_PLANNER_H_ */ diff --git a/apollo_planning/include/apollo_planning/planner/rtk_replay_planner.h b/apollo_planning/include/apollo_planning/planner/rtk_replay_planner.h new file mode 100644 index 0000000..63ba799 --- /dev/null +++ b/apollo_planning/include/apollo_planning/planner/rtk_replay_planner.h @@ -0,0 +1,93 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_PLANNING_PLANNER_RTK_REPLAY_PLANNER_H_ +#define MODULES_PLANNING_PLANNER_RTK_REPLAY_PLANNER_H_ + +#include "apollo_planning/planner/planner.h" + +#include +#include + +/** + * @namespace apollo::planning + * @brief apollo::planning + */ +namespace apollo { +namespace planning { + +/** + * @class RTKReplayPlanner + * @brief RTKReplayPlanner is a derived class of Planner. + * It reads a recorded trajectory from a trajectory file and + * outputs proper segment of the trajectory according to vehicle + * position. + */ +class RTKReplayPlanner : public Planner { + public: + /** + * @brief Constructor + */ + RTKReplayPlanner(); + + /** + * @brief Destructor + */ + virtual ~RTKReplayPlanner() = default; + + /** + * @brief Overrode function Plan in parent class Planner. + * @param start_point The trajectory point where planning starts + * @param discretized_trajectory The computed trajectory + * @return true if planning succeeds; false otherwise. + */ + bool Plan(const TrajectoryPoint& start_point, + std::vector* ptr_trajectory) override; + + /** + * @brief Read the recorded trajectory file. + * @param filename The name of the trajectory file. + */ + void ReadTrajectoryFile(const std::string& filename); + + private: + std::size_t QueryPositionMatchedPoint( + const TrajectoryPoint& start_point, + const std::vector& trajectory) const; + + std::vector complete_rtk_trajectory_; +}; + +} // namespace planning +} // nameapace apollo + +#endif /* MODULES_PLANNING_PLANNER_RTK_REPLAY_PLANNER_H_ */ diff --git a/apollo_planning/include/apollo_planning/planner_factory.h b/apollo_planning/include/apollo_planning/planner_factory.h new file mode 100644 index 0000000..a04e72c --- /dev/null +++ b/apollo_planning/include/apollo_planning/planner_factory.h @@ -0,0 +1,74 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_PLANNING_PLANNER_FACTORY_H_ +#define MODULES_PLANNING_PLANNER_FACTORY_H_ + +#include "apollo_planning/planner/planner.h" + +#include + +/** + * @namespace apollo::planning + * @brief apollo::planning + */ +namespace apollo { +namespace planning { + +/** + * @class PlanningType + * @brief PlanningType is a enum class used to specify a planner instance. + */ +enum class PlannerType { RTK_PLANNER, OTHER }; + +/** + * @class PlannerFactory + * @brief PlannerFactory is a creator class that + * creates an instance of a specific planner. + */ +class PlannerFactory { + public: + PlannerFactory() = delete; + /** + * @brief Generate a planner instance. + * @param planner_type The specific type of planner, + * currently only supports PlannerType::RTK_PLANNER + * @return A unique pointer pointing to the planner instance. + */ + static std::unique_ptr CreateInstance( + const PlannerType& planner_type); +}; + +} // namespace planning +} // namespace apollo + +#endif /* MODULES_PLANNING_PLANNER_FACTORY_H_ */ diff --git a/apollo_planning/include/apollo_planning/planning.h b/apollo_planning/include/apollo_planning/planning.h new file mode 100644 index 0000000..e0cc14c --- /dev/null +++ b/apollo_planning/include/apollo_planning/planning.h @@ -0,0 +1,94 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_PLANNING_PLANNING_H_ +#define MODULES_PLANNING_PLANNING_H_ + +#include "apollo_common/vehicle_state/vehicle_state.h" +#include "apollo_planning/planner/planner.h" + +#include + +namespace apollo { +namespace planning { + +class Planning { + public: + /** + * @brief Constructor + */ + Planning(); + + /** + * @brief Destructor + */ + ~Planning() = default; + + /** + * @brief Plan the trajectory given current vehicle state + * @param vehicle_state variable describes the vehicle state, including + * position, + * velocity, acceleration, heading, etc + * @param is_on_auto_mode whether the current system is on auto-driving mode + * @param publishable_trajectory the computed planning trajectory + */ + bool Plan(const common::vehicle_state::VehicleState& vehicle_state, + const bool is_on_auto_mode, const double publish_time, + std::vector* discretized_trajectory); + + /** + * @brief Reset the planner to initial state. + */ + void Reset(); + + private: + std::pair + ComputeStartingPointFromLastTrajectory(const double curr_time) const; + + TrajectoryPoint ComputeStartingPointFromVehicleState( + const common::vehicle_state::VehicleState& vehicle_state, + const double forward_time) const; + + std::vector GetOverheadTrajectory( + const std::size_t matched_index, const std::size_t buffer_size); + + std::unique_ptr ptr_planner_; + + std::vector last_trajectory_; + + double last_header_time_ = 0.0; +}; + +} // namespace planning +} // namespace apollo + +#endif /* MODULES_PLANNING_PLANNING_H_ */ diff --git a/apollo_planning/include/apollo_planning/planning_node.h b/apollo_planning/include/apollo_planning/planning_node.h new file mode 100644 index 0000000..a1e2177 --- /dev/null +++ b/apollo_planning/include/apollo_planning/planning_node.h @@ -0,0 +1,91 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#ifndef MODULES_PLANNING_PLANNING_NODE_H_ +#define MODULES_PLANNING_PLANNING_NODE_H_ + +#include + +#include "apollo_common/vehicle_state/vehicle_state.h" +#include "apollo_msgs/proto/planning/planning.pb.h" + +#include "apollo_planning/common/base_types.h" +#include "apollo_planning/planning.h" + +/** + * @namespace apollo::planning + * @brief apollo::planning + */ +namespace apollo { +namespace planning { + +/** + * @class PlanningNode + * @brief PlanningNode is a class that + * implements a ros node for planning module. + */ +class PlanningNode { + public: + /** + * @brief Constructor + */ + PlanningNode(); + + /** + * @brief Destructor + */ + virtual ~PlanningNode(); + + /** + * @brief Start the planning node. + */ + void Run(); + + /** + * @brief Reset the planning node. + */ + void Reset(); + + private: + void RunOnce(); + + ADCTrajectory ToTrajectoryPb( + const double header_time, + const std::vector& discretized_trajectory); + + Planning planning_; +}; + +} // namespace planning +} // namespace apollo + +#endif /* MODULES_PLANNING_PLANNING_NODE_H_ */ diff --git a/apollo_planning/launch/planning.launch b/apollo_planning/launch/planning.launch new file mode 100644 index 0000000..705b8b6 --- /dev/null +++ b/apollo_planning/launch/planning.launch @@ -0,0 +1,8 @@ + + + + \ No newline at end of file diff --git a/apollo_planning/package.xml b/apollo_planning/package.xml new file mode 100644 index 0000000..e368c84 --- /dev/null +++ b/apollo_planning/package.xml @@ -0,0 +1,29 @@ + + + apollo_planning + 0.0.0 + The apollo_planning package + + forrest + TODO + + catkin + + roscpp + roscpp + roscpp + + apollo_msgs + apollo_msgs + apollo_msgs + + apollo_common + apollo_common + apollo_common + + + + + + + diff --git a/apollo_planning/src/common/planning_gflags.cc b/apollo_planning/src/common/planning_gflags.cc new file mode 100644 index 0000000..e1fd684 --- /dev/null +++ b/apollo_planning/src/common/planning_gflags.cc @@ -0,0 +1,53 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_planning/common/planning_gflags.h" + +DEFINE_double(planning_loop_rate, 5.0, "Loop rate for planning node"); + +DEFINE_string(rtk_trajectory_filename, "modules/planning/data/garage.csv", + "Loop rate for planning node"); + +DEFINE_uint64(rtk_trajectory_backward, 10, + "The number of points to be included in RTK trajectory " + "before the matched point"); + +DEFINE_uint64(rtk_trajectory_forward, 800, + "The number of points to be included in RTK trajectory " + "after the matched point"); + +DEFINE_double(replanning_threshold, 2.0, + "The threshold of position deviation " + "that triggers the planner replanning"); + +DEFINE_double(trajectory_resolution, 0.01, "The time resolution of " + "output trajectory."); diff --git a/apollo_planning/src/main.cc b/apollo_planning/src/main.cc new file mode 100644 index 0000000..a35d3ff --- /dev/null +++ b/apollo_planning/src/main.cc @@ -0,0 +1,49 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include +#include + +#include "apollo_common/log.h" +#include "apollo_planning/planning_node.h" + +int main(int argc, char **argv) { + google::InitGoogleLogging(argv[0]); + google::ParseCommandLineFlags(&argc, &argv, true); + + ros::init(argc, argv, "planning"); + + ::apollo::planning::PlanningNode planning_node; + planning_node.Run(); + + return 0; +} diff --git a/apollo_planning/src/planner/rtk_replay_planner.cc b/apollo_planning/src/planner/rtk_replay_planner.cc new file mode 100644 index 0000000..9f24c82 --- /dev/null +++ b/apollo_planning/src/planner/rtk_replay_planner.cc @@ -0,0 +1,178 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_planning/planner/rtk_replay_planner.h" + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "apollo_common/log.h" +#include "apollo_common/util/string_tokenizer.h" +#include "apollo_planning/common/planning_gflags.h" + +namespace apollo { +namespace planning { + +using apollo::common::vehicle_state::VehicleState; + +RTKReplayPlanner::RTKReplayPlanner() { + ReadTrajectoryFile(FLAGS_rtk_trajectory_filename); +} + +bool RTKReplayPlanner::Plan( + const TrajectoryPoint& start_point, + std::vector* ptr_discretized_trajectory) { + + if (complete_rtk_trajectory_.empty() || complete_rtk_trajectory_.size() < 2) { + AERROR << "RTKReplayPlanner doesn't have a recorded trajectory or " + "the recorded trajectory doesn't have enough valid trajectory " + "points."; + return false; + } + + std::size_t matched_index = + QueryPositionMatchedPoint(start_point, complete_rtk_trajectory_); + + std::size_t forward_buffer = FLAGS_rtk_trajectory_forward; + std::size_t end_index = + matched_index + forward_buffer >= complete_rtk_trajectory_.size() + ? complete_rtk_trajectory_.size() - 1 + : matched_index + forward_buffer - 1; + + if (ptr_discretized_trajectory->size() > 0) { + ptr_discretized_trajectory->clear(); + } + + ptr_discretized_trajectory->insert( + ptr_discretized_trajectory->begin(), + complete_rtk_trajectory_.begin() + matched_index, + complete_rtk_trajectory_.begin() + end_index + 1); + + // reset relative time + double zero_time = complete_rtk_trajectory_[matched_index].relative_time;; + for (std::size_t i = 0; i < ptr_discretized_trajectory->size(); ++i) { + (*ptr_discretized_trajectory)[i].relative_time -= zero_time; + } + + // check if the trajectory has enough points; + // if not, append the last points multiple times and + // adjust their corresponding time stamps. + while (ptr_discretized_trajectory->size() < FLAGS_rtk_trajectory_forward) { + const auto& last_point = ptr_discretized_trajectory->back(); + ptr_discretized_trajectory->push_back(last_point); + ptr_discretized_trajectory->back().relative_time += FLAGS_trajectory_resolution; + } + return true; +} + +void RTKReplayPlanner::ReadTrajectoryFile(const std::string& filename) { + if (!complete_rtk_trajectory_.empty()) { + complete_rtk_trajectory_.clear(); + } + + std::ifstream file_in(filename.c_str()); + if (!file_in.is_open()) { + AERROR << "RTKReplayPlanner cannot open trajectory file: " << filename; + return; + } + + std::string line; + // skip the header line. + getline(file_in, line); + + while (true) { + getline(file_in, line); + if (line == "") { + break; + } + + auto tokens = apollo::common::util::StringTokenizer::Split(line, "\t "); + if (tokens.size() < 11) { + AERROR << "RTKReplayPlanner parse line failed; the data dimension does not match."; + AERROR << line; + continue; + } + + TrajectoryPoint point; + point.x = std::stod(tokens[0]); + point.y = std::stod(tokens[1]); + point.z = std::stod(tokens[2]); + + point.v = std::stod(tokens[3]); + point.a = std::stod(tokens[4]); + + point.kappa = std::stod(tokens[5]); + point.dkappa = std::stod(tokens[6]); + + point.relative_time = std::stod(tokens[7]); + + point.theta = std::stod(tokens[8]); + + point.s = std::stod(tokens[10]); + complete_rtk_trajectory_.push_back(point); + } + + file_in.close(); +} + +std::size_t RTKReplayPlanner::QueryPositionMatchedPoint( + const TrajectoryPoint& start_point, + const std::vector& trajectory) const { + auto func_distance_square = [](const PathPoint& point, const double x, + const double y) { + double dx = point.x - x; + double dy = point.y - y; + return dx * dx + dy * dy; + }; + double d_min = func_distance_square(trajectory.front(), start_point.x, + start_point.y); + std::size_t index_min = 0; + for (std::size_t i = 1; i < trajectory.size(); ++i) { + double d_temp = func_distance_square(trajectory[i], start_point.x, + start_point.y); + if (d_temp < d_min) { + d_min = d_temp; + index_min = i; + } + } + return index_min; +} + +} // namespace planning +} // nameapace apollo diff --git a/apollo_planning/src/planner_factory.cc b/apollo_planning/src/planner_factory.cc new file mode 100644 index 0000000..97e2328 --- /dev/null +++ b/apollo_planning/src/planner_factory.cc @@ -0,0 +1,51 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_planning/planner_factory.h" + +#include "apollo_planning/planner/rtk_replay_planner.h" + +namespace apollo { +namespace planning { + +std::unique_ptr PlannerFactory::CreateInstance( + const PlannerType& planner_type) { + switch (planner_type) { + case PlannerType::RTK_PLANNER: + return std::unique_ptr(new RTKReplayPlanner()); + default: + return nullptr; + } +} + +} // namespace planning +} // namespace apollo diff --git a/apollo_planning/src/planning.cc b/apollo_planning/src/planning.cc new file mode 100644 index 0000000..260a17e --- /dev/null +++ b/apollo_planning/src/planning.cc @@ -0,0 +1,186 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_planning/planning.h" + +#include "apollo_common/adapters/adapter_manager.h" +#include "apollo_common/time/time.h" + +#include "apollo_planning/common/planning_gflags.h" +#include "apollo_planning/planner_factory.h" + +namespace apollo { +namespace planning { + +using apollo::common::adapter::AdapterManager; +using TrajectoryPb = ADCTrajectory; + +Planning::Planning() { + ptr_planner_ = PlannerFactory::CreateInstance(PlannerType::RTK_PLANNER); +} + +bool Planning::Plan(const common::vehicle_state::VehicleState& vehicle_state, + const bool is_on_auto_mode, const double publish_time, + std::vector* planning_trajectory) { + double planning_cycle_time = 1.0 / FLAGS_planning_loop_rate; + double execution_start_time = publish_time; + + if (is_on_auto_mode && !last_trajectory_.empty()) { + // if the auto-driving mode is on and we have the trajectory from last + // cycle, then + // find the planning starting point from the last planning result. + // this ensures the smoothness of planning output and + // therefore the smoothness of control execution. + + auto matched_info = + ComputeStartingPointFromLastTrajectory(execution_start_time); + TrajectoryPoint matched_point = matched_info.first; + std::size_t matched_index = matched_info.second; + + // Compute the position deviation between current vehicle + // position and target vehicle position. + // If the deviation exceeds a specific threshold, + // it will be unsafe to planning from the matched point. + double dx = matched_point.x - vehicle_state.x(); + double dy = matched_point.y - vehicle_state.y(); + double position_deviation = std::sqrt(dx * dx + dy * dy); + + if (position_deviation < FLAGS_replanning_threshold) { + // planned trajectory from the matched point, the matched point has + // relative time 0. + bool planning_succeeded = + ptr_planner_->Plan(matched_point, planning_trajectory); + + if (!planning_succeeded) { + last_trajectory_.clear(); + return false; + } + + // a segment of last trajectory to be attached to planned trajectory in + // case controller needs. + auto overhead_trajectory = GetOverheadTrajectory( + matched_index, (std::size_t)FLAGS_rtk_trajectory_backward); + planning_trajectory->insert(planning_trajectory->begin(), + overhead_trajectory.begin(), + overhead_trajectory.end()); + + // store the planned trajectory and header info for next planning cycle. + last_trajectory_ = *planning_trajectory; + last_header_time_ = execution_start_time; + return true; + } + } + + // if 1. the auto-driving mode is off or + // 2. we don't have the trajectory from last planning cycle or + // 3. the position deviation from actual and target is too high + // then planning from current vehicle state. + TrajectoryPoint vehicle_state_point = + ComputeStartingPointFromVehicleState(vehicle_state, planning_cycle_time); + + bool planning_succeeded = + ptr_planner_->Plan(vehicle_state_point, planning_trajectory); + if (!planning_succeeded) { + last_trajectory_.clear(); + return false; + } + // store the planned trajectory and header info for next planning cycle. + last_trajectory_ = *planning_trajectory; + last_header_time_ = execution_start_time; + return true; +} + +std::pair +Planning::ComputeStartingPointFromLastTrajectory( + const double start_time) const { + auto comp = [](const TrajectoryPoint& p, const double t) { + return p.relative_time < t; + }; + + auto it_lower = + std::lower_bound(last_trajectory_.begin(), last_trajectory_.end(), + start_time - last_header_time_, comp); + if (it_lower == last_trajectory_.end()) { + it_lower--; + } + std::size_t index = it_lower - last_trajectory_.begin(); + return std::pair(*it_lower, index); +} + +TrajectoryPoint Planning::ComputeStartingPointFromVehicleState( + const common::vehicle_state::VehicleState& vehicle_state, + const double forward_time) const { + // Eigen::Vector2d estimated_position = + // vehicle_state.EstimateFuturePosition(forward_time); + TrajectoryPoint point; + // point.x = estimated_position.x(); + // point.y = estimated_position.y(); + point.x = vehicle_state.x(); + point.y = vehicle_state.y(); + point.z = vehicle_state.z(); + point.v = vehicle_state.linear_velocity(); + point.a = vehicle_state.linear_acceleration(); + point.kappa = 0.0; + if (point.v > 0.1) { + point.kappa = + vehicle_state.angular_velocity() / vehicle_state.linear_velocity(); + } + point.dkappa = 0.0; + point.s = 0.0; + point.relative_time = 0.0; + return point; +} + +void Planning::Reset() { + last_header_time_ = 0.0; + last_trajectory_.clear(); +} + +std::vector Planning::GetOverheadTrajectory( + const std::size_t matched_index, const std::size_t buffer_size) { + const std::size_t start_index = + matched_index < buffer_size ? 0 : matched_index - buffer_size; + + auto overhead_trajectory = + std::vector(last_trajectory_.begin() + start_index, + last_trajectory_.begin() + matched_index); + + double zero_relative_time = last_trajectory_[matched_index].relative_time; + // reset relative time + for (auto& p : overhead_trajectory) { + p.relative_time -= zero_relative_time; + } + return overhead_trajectory; +} + +} // namespace planning +} // namespace apollo diff --git a/apollo_planning/src/planning_node.cc b/apollo_planning/src/planning_node.cc new file mode 100644 index 0000000..220c639 --- /dev/null +++ b/apollo_planning/src/planning_node.cc @@ -0,0 +1,144 @@ +/****************************************************************************** + * Copyright 2017 The Apollo Authors. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_planning/planning_node.h" + +#include "apollo_common/adapters/adapter_manager.h" +#include "apollo_common/log.h" +#include "apollo_msgs/proto/planning/planning.pb.h" + +#include "apollo_planning/common/planning_gflags.h" + +namespace apollo { +namespace planning { + +using apollo::common::vehicle_state::VehicleState; +using apollo::common::adapter::AdapterManager; +using apollo::common::time::Clock; +using TrajectoryPb = ADCTrajectory; + +PlanningNode::PlanningNode() { + AdapterManager::Init(FLAGS_adapter_config_path); +} + +PlanningNode::~PlanningNode() {} + +void PlanningNode::Run() { + static ros::Rate loop_rate(FLAGS_planning_loop_rate); + while (ros::ok()) { + RunOnce(); + ros::spinOnce(); + loop_rate.sleep(); + } +} + +void PlanningNode::RunOnce() { + AdapterManager::Observe(); + if (AdapterManager::GetLocalization() == nullptr) { + AERROR << "Localization is not available; skip the planning cycle"; + return; + } + if (AdapterManager::GetLocalization()->Empty()) { + AERROR << "localization messages are missing; skip the planning cycle"; + return; + } else { + AINFO << "Get localization message;"; + } + + if (AdapterManager::GetChassis() == nullptr) { + AERROR << "Chassis is not available; skip the planning cycle"; + return; + } + if (AdapterManager::GetChassis()->Empty()) { + AERROR << "Chassis messages are missing; skip the planning cycle"; + return; + } else { + AINFO << "Get localization message;"; + } + + AINFO << "Start planning ..."; + + const auto& localization = + AdapterManager::GetLocalization()->GetLatestObserved(); + VehicleState vehicle_state(localization); + + const auto& chassis = AdapterManager::GetChassis()->GetLatestObserved(); + bool is_on_auto_mode = chassis.driving_mode() == chassis.COMPLETE_AUTO_DRIVE; + + double planning_cycle_time = 1.0 / FLAGS_planning_loop_rate; + // the execution_start_time is the estimated time when the planned trajectory + // will be executed by the controller. + double execution_start_time = + apollo::common::time::ToSecond(apollo::common::time::Clock::Now()) + + planning_cycle_time; + + std::vector planning_trajectory; + bool res_planning = planning_.Plan(vehicle_state, is_on_auto_mode, + execution_start_time, &planning_trajectory); + if (res_planning) { + TrajectoryPb trajectory_pb = ToTrajectoryPb(execution_start_time, planning_trajectory); + AdapterManager::PublishPlanningTrajectory(trajectory_pb); + AINFO << "Planning succeeded"; + } else { + AINFO << "Planning failed"; + } +} + +void PlanningNode::Reset() { + planning_.Reset(); +} + +TrajectoryPb PlanningNode::ToTrajectoryPb( + const double header_time, + const std::vector& discretized_trajectory) { + TrajectoryPb trajectory_pb; + AdapterManager::FillPlanningTrajectoryHeader("planning", + trajectory_pb.mutable_header()); + + trajectory_pb.mutable_header()->set_timestamp_sec(header_time); + + for (const auto& trajectory_point : discretized_trajectory) { + auto ptr_trajectory_point_pb = trajectory_pb.add_adc_trajectory_point(); + ptr_trajectory_point_pb->set_x(trajectory_point.x); + ptr_trajectory_point_pb->set_y(trajectory_point.y); + ptr_trajectory_point_pb->set_theta(trajectory_point.theta); + ptr_trajectory_point_pb->set_curvature(trajectory_point.kappa); + ptr_trajectory_point_pb->set_relative_time(trajectory_point.relative_time); + ptr_trajectory_point_pb->set_speed(trajectory_point.v); + ptr_trajectory_point_pb->set_acceleration_s(trajectory_point.a); + ptr_trajectory_point_pb->set_accumulated_s(trajectory_point.s); + } + return std::move(trajectory_pb); +} + +} // namespace planning +} // namespace apollo diff --git a/apollo_simulator/CMakeLists.txt b/apollo_simulator/CMakeLists.txt new file mode 100644 index 0000000..ef73c7e --- /dev/null +++ b/apollo_simulator/CMakeLists.txt @@ -0,0 +1,51 @@ +cmake_minimum_required(VERSION 2.8.3) +project(apollo_simulator) + +add_compile_options(-std=c++11) +# set(CMAKE_BUILD_TYPE "Debug") +set(CMAKE_BUILD_TYPE "Release") + +find_package(Eigen3 REQUIRED) +find_package(catkin REQUIRED COMPONENTS + roscpp + tf + tf2 + std_msgs + geometry_msgs + apollo_msgs + apollo_common +) + +catkin_package() + +include_directories( + include + ${catkin_INCLUDE_DIRS} + ${EIGEN3_INCLUDE_DIR} +) + +add_executable(${PROJECT_NAME} + src/main.cpp + src/apollo_simulator.cpp + src/vehicle_sim_model/sim_model_constant_acceleration.cpp + src/vehicle_sim_model/sim_model_ideal.cpp + src/vehicle_sim_model/sim_model_interface.cpp + src/vehicle_sim_model/sim_model_time_delay.cpp + src/vehicle_sim_model/sim_model_util.cpp +) +target_link_libraries(${PROJECT_NAME} + ${catkin_LIBRARIES} + protobuf + glog + gflags +) + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} + RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} +) + +install(DIRECTORY launch param + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) \ No newline at end of file diff --git a/apollo_simulator/README.md b/apollo_simulator/README.md new file mode 100644 index 0000000..d185f74 --- /dev/null +++ b/apollo_simulator/README.md @@ -0,0 +1,3 @@ +# Simulator + +This node simulates the vehicle motion for a vehicle command in 2D using a simple vehicle model. \ No newline at end of file diff --git a/apollo_simulator/conf/adapter.conf b/apollo_simulator/conf/adapter.conf new file mode 100644 index 0000000..290d5b8 --- /dev/null +++ b/apollo_simulator/conf/adapter.conf @@ -0,0 +1,21 @@ +config { + type: PLANNING_TRAJECTORY + mode: RECEIVE_ONLY + message_history_limit: 10 +} +config { + type: CONTROL_COMMAND + mode: RECEIVE_ONLY + message_history_limit: 10 +} +config { + type: LOCALIZATION + mode: PUBLISH_ONLY + message_history_limit: 10 +} +config { + type: CHASSIS + mode: PUBLISH_ONLY + message_history_limit: 10 +} +is_ros: true diff --git a/apollo_simulator/include/apollo_simulator/apollo_simulator.h b/apollo_simulator/include/apollo_simulator/apollo_simulator.h new file mode 100644 index 0000000..c7eb5cc --- /dev/null +++ b/apollo_simulator/include/apollo_simulator/apollo_simulator.h @@ -0,0 +1,197 @@ +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#pragma once + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "apollo_simulator/vehicle_sim_model/sim_model_constant_acceleration.h" +#include "apollo_simulator/vehicle_sim_model/sim_model_ideal.h" +#include "apollo_simulator/vehicle_sim_model/sim_model_interface.h" +#include "apollo_simulator/vehicle_sim_model/sim_model_time_delay.h" + +class Simulator { + public: + /** + * @brief constructor + */ + explicit Simulator(tf2_ros::Buffer &tf_buffer); + + /** + * @brief default destructor + */ + // ~Simulator() = default; + + protected: + /** + * @brief set initial pose for simulation with received message + */ + void CallbackInitialPoseWithCov( + const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg); + + /** + * @brief set initial pose with received message + */ + void CallbackInitialPoseStamped(const geometry_msgs::PoseStamped::ConstPtr &msg); + + /** + * @brief set initial twist with received message + */ + void CallbackInitialTwistStamped(const geometry_msgs::TwistStamped::ConstPtr &msg); + + /** + * @brief get transform from two frame_ids + * @param [in] parent_frame parent frame id + * @param [in] child frame id + * @param [out] transform transform from parent frame to child frame + */ + void GetTransformFromTF( + const std::string parent_frame, const std::string child_frame, + geometry_msgs::TransformStamped &transform); + + /** + * @brief timer callback for simulation with loop_rate + */ + void TimerCallbackSimulation(const ros::TimerEvent &event); + + /** + * @brief set initial state of simulated vehicle + * @param [in] pose initial position and orientation + * @param [in] twist initial velocity and angular velocity + */ + void SetInitialState(const geometry_msgs::Pose &pose, const geometry_msgs::Twist &twist); + + /** + * @brief set initial state of simulated vehicle with pose transformation based on frame_id + * @param [in] pose initial position and orientation with header + * @param [in] twist initial velocity and angular velocity + */ + void SetInitialStateWithPoseTransform( + const geometry_msgs::PoseStamped &pose, const geometry_msgs::Twist &twist); + + /** + * @brief set initial state of simulated vehicle with pose transformation based on frame_id + * @param [in] pose initial position and orientation with header + * @param [in] twist initial velocity and angular velocity + */ + void SetInitialStateWithPoseTransform( + const geometry_msgs::PoseWithCovarianceStamped &pose, + const geometry_msgs::Twist &twist); + + /** + * @brief publish tf + * @param [in] pose pose used for tf + */ + void PublishTF(const geometry_msgs::Pose &pose); + + /** + * @brief convert roll-pitch-yaw Euler angle to ros Quaternion + * @param [in] roll roll angle [rad] + * @param [in] pitch pitch angle [rad] + * @param [in] yaw yaw angle [rad] + */ + geometry_msgs::Quaternion GetQuaternionFromRPY( + const double &roll, const double &pitch, const double &yaw); + + void PublishChassis(const double &steering_angle, const geometry_msgs::Twist &twist); + void PublishLocalization(const geometry_msgs::Pose &pose, const geometry_msgs::Twist &twist); + void PublishPlanningTrajectory(); + + double GetNumberFromXMLRPC(XmlRpc::XmlRpcValue &value, const std::string &full_param_name); + std::vector MakeFootprintFromXMLRPC(XmlRpc::XmlRpcValue &footprint_xmlrpc, + const std::string &full_param_name, const size_t min_size = 1); + + private: + /* ros system */ + ros::Publisher pub_pose_; //!< @brief topic ros publisher for current pose + ros::Publisher pub_speed_; //!< @brief topic ros publisher for current speed + ros::Publisher pub_footprint_; //!< @brief topic ros publisher for vehicle footprint + ros::Publisher pub_trajectory_; + + ros::Subscriber sub_initialpose_; //!< @brief topic subscriber for initialpose topic + ros::Subscriber sub_initialtwist_; //!< @brief topic subscriber for initialtwist topic + + ros::Timer timer_simulation_; //!< @brief timer for simulation + + /* tf */ + tf2_ros::TransformBroadcaster tf_broadcaster_; + tf2_ros::Buffer &tf_buffer_; + + /* received & published topics */ + geometry_msgs::PoseStamped::ConstPtr initial_pose_ptr_; //!< @brief initial vehicle pose + geometry_msgs::PoseWithCovarianceStamped::ConstPtr initial_pose_with_cov_ptr_; //!< @brief initial vehicle pose with cov + geometry_msgs::TwistStamped::ConstPtr initial_twist_ptr_; //!< @brief initial vehicle velocity + geometry_msgs::Pose current_pose_; //!< @brief current vehicle position and angle + geometry_msgs::Twist current_twist_; //!< @brief current vehicle velocity + double closest_pos_z_; //!< @brief z position on closest trajectory + + /* frame_id */ + std::string simulation_frame_id_; //!< @brief vehicle frame id simulated by apollo_simulator + std::string map_frame_id_; //!< @brief map frame_id + + /* apollo_simulator parameters */ + double loop_rate_; //!< @brief frequency to calculate vehicle model & publish result + double wheelbase_; //!< @brief wheelbase length to convert angular-velocity & steering + std::vector footprint_; + double steer_transmission_ratio_; + double steer_single_direction_max_degree_; + + /* flags */ + bool is_initialized_ = false; //!< @brief flag to check the initial position is set + bool add_measurement_noise_; //!< @brief flag to add measurement noise + + /* saved values */ + std::shared_ptr prev_update_time_ptr_; //!< @brief previously updated time + + /* vehicle model */ + enum class VehicleModelType { + IDEAL_TWIST = 0, + IDEAL_STEER = 1, + DELAY_TWIST = 2, + DELAY_STEER = 3, + CONST_ACCEL_TWIST = 4, + IDEAL_FORKLIFT_RLS = 5, + DELAY_FORKLIFT_RLS = 6, + IDEAL_ACCEL = 7, + DELAY_STEER_ACC = 8, + } vehicle_model_type_; //!< @brief vehicle model type to decide the model dynamics + std::shared_ptr vehicle_model_ptr_; //!< @brief vehicle model pointer + + /* to generate measurement noise */ + std::shared_ptr rand_engine_ptr_; //!< @brief random engine for measurement noise + std::shared_ptr> pos_norm_dist_ptr_; //!< @brief Gaussian noise for position + std::shared_ptr> vel_norm_dist_ptr_; //!< @brief Gaussian noise for velocity + std::shared_ptr> rpy_norm_dist_ptr_; //!< @brief Gaussian noise for roll-pitch-yaw + std::shared_ptr> angvel_norm_dist_ptr_; //!< @brief Gaussian noise for angular velocity + std::shared_ptr> steer_norm_dist_ptr_; //!< @brief Gaussian noise for steering angle +}; diff --git a/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_constant_acceleration.h b/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_constant_acceleration.h new file mode 100644 index 0000000..d4dbaf3 --- /dev/null +++ b/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_constant_acceleration.h @@ -0,0 +1,105 @@ +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#pragma once + +#include +#include +#include + +#include "apollo_simulator/vehicle_sim_model/sim_model_interface.h" + +/** + * @class simple_planning_simulator constant acceleration twist model + * @brief calculate velocity & angular-velocity with constant acceleration + */ +class SimModelConstantAccelTwist : public SimModelInterface { + public: + /** + * @brief constructor + * @param [in] vx_lim velocity limit [m/s] + * @param [in] wz_lim angular velocity limit [m/s] + * @param [in] vx_rate acceleration for velocity [m/ss] + * @param [in] wz_rate acceleration for angular velocity [rad/ss] + */ + SimModelConstantAccelTwist(double vx_lim, double wz_lim, double vx_rate, double wz_rate); + + /** + * @brief default destructor + */ + ~SimModelConstantAccelTwist() = default; + + private: + enum IDX { + X = 0, + Y, + YAW, + VX, + WZ, + }; + enum IDX_U { + VX_DES = 0, + WZ_DES, + }; + + const double vx_lim_; //!< @brief velocity limit + const double wz_lim_; //!< @brief angular velocity limit + const double vx_rate_; //!< @brief velocity rate + const double wz_rate_; //!< @brief angular velocity rate + + /** + * @brief get vehicle position x + */ + double getX() override; + + /** + * @brief get vehicle position y + */ + double getY() override; + + /** + * @brief get vehicle angle yaw + */ + double getYaw() override; + + /** + * @brief get vehicle velocity vx + */ + double getVx() override; + + /** + * @brief get vehicle angular-velocity wz + */ + double getWz() override; + + /** + * @brief get vehicle steering angle + */ + double getSteer() override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double &dt) override; + + /** + * @brief calculate derivative of states with constant acceleration + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd &state, const Eigen::VectorXd &input) override; +}; diff --git a/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_ideal.h b/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_ideal.h new file mode 100644 index 0000000..b6ef0fd --- /dev/null +++ b/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_ideal.h @@ -0,0 +1,243 @@ +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#pragma once + +#include +#include +#include + +#include "apollo_simulator/vehicle_sim_model/sim_model_interface.h" + +/** + * @class simple_planning_simulator ideal twist model + * @brief calculate ideal twist dynamics + */ +class SimModelIdealTwist : public SimModelInterface { + public: + /** + * @brief constructor + */ + SimModelIdealTwist(); + + /** + * @brief destructor + */ + ~SimModelIdealTwist() = default; + + private: + enum IDX { + X = 0, + Y, + YAW, + }; + enum IDX_U { + VX_DES = 0, + WZ_DES, + }; + + /** + * @brief get vehicle position x + */ + double getX() override; + + /** + * @brief get vehicle position y + */ + double getY() override; + + /** + * @brief get vehicle angle yaw + */ + double getYaw() override; + + /** + * @brief get vehicle velocity vx + */ + double getVx() override; + + /** + * @brief get vehicle angular-velocity wz + */ + double getWz() override; + + /** + * @brief get vehicle steering angle + */ + double getSteer() override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double &dt) override; + + /** + * @brief calculate derivative of states with ideal twist model + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd &state, const Eigen::VectorXd &input) override; +}; + +/** + * @class simple_planning_simulator ideal steering model + * @brief calculate ideal steering dynamics + */ +class SimModelIdealSteer : public SimModelInterface { + public: + /** + * @brief constructor + * @param [in] wheelbase vehicle wheelbase length [m] + */ + explicit SimModelIdealSteer(double wheelbase); + + /** + * @brief destructor + */ + ~SimModelIdealSteer() = default; + + private: + enum IDX { + X = 0, + Y, + YAW, + }; + enum IDX_U { + VX_DES = 0, + STEER_DES, + }; + + const double wheelbase_; //!< @brief vehicle wheelbase length + + /** + * @brief get vehicle position x + */ + double getX() override; + + /** + * @brief get vehicle position y + */ + double getY() override; + + /** + * @brief get vehicle angle yaw + */ + double getYaw() override; + + /** + * @brief get vehicle velocity vx + */ + double getVx() override; + + /** + * @brief get vehicle angular-velocity wz + */ + double getWz() override; + + /** + * @brief get vehicle steering angle + */ + double getSteer() override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double &dt) override; + + /** + * @brief calculate derivative of states with ideal steering model + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd &state, const Eigen::VectorXd &input) override; +}; + +/** + * @class wf_simulator ideal acceleration and steering model + * @brief calculate ideal steering dynamics + */ +class SimModelIdealAccel : public SimModelInterface { + public: + /** + * @brief constructor + * @param [in] wheelbase vehicle wheelbase length [m] + */ + explicit SimModelIdealAccel(double wheelbase); + + /** + * @brief destructor + */ + ~SimModelIdealAccel() = default; + + private: + enum IDX { + X = 0, + Y, + YAW, + VX, + }; + enum IDX_U { + AX_DES = 0, + STEER_DES, + }; + + const double wheelbase_; //!< @brief vehicle wheelbase length + + /** + * @brief get vehicle position x + */ + double getX() override; + + /** + * @brief get vehicle position y + */ + double getY() override; + + /** + * @brief get vehicle angle yaw + */ + double getYaw() override; + + /** + * @brief get vehicle velocity vx + */ + double getVx() override; + + /** + * @brief get vehicle angular-velocity wz + */ + double getWz() override; + + /** + * @brief get vehicle steering angle + */ + double getSteer() override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double &dt) override; + + /** + * @brief calculate derivative of states with ideal steering model + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd &state, const Eigen::VectorXd &input) override; +}; diff --git a/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_interface.h b/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_interface.h new file mode 100644 index 0000000..ba4894a --- /dev/null +++ b/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_interface.h @@ -0,0 +1,126 @@ +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#pragma once + +#include + +/** + * @class simple_planning_simulator vehicle model class + * @brief calculate vehicle dynamics + */ +class SimModelInterface { + protected: + const int dim_x_; //!< @brief dimension of state x + const int dim_u_; //!< @brief dimension of input u + Eigen::VectorXd state_; //!< @brief vehicle state vector + Eigen::VectorXd input_; //!< @brief vehicle input vector + + public: + /** + * @brief constructor + * @param [in] dim_x dimension of state x + * @param [in] dim_u dimension of input u + */ + SimModelInterface(int dim_x, int dim_u); + + /** + * @brief destructor + */ + ~SimModelInterface() = default; + + /** + * @brief get state vector of model + * @param [out] state state vector + */ + void getState(Eigen::VectorXd &state); + + /** + * @brief get input vector of model + * @param [out] input input vector + */ + void getInput(Eigen::VectorXd &input); + + /** + * @brief set state vector of model + * @param [in] state state vector + */ + void setState(const Eigen::VectorXd &state); + + /** + * @brief set input vector of model + * @param [in] input input vector + */ + void setInput(const Eigen::VectorXd &input); + + /** + * @brief update vehicle states with Runge-Kutta methods + * @param [in] dt delta time [s] + * @param [in] input vehicle input + */ + void updateRungeKutta(const double &dt, const Eigen::VectorXd &input); + + /** + * @brief update vehicle states with Euler methods + * @param [in] dt delta time [s] + * @param [in] input vehicle input + */ + void updateEuler(const double &dt, const Eigen::VectorXd &input); + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + virtual void update(const double &dt) = 0; + + /** + * @brief get vehicle position x + */ + virtual double getX() = 0; + + /** + * @brief get vehicle position y + */ + virtual double getY() = 0; + + /** + * @brief get vehicle angle yaw + */ + virtual double getYaw() = 0; + + /** + * @brief get vehicle velocity vx + */ + virtual double getVx() = 0; + + /** + * @brief get vehicle angular-velocity wz + */ + virtual double getWz() = 0; + + /** + * @brief get vehicle steering angle + */ + virtual double getSteer() = 0; + + /** + * @brief calculate derivative of states with vehicle model + * @param [in] state current model state + * @param [in] input input vector to model + */ + virtual Eigen::VectorXd calcModel( + const Eigen::VectorXd &state, const Eigen::VectorXd &input) = 0; +}; diff --git a/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_time_delay.h b/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_time_delay.h new file mode 100644 index 0000000..f5c194b --- /dev/null +++ b/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_time_delay.h @@ -0,0 +1,347 @@ +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#pragma once + +#include +#include +#include + +#include +#include + +#include "apollo_simulator/vehicle_sim_model/sim_model_interface.h" +#include "apollo_simulator/vehicle_sim_model/sim_model_util.h" + +/** + * @class simple_planning_simulator time delay twist model + * @brief calculate time delay twist dynamics + */ +class SimModelTimeDelayTwist : public SimModelInterface { + public: + /** + * @brief constructor + * @param [in] vx_lim velocity limit [m/s] + * @param [in] angvel_lim angular velocity limit [m/s] + * @param [in] vx_rate_lim acceleration limit [m/ss] + * @param [in] wz_rate_lim angular acceleration limit [rad/ss] + * @param [in] dt delta time information to set input buffer for delay + * @param [in] vx_delay time delay for velocity command [s] + * @param [in] vx_time_constant time constant for 1D model of velocity dynamics + * @param [in] wx_delay time delay for angular-velocity command [s] + * @param [in] wz_time_constant time constant for 1D model of angular-velocity dynamics + * @param [in] deadzone_delta_steer deadzone value of steer + */ + SimModelTimeDelayTwist( + double vx_lim, double angvel_lim, double vx_rate_lim, double wz_rate_lim, double dt, + double vx_delay, double vx_time_constant, double wz_delay, double wz_time_constant, + double deadzone_delta_steer); + + /** + * @brief default destructor + */ + ~SimModelTimeDelayTwist() = default; + + private: + const double MIN_TIME_CONSTANT; //!< @brief minimum time constant + + enum IDX { + X = 0, + Y, + YAW, + VX, + WZ, + }; + enum IDX_U { + VX_DES = 0, + WZ_DES, + }; + + const double vx_lim_; //!< @brief velocity limit + const double vx_rate_lim_; //!< @brief acceleration limit + const double wz_lim_; //!< @brief angular velocity limit + const double wz_rate_lim_; //!< @brief angular acceleration limit + + std::deque vx_input_queue_; //!< @brief buffer for velocity command + std::deque wz_input_queue_; //!< @brief buffer for angular velocity command + const double vx_delay_; //!< @brief time delay for velocity command [s] + const double vx_time_constant_; //!< @brief time constant for 1D model of velocity dynamics + const double wz_delay_; //!< @brief time delay for angular-velocity command [s] + const double + wz_time_constant_; //!< @brief time constant for 1D model of angular-velocity dynamics + const double deadzone_delta_steer_; //!<@ brief deadzone value of steer + + /** + * @brief set queue buffer for input command + * @param [in] dt delta time + */ + void initializeInputQueue(const double &dt); + + /** + * @brief get vehicle position x + */ + double getX() override; + + /** + * @brief get vehicle position y + */ + double getY() override; + + /** + * @brief get vehicle angle yaw + */ + double getYaw() override; + + /** + * @brief get vehicle velocity vx + */ + double getVx() override; + + /** + * @brief get vehicle angular-velocity wz + */ + double getWz() override; + + /** + * @brief get vehicle steering angle + */ + double getSteer() override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double &dt) override; + + /** + * @brief calculate derivative of states with time delay twist model + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd &state, const Eigen::VectorXd &input) override; +}; + +class SimModelTimeDelaySteer : public SimModelInterface { + public: + /** + * @brief constructor + * @param [in] vx_lim velocity limit [m/s] + * @param [in] steer_lim steering limit [rad] + * @param [in] vx_rate_lim acceleration limit [m/ss] + * @param [in] steer_rate_lim steering angular velocity limit [rad/ss] + * @param [in] wheelbase vehicle wheelbase length [m] + * @param [in] dt delta time information to set input buffer for delay + * @param [in] vx_delay time delay for velocity command [s] + * @param [in] vx_time_constant time constant for 1D model of velocity dynamics + * @param [in] steer_delay time delay for steering command [s] + * @param [in] steer_time_constant time constant for 1D model of steering dynamics + * @param [in] deadzone_delta_steer deadzone value of steer + */ + SimModelTimeDelaySteer( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double vx_delay, double vx_time_constant, double steer_delay, + double steer_time_constant, double deadzone_delta_steer); + + /** + * @brief default destructor + */ + ~SimModelTimeDelaySteer() = default; + + private: + const double MIN_TIME_CONSTANT; //!< @brief minimum time constant + + enum IDX { + X = 0, + Y, + YAW, + VX, + STEER, + }; + enum IDX_U { + VX_DES = 0, + STEER_DES, + }; + + const double vx_lim_; //!< @brief velocity limit [m/s] + const double vx_rate_lim_; //!< @brief acceleration limit [m/ss] + const double steer_lim_; //!< @brief steering limit [rad] + const double steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s] + const double wheelbase_; //!< @brief vehicle wheelbase length [m] + + std::deque vx_input_queue_; //!< @brief buffer for velocity command + std::deque steer_input_queue_; //!< @brief buffer for steering command + const double vx_delay_; //!< @brief time delay for velocity command [s] + const double vx_time_constant_; //!< @brief time constant for 1D model of velocity dynamics + const double steer_delay_; //!< @brief time delay for steering command [s] + const double steer_time_constant_; //!< @brief time constant for 1D model of steering dynamics + const double deadzone_delta_steer_; //!<@ brief deadzone value of steer + + /** + * @brief set queue buffer for input command + * @param [in] dt delta time + */ + void initializeInputQueue(const double &dt); + + /** + * @brief get vehicle position x + */ + double getX() override; + + /** + * @brief get vehicle position y + */ + double getY() override; + + /** + * @brief get vehicle angle yaw + */ + double getYaw() override; + + /** + * @brief get vehicle velocity vx + */ + double getVx() override; + + /** + * @brief get vehicle angular-velocity wz + */ + double getWz() override; + + /** + * @brief get vehicle steering angle + */ + double getSteer() override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double &dt) override; + + /** + * @brief calculate derivative of states with time delay steering model + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd &state, const Eigen::VectorXd &input) override; +}; + +class SimModelTimeDelaySteerAccel : public SimModelInterface { + public: + /** + * @brief constructor + * @param [in] vx_lim velocity limit [m/s] + * @param [in] steer_lim steering limit [rad] + * @param [in] vx_rate_lim acceleration limit [m/ss] + * @param [in] steer_rate_lim steering angular velocity limit [rad/ss] + * @param [in] wheelbase vehicle wheelbase length [m] + * @param [in] dt delta time information to set input buffer for delay + * @param [in] acc_delay time delay for accel command [s] + * @param [in] acc_time_constant time constant for 1D model of accel dynamics + * @param [in] steer_delay time delay for steering command [s] + * @param [in] steer_time_constant time constant for 1D model of steering dynamics + * @param [in] deadzone_delta_steer deadzone value of steer + */ + SimModelTimeDelaySteerAccel( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double acc_delay, double acc_time_constant, double steer_delay, + double steer_time_constant, double deadzone_delta_steer); + + /** + * @brief default destructor + */ + ~SimModelTimeDelaySteerAccel() = default; + + private: + const double MIN_TIME_CONSTANT; //!< @brief minimum time constant + + enum IDX { + X = 0, + Y, + YAW, + VX, + STEER, + ACCX, + }; + enum IDX_U { + ACCX_DES = 0, + STEER_DES, + DRIVE_SHIFT, + }; + + const double vx_lim_; //!< @brief velocity limit [m/s] + const double vx_rate_lim_; //!< @brief acceleration limit [m/ss] + const double steer_lim_; //!< @brief steering limit [rad] + const double steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s] + const double wheelbase_; //!< @brief vehicle wheelbase length [m] + + std::deque acc_input_queue_; //!< @brief buffer for accel command + std::deque steer_input_queue_; //!< @brief buffer for steering command + const double acc_delay_; //!< @brief time delay for accel command [s] + const double acc_time_constant_; //!< @brief time constant for 1D model of accel dynamics + const double steer_delay_; //!< @brief time delay for steering command [s] + const double steer_time_constant_; //!< @brief time constant for 1D model of steering dynamics + const double deadzone_delta_steer_; //!<@ brief deadzone value of steer + + /** + * @brief set queue buffer for input command + * @param [in] dt delta time + */ + void initializeInputQueue(const double &dt); + + /** + * @brief get vehicle position x + */ + double getX() override; + + /** + * @brief get vehicle position y + */ + double getY() override; + + /** + * @brief get vehicle angle yaw + */ + double getYaw() override; + + /** + * @brief get vehicle velocity vx + */ + double getVx() override; + + /** + * @brief get vehicle angular-velocity wz + */ + double getWz() override; + + /** + * @brief get vehicle steering angle + */ + double getSteer() override; + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double &dt) override; + + /** + * @brief calculate derivative of states with time delay steering model + * @param [in] state current model state + * @param [in] input input vector to model + */ + Eigen::VectorXd calcModel(const Eigen::VectorXd &state, const Eigen::VectorXd &input) override; +}; diff --git a/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_util.h b/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_util.h new file mode 100644 index 0000000..252b48e --- /dev/null +++ b/apollo_simulator/include/apollo_simulator/vehicle_sim_model/sim_model_util.h @@ -0,0 +1,24 @@ +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#pragma once + +#include + +namespace sim_model_util { +double getDummySteerCommandWithFriction( + const double steer, const double steer_command, const double deadzone_delta_steer); +} \ No newline at end of file diff --git a/apollo_simulator/launch/simulation.launch b/apollo_simulator/launch/simulation.launch new file mode 100644 index 0000000..aa2640a --- /dev/null +++ b/apollo_simulator/launch/simulation.launch @@ -0,0 +1,7 @@ + + + + + + + diff --git a/apollo_simulator/launch/simulator.launch b/apollo_simulator/launch/simulator.launch new file mode 100644 index 0000000..b2bc3f3 --- /dev/null +++ b/apollo_simulator/launch/simulator.launch @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/apollo_simulator/package.xml b/apollo_simulator/package.xml new file mode 100644 index 0000000..2479951 --- /dev/null +++ b/apollo_simulator/package.xml @@ -0,0 +1,22 @@ + + + apollo_simulator + 1.0.0 + The apollo_simulator package + Forrest + Forrest + + Apache 2 + + catkin + + roscpp + tf2 + tf + roslint + std_msgs + geometry_msgs + apollo_msgs + apollo_common + + diff --git a/apollo_simulator/param/simulator_params.yaml b/apollo_simulator/param/simulator_params.yaml new file mode 100644 index 0000000..8060eef --- /dev/null +++ b/apollo_simulator/param/simulator_params.yaml @@ -0,0 +1,32 @@ +loop_rate: 100.0 +footprint: [[-1.0, 0.8],[3.0, 0.8], [3.0, -0.8], [-1.0, -0.8]] +wheelbase: 2.85 +simulation_frame_id: base_link +map_frame_id: map +add_measurement_noise: true + +# Option for vehicle_model_type: +# - IDEAL_STEER : reads velocity command. The steering and velocity changes exactly the same as commanded. +# - DELAY_STEER : reads velocity command. The steering and velocity changes with delay model. +# - DELAY_STEER_ACC : reads acceleration command. The steering and acceleration changes with delay model. +vehicle_model_type: DELAY_STEER_ACC + +vel_lim: 4.0 +vel_time_constant: 0.61 +vel_time_delay: 0.25 + +accel_rate: 7.0 +acc_time_delay: 0.1 +acc_time_constant: 0.1 + +steer_lim: 1.0 +steer_rate_lim: 5.0 +steer_time_constant: 0.27 +steer_time_delay: 0.24 +deadzone_delta_steer: 0.00 + +pos_noise_stddev: 0.01 +vel_noise_stddev: 0.0 +rpy_noise_stddev: 0.0001 +angvel_noise_stddev: 0.0 +steer_noise_stddev: 0.0001 diff --git a/apollo_simulator/rviz/simulation.rviz b/apollo_simulator/rviz/simulation.rviz new file mode 100644 index 0000000..39b66c0 --- /dev/null +++ b/apollo_simulator/rviz/simulation.rviz @@ -0,0 +1,161 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: ~ + Splitter Ratio: 0.5 + Tree Height: 719 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Axes Length: 1 + Axes Radius: 0.10000000149011612 + Class: rviz/Pose + Color: 255; 25; 0 + Enabled: true + Head Length: 0.30000001192092896 + Head Radius: 0.10000000149011612 + Name: current_pose + Queue Size: 10 + Shaft Length: 1 + Shaft Radius: 0.05000000074505806 + Shape: Arrow + Topic: /current_pose + Unreliable: false + Value: true + - Alpha: 1 + Class: rviz/Polygon + Color: 25; 255; 0 + Enabled: true + Name: footprint + Queue Size: 10 + Topic: /apollo_simulator/footprint + Unreliable: false + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Head Diameter: 0.30000001192092896 + Head Length: 0.20000000298023224 + Length: 0.30000001192092896 + Line Style: Billboards + Line Width: 0.5 + Name: Path + Offset: + X: 0 + Y: 0 + Z: 0 + Pose Color: 255; 85; 255 + Pose Style: None + Queue Size: 10 + Radius: 0.029999999329447746 + Shaft Diameter: 0.10000000149011612 + Shaft Length: 0.10000000149011612 + Topic: /apollo_simulator/trajectory + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Angle: 0.034999772906303406 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Scale: 16.274085998535156 + Target Frame: + X: -1.9362672567367554 + Y: -3.652482748031616 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1016 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd0000000400000000000001560000035afc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000035a000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004f80000003efc0100000002fb0000000800540069006d00650100000000000004f8000002eb00fffffffb0000000800540069006d006501000000000000045000000000000000000000039c0000035a00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: true + Width: 1272 + X: 648 + Y: 27 diff --git a/apollo_simulator/src/apollo_simulator.cpp b/apollo_simulator/src/apollo_simulator.cpp new file mode 100644 index 0000000..cbf32c3 --- /dev/null +++ b/apollo_simulator/src/apollo_simulator.cpp @@ -0,0 +1,475 @@ +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_simulator/apollo_simulator.h" + +#include +#include +#include + +#include "apollo_common/adapters/adapter_manager.h" +#include "apollo_common/log.h" +#include "apollo_common/math/quaternion.h" +#include "apollo_common/math/math_utils.h" +#include "apollo_msgs/proto/localization/localization.pb.h" +#include "apollo_msgs/proto/canbus/chassis.pb.h" + +using apollo::common::adapter::AdapterManager; + +Simulator::Simulator(tf2_ros::Buffer &tf_buffer) + : tf_buffer_(tf_buffer) { + ros::NodeHandle nh; + ros::NodeHandle private_nh("~"); + + /* simple_planning_simulator parameters */ + private_nh.param("loop_rate", loop_rate_, 30.0); + private_nh.param("wheelbase", wheelbase_, 0.0); + private_nh.param("steer_transmission_ratio", steer_transmission_ratio_, 16.0); + private_nh.param("steer_single_direction_max_degree", steer_single_direction_max_degree_, 470.0); + private_nh.param("simulation_frame_id", simulation_frame_id_, std::string("base_link")); + private_nh.param("map_frame_id", map_frame_id_, std::string("map")); + private_nh.param("add_measurement_noise", add_measurement_noise_, false); + std::string full_param_name; + if (private_nh.searchParam("footprint", full_param_name)) { + XmlRpc::XmlRpcValue footprint_xmlrpc; + private_nh.getParam(full_param_name, footprint_xmlrpc); + if (footprint_xmlrpc.getType() == XmlRpc::XmlRpcValue::TypeArray) { + footprint_ = MakeFootprintFromXMLRPC(footprint_xmlrpc, full_param_name); + } else { + ROS_FATAL("Values in the footprint specification must be numbers"); + throw std::runtime_error("Values in the footprint specification must be numbers"); + } + } else { + ROS_FATAL("search footprint param fail"); + throw std::runtime_error("search footprint param fail."); + } + + /* set pub sub topic name */ + pub_pose_ = private_nh.advertise("current_pose", 1); + pub_speed_ = private_nh.advertise("current_speed", 1); + pub_footprint_ = private_nh.advertise("footprint", 1); + pub_trajectory_ = private_nh.advertise("trajectory", 1); + + sub_initialtwist_ = nh.subscribe("/initial_twist", 10, &Simulator::CallbackInitialTwistStamped, this); + sub_initialpose_ = nh.subscribe("/initial_pose", 10, &Simulator::CallbackInitialPoseWithCov, this); + + const double dt = 1.0 / loop_rate_; + + /* Timer */ + timer_simulation_ = nh.createTimer(ros::Duration(dt), &Simulator::TimerCallbackSimulation, this); + + /* set vehicle model parameters */ + { + std::string vehicle_model_type_str; + private_nh.param("vehicle_model_type", vehicle_model_type_str, std::string("IDEAL_STEER")); + ROS_INFO("vehicle_model_type = %s", vehicle_model_type_str.c_str()); + double vel_lim, vel_time_delay, vel_time_constant; + private_nh.param("vel_lim", vel_lim, 50.0); + private_nh.param("vel_time_delay", vel_time_delay, 0.25); + private_nh.param("vel_time_constant", vel_time_constant, 0.5); + double accel_rate, acc_time_delay, acc_time_constant; + private_nh.param("accel_rate", accel_rate, 10.0); + private_nh.param("acc_time_delay", acc_time_delay, 0.1); + private_nh.param("acc_time_constant", acc_time_constant, 0.1); + double steer_lim, steer_rate_lim, steer_time_delay, steer_time_constant, deadzone_delta_steer; + private_nh.param("steer_lim", steer_lim, 1.0); + private_nh.param("steer_rate_lim", steer_rate_lim, 5.0); + private_nh.param("steer_time_delay", steer_time_delay, 0.3); + private_nh.param("steer_time_constant", steer_time_constant, 0.3); + private_nh.param("deadzone_delta_steer", steer_time_constant, 0.0); + + if (vehicle_model_type_str == "IDEAL_STEER") { + vehicle_model_type_ = VehicleModelType::IDEAL_STEER; + vehicle_model_ptr_ = std::make_shared(wheelbase_); + } else if (vehicle_model_type_str == "DELAY_STEER") { + vehicle_model_type_ = VehicleModelType::DELAY_STEER; + vehicle_model_ptr_ = std::make_shared( + vel_lim, steer_lim, accel_rate, steer_rate_lim, wheelbase_, dt, vel_time_delay, + vel_time_constant, steer_time_delay, steer_time_constant, deadzone_delta_steer); + } else if (vehicle_model_type_str == "DELAY_STEER_ACC") { + vehicle_model_type_ = VehicleModelType::DELAY_STEER_ACC; + vehicle_model_ptr_ = std::make_shared( + vel_lim, steer_lim, accel_rate, steer_rate_lim, wheelbase_, dt, acc_time_delay, + acc_time_constant, steer_time_delay, steer_time_constant, deadzone_delta_steer); + } else { + ROS_ERROR("Invalid vehicle_model_type. Initialization failed."); + } + } + + /* set normal distribution noises */ + { + int random_seed; + private_nh.param("random_seed", random_seed, 1); + if (random_seed >= 0) { + rand_engine_ptr_ = std::make_shared(random_seed); + } else { + std::random_device seed; + rand_engine_ptr_ = std::make_shared(seed()); + } + double pos_noise_stddev, vel_noise_stddev, rpy_noise_stddev, angvel_noise_stddev, steer_noise_stddev; + private_nh.param("pos_noise_stddev", pos_noise_stddev, 0.01); + private_nh.param("vel_noise_stddev", vel_noise_stddev, 0.0); + private_nh.param("rpy_noise_stddev", rpy_noise_stddev, 0.0001); + private_nh.param("angvel_noise_stddev", angvel_noise_stddev, 0.0); + private_nh.param("steer_noise_stddev", steer_noise_stddev, 0.0001); + pos_norm_dist_ptr_ = std::make_shared>(0.0, pos_noise_stddev); + vel_norm_dist_ptr_ = std::make_shared>(0.0, vel_noise_stddev); + rpy_norm_dist_ptr_ = std::make_shared>(0.0, rpy_noise_stddev); + angvel_norm_dist_ptr_ = std::make_shared>(0.0, angvel_noise_stddev); + steer_norm_dist_ptr_ = std::make_shared>(0.0, steer_noise_stddev); + } + + current_pose_.orientation.w = 1.0; + closest_pos_z_ = 0.0; + + std::string adapter_config_path; + private_nh.param("adapter_config_path", adapter_config_path, std::string("")); + AdapterManager::Init(adapter_config_path); +} + +void Simulator::PublishChassis(const double &steering_angle, const geometry_msgs::Twist &twist) { + apollo::canbus::Chassis chassis; + AdapterManager::FillChassisHeader("chassis", chassis.mutable_header()); + chassis.set_driving_mode(apollo::canbus::Chassis_DrivingMode_COMPLETE_AUTO_DRIVE); + chassis.set_speed_mps(twist.linear.x); + + AdapterManager::PublishChassis(chassis); + ADEBUG << chassis.ShortDebugString(); +} + +void Simulator::PublishLocalization(const geometry_msgs::Pose &pose, const geometry_msgs::Twist &twist) { + apollo::localization::LocalizationEstimate localization; + // header + AdapterManager::FillLocalizationHeader("localization", localization.mutable_header()); + // position + auto mutable_pose = localization.mutable_pose(); + mutable_pose->mutable_position()->set_x(pose.position.x); + mutable_pose->mutable_position()->set_y(pose.position.y); + mutable_pose->mutable_position()->set_z(pose.position.z); + // orientation(RFU) + double roll, pitch, yaw; + tf2::getEulerYPR(pose.orientation, yaw, pitch, roll); + yaw = apollo::common::math::NormalizeAngle(yaw - M_PI_2); + auto rfu_orientation = GetQuaternionFromRPY(roll, pitch, yaw); + mutable_pose->mutable_orientation()->set_qw(rfu_orientation.w); + mutable_pose->mutable_orientation()->set_qx(rfu_orientation.x); + mutable_pose->mutable_orientation()->set_qy(rfu_orientation.y); + mutable_pose->mutable_orientation()->set_qz(rfu_orientation.z); + // car heading + double heading = ::apollo::common::math::QuaternionToHeading( + rfu_orientation.w, rfu_orientation.x, + rfu_orientation.y, rfu_orientation.z); + mutable_pose->set_heading(heading); + // linear velocity(RFU) + mutable_pose->mutable_linear_velocity()->set_x(-twist.linear.y); + mutable_pose->mutable_linear_velocity()->set_y(twist.linear.x); + mutable_pose->mutable_linear_velocity()->set_z(twist.linear.z); + // angular velocity(RFU) + mutable_pose->mutable_angular_velocity()->set_x(-twist.angular.y); + mutable_pose->mutable_angular_velocity()->set_y(twist.angular.x); + mutable_pose->mutable_angular_velocity()->set_z(twist.angular.z); + + // publish localization messages + AdapterManager::PublishLocalization(localization); + AINFO << "[OnTimer]: Localization message publish success!"; +} + +void Simulator::PublishPlanningTrajectory() { + if (AdapterManager::GetPlanningTrajectory() == nullptr) { + return; + } + if (AdapterManager::GetPlanningTrajectory()->Empty()) { + return; + } + const auto &trajectory = AdapterManager::GetPlanningTrajectory()->GetLatestObserved(); + // AERROR << "trajectory: " << trajectory.ShortDebugString(); + nav_msgs::Path path; + path.header.frame_id = map_frame_id_; + path.header.stamp = ros::Time::now(); + geometry_msgs::PoseStamped ps; + ps.header = path.header; + for (size_t i = 0; i < trajectory.adc_trajectory_point_size(); ++i) { + ps.pose.position.x = trajectory.adc_trajectory_point(i).x(); + ps.pose.position.y = trajectory.adc_trajectory_point(i).y(); + ps.pose.position.z = 0; + ps.pose.orientation = GetQuaternionFromRPY(0, 0, trajectory.adc_trajectory_point(i).theta()); + path.poses.push_back(ps); + } + pub_trajectory_.publish(path); +} + +void Simulator::TimerCallbackSimulation(const ros::TimerEvent &event) { + if (!is_initialized_) { + ROS_INFO("waiting initial position..."); + return; + } + + if (prev_update_time_ptr_ == nullptr) { + prev_update_time_ptr_ = std::make_shared(ros::Time::now()); + } + + AdapterManager::Observe(); + if (AdapterManager::GetControlCommand() != nullptr && !AdapterManager::GetControlCommand()->Empty()) { + const auto &ctrl_cmd = AdapterManager::GetControlCommand()->GetLatestObserved(); + // AERROR << "control_command: " << ctrl_cmd.ShortDebugString(); + + double linear_vel = ctrl_cmd.debug().simple_lon_debug().speed_reference(); + double steer_angle = ctrl_cmd.debug().simple_lat_debug().steer_angle(); + steer_angle /= (180.0 / M_PI * steer_transmission_ratio_ / steer_single_direction_max_degree_ * 100.0); + if (vehicle_model_type_ == VehicleModelType::IDEAL_STEER || + vehicle_model_type_ == VehicleModelType::DELAY_STEER) { + Eigen::VectorXd input(2); + input << linear_vel, steer_angle; + vehicle_model_ptr_->setInput(input); + } else if (vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC) { + Eigen::VectorXd input(3); + double drive_shift = (linear_vel < 0) ? -1.0 : 1.0; + // 注意:这里的input中acceleration不管前进还是后退都是正向增大的,但是msg中后退是负向增大的 + double acceleration = ctrl_cmd.debug().simple_lon_debug().acceleration_cmd(); + input << (acceleration * drive_shift), steer_angle, drive_shift; + vehicle_model_ptr_->setInput(input); + // ROS_INFO("target linear_vel: %.2f", linear_vel); + // ROS_INFO("target acceleration: %.2f", acceleration); + // ROS_INFO("target steer_angle: %.2f", steer_angle); + } else { + ROS_WARN("invalid vehicle_model_type_ error."); + } + } + + /* calculate delta time */ + const double dt = (ros::Time::now() - *prev_update_time_ptr_).toSec(); + *prev_update_time_ptr_ = ros::Time::now(); + + /* update vehicle dynamics*/ + vehicle_model_ptr_->update(dt); + + /* save current vehicle pose & twist */ + current_pose_.position.x = vehicle_model_ptr_->getX(); + current_pose_.position.y = vehicle_model_ptr_->getY(); + closest_pos_z_ = 0.0; + current_pose_.position.z = closest_pos_z_; + double roll = 0.0; + double pitch = 0.0; + double yaw = vehicle_model_ptr_->getYaw(); + current_twist_.linear.x = vehicle_model_ptr_->getVx(); + current_twist_.angular.z = vehicle_model_ptr_->getWz(); + + if (add_measurement_noise_) { + current_pose_.position.x += (*pos_norm_dist_ptr_)(*rand_engine_ptr_); + current_pose_.position.y += (*pos_norm_dist_ptr_)(*rand_engine_ptr_); + current_pose_.position.z += (*pos_norm_dist_ptr_)(*rand_engine_ptr_); + roll += (*rpy_norm_dist_ptr_)(*rand_engine_ptr_); + pitch += (*rpy_norm_dist_ptr_)(*rand_engine_ptr_); + yaw += (*rpy_norm_dist_ptr_)(*rand_engine_ptr_); + if (current_twist_.linear.x >= 0.0) { + current_twist_.linear.x += (*vel_norm_dist_ptr_)(*rand_engine_ptr_); + } else { + current_twist_.linear.x -= (*vel_norm_dist_ptr_)(*rand_engine_ptr_); + } + current_twist_.angular.z += (*angvel_norm_dist_ptr_)(*rand_engine_ptr_); + } + + current_pose_.orientation = GetQuaternionFromRPY(roll, pitch, yaw); + + /* publish pose */ + ros::Time current_time = ros::Time::now(); + geometry_msgs::PoseStamped sim_ps; + sim_ps.header.frame_id = map_frame_id_; + sim_ps.header.stamp = current_time; + sim_ps.pose = current_pose_; + pub_pose_.publish(sim_ps); + + /* publish speed */ + pub_speed_.publish(current_twist_); + + /* publish for apollo */ + double steering_angle = vehicle_model_ptr_->getSteer(); + if (add_measurement_noise_) { + steering_angle += (*steer_norm_dist_ptr_)(*rand_engine_ptr_); + } + PublishChassis(steering_angle, current_twist_); + PublishLocalization(current_pose_, current_twist_); + PublishPlanningTrajectory(); + + /* publish tf */ + PublishTF(current_pose_); + + /* publish footprint polygon */ + geometry_msgs::PolygonStamped footprint; + footprint.header.frame_id = simulation_frame_id_; + footprint.header.stamp = current_time; + for (const auto &point : footprint_) { + geometry_msgs::Point32 new_pt; + new_pt.x = point.x; + new_pt.y = point.y; + footprint.polygon.points.push_back(new_pt); + } + pub_footprint_.publish(footprint); +} + +void Simulator::CallbackInitialPoseWithCov(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg) { + geometry_msgs::Twist initial_twist; // initialized with zero for all components + if (initial_twist_ptr_) { + initial_twist = initial_twist_ptr_->twist; + } + // save initial pose + initial_pose_with_cov_ptr_ = msg; + SetInitialStateWithPoseTransform(*initial_pose_with_cov_ptr_, initial_twist); +} + +void Simulator::CallbackInitialPoseStamped(const geometry_msgs::PoseStamped::ConstPtr &msg) { + geometry_msgs::Twist initial_twist; // initialized with zero for all components + if (initial_twist_ptr_) { + initial_twist = initial_twist_ptr_->twist; + } + // save initial pose + initial_pose_ptr_ = msg; + SetInitialStateWithPoseTransform(*initial_pose_ptr_, initial_twist); +} + +void Simulator::CallbackInitialTwistStamped(const geometry_msgs::TwistStamped::ConstPtr &msg) { + // save initial pose + initial_twist_ptr_ = msg; + if (initial_pose_ptr_) { + SetInitialStateWithPoseTransform(*initial_pose_ptr_, initial_twist_ptr_->twist); + // input twist to simulator's internal parameter + current_pose_ = initial_pose_ptr_->pose; + current_twist_ = initial_twist_ptr_->twist; + } else if (initial_pose_with_cov_ptr_) { + SetInitialStateWithPoseTransform(*initial_pose_with_cov_ptr_, initial_twist_ptr_->twist); + } +} + +void Simulator::SetInitialStateWithPoseTransform( + const geometry_msgs::PoseStamped &pose_stamped, const geometry_msgs::Twist &twist) { + geometry_msgs::TransformStamped transform; + GetTransformFromTF(map_frame_id_, pose_stamped.header.frame_id, transform); + geometry_msgs::Pose pose; + pose.position.x = pose_stamped.pose.position.x + transform.transform.translation.x; + pose.position.y = pose_stamped.pose.position.y + transform.transform.translation.y; + pose.position.z = pose_stamped.pose.position.z + transform.transform.translation.z; + pose.orientation = pose_stamped.pose.orientation; + SetInitialState(pose, twist); +} + +void Simulator::SetInitialStateWithPoseTransform(const geometry_msgs::PoseWithCovarianceStamped &pose, + const geometry_msgs::Twist &twist) { + geometry_msgs::PoseStamped ps; + ps.header = pose.header; + ps.pose = pose.pose.pose; + SetInitialStateWithPoseTransform(ps, twist); +} + +void Simulator::SetInitialState(const geometry_msgs::Pose &pose, const geometry_msgs::Twist &twist) { + const double x = pose.position.x; + const double y = pose.position.y; + const double yaw = tf2::getYaw(pose.orientation); + const double vx = twist.linear.x; + const double steer = 0.0; + const double acc = 0.0; + + if (vehicle_model_type_ == VehicleModelType::IDEAL_STEER) { + Eigen::VectorXd state(3); + state << x, y, yaw; + vehicle_model_ptr_->setState(state); + } else if (vehicle_model_type_ == VehicleModelType::DELAY_STEER) { + Eigen::VectorXd state(5); + state << x, y, yaw, vx, steer; + vehicle_model_ptr_->setState(state); + } else if (vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC) { + Eigen::VectorXd state(6); + state << x, y, yaw, vx, steer, acc; + vehicle_model_ptr_->setState(state); + } else { + ROS_WARN("undesired vehicle model type! Initialization failed."); + return; + } + + is_initialized_ = true; +} + +void Simulator::GetTransformFromTF(const std::string parent_frame, const std::string child_frame, + geometry_msgs::TransformStamped &transform) { + while (ros::ok()) { + try { + transform = tf_buffer_.lookupTransform(parent_frame, child_frame, ros::Time(0)); + break; + } catch (tf2::TransformException &ex) { + ROS_ERROR("%s", ex.what()); + } + } +} + +void Simulator::PublishTF(const geometry_msgs::Pose &pose) { + ros::Time current_time = ros::Time::now(); + + // send odom transform + geometry_msgs::TransformStamped odom_trans; + odom_trans.header.stamp = current_time; + odom_trans.header.frame_id = map_frame_id_; + odom_trans.child_frame_id = simulation_frame_id_; + odom_trans.transform.translation.x = pose.position.x; + odom_trans.transform.translation.y = pose.position.y; + odom_trans.transform.translation.z = pose.position.z; + odom_trans.transform.rotation = pose.orientation; + tf_broadcaster_.sendTransform(odom_trans); +} + +geometry_msgs::Quaternion Simulator::GetQuaternionFromRPY( + const double &roll, const double &pitch, const double &yaw) { + tf2::Quaternion q; + q.setRPY(roll, pitch, yaw); + return tf2::toMsg(q); +} + +double Simulator::GetNumberFromXMLRPC(XmlRpc::XmlRpcValue &value, const std::string &full_param_name) { + // Make sure that the value we're looking at is either a double or an int. + if (value.getType() != XmlRpc::XmlRpcValue::TypeInt && value.getType() != XmlRpc::XmlRpcValue::TypeDouble) { + std::string &value_string = value; + ROS_FATAL("Values in the footprint specification (param %s) must be numbers. Found value %s.", + full_param_name.c_str(), value_string.c_str()); + throw std::runtime_error("Values in the footprint specification must be numbers"); + } + return value.getType() == XmlRpc::XmlRpcValue::TypeInt ? (int)(value) : (double)(value); +} + +std::vector Simulator::MakeFootprintFromXMLRPC(XmlRpc::XmlRpcValue &footprint_xmlrpc, + const std::string &full_param_name, const size_t min_size) { + // Make sure we have an array of at least 3 elements. + if (footprint_xmlrpc.getType() != XmlRpc::XmlRpcValue::TypeArray || footprint_xmlrpc.size() < min_size) { + ROS_FATAL("The footprint must be specified as list of lists on the parameter server, %s was specified as %s", + full_param_name.c_str(), std::string(footprint_xmlrpc).c_str()); + throw std::runtime_error("The footprint must be specified as list of lists on the parameter server with at least " + "1 points eg: [[x1, y1], [x2, y2], ..., [xn, yn]]"); + } + std::vector footprint; + geometry_msgs::Point pt; + for (int i = 0; i < footprint_xmlrpc.size(); ++i) { + // Make sure each element of the list is an array of size 2. (x and y coordinates) + XmlRpc::XmlRpcValue point = footprint_xmlrpc[ i ]; + if (point.getType() != XmlRpc::XmlRpcValue::TypeArray || point.size() != 2) { + ROS_FATAL("The footprint (parameter %s) must be specified as list of lists on the parameter server eg: " + "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form.", + full_param_name.c_str()); + throw std::runtime_error("The footprint must be specified as list of lists on the parameter server eg: " + "[[x1, y1], [x2, y2], ..., [xn, yn]], but this spec is not of that form"); + } + pt.x = GetNumberFromXMLRPC(point[0], full_param_name); + pt.y = GetNumberFromXMLRPC(point[1], full_param_name); + footprint.push_back(pt); + } + return footprint; +} diff --git a/apollo_simulator/src/main.cpp b/apollo_simulator/src/main.cpp new file mode 100644 index 0000000..ca863a9 --- /dev/null +++ b/apollo_simulator/src/main.cpp @@ -0,0 +1,39 @@ +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include +#include +#include + +#include "apollo_common/log.h" +#include "apollo_simulator/apollo_simulator.h" + +int main(int argc, char **argv) { + google::InitGoogleLogging(argv[0]); + google::ParseCommandLineFlags(&argc, &argv, true); + + ros::init(argc, argv, "apollo_simulator"); + + tf2_ros::Buffer buffer(ros::Duration(10)); + tf2_ros::TransformListener tf(buffer); + + Simulator obj(buffer); + + ros::spin(); + ros::waitForShutdown(); + + return 0; +}; diff --git a/apollo_simulator/src/vehicle_sim_model/sim_model_constant_acceleration.cpp b/apollo_simulator/src/vehicle_sim_model/sim_model_constant_acceleration.cpp new file mode 100644 index 0000000..13f9b6f --- /dev/null +++ b/apollo_simulator/src/vehicle_sim_model/sim_model_constant_acceleration.cpp @@ -0,0 +1,79 @@ +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_simulator/vehicle_sim_model/sim_model_constant_acceleration.h" + +#include + +SimModelConstantAccelTwist::SimModelConstantAccelTwist( + double vx_lim, double wz_lim, double vx_rate, double wz_rate) + : SimModelInterface(5 /* dim x */, 2 /* dim u */), + vx_lim_(vx_lim), + wz_lim_(wz_lim), + vx_rate_(vx_rate), + wz_rate_(wz_rate) {} + +double SimModelConstantAccelTwist::getX() { + return state_(IDX::X); +} +double SimModelConstantAccelTwist::getY() { + return state_(IDX::Y); +} +double SimModelConstantAccelTwist::getYaw() { + return state_(IDX::YAW); +} +double SimModelConstantAccelTwist::getVx() { + return state_(IDX::VX); +} +double SimModelConstantAccelTwist::getWz() { + return state_(IDX::WZ); +} +double SimModelConstantAccelTwist::getSteer() { + return 0.0; +} +void SimModelConstantAccelTwist::update(const double &dt) { + updateRungeKutta(dt, input_); +} +Eigen::VectorXd SimModelConstantAccelTwist::calcModel( + const Eigen::VectorXd &state, const Eigen::VectorXd &input) { + const double vel = state(IDX::VX); + const double angvel = state(IDX::WZ); + const double yaw = state(IDX::YAW); + const double vx_des = std::max(std::min(input(IDX_U::VX_DES), vx_lim_), -vx_lim_); + const double wz_des = std::max(std::min(input(IDX_U::WZ_DES), wz_lim_), -wz_lim_); + double vx_rate = 0.0; + double wz_rate = 0.0; + if (vx_des > vel) { + vx_rate = vx_rate_; + } else if (vx_des < vel) { + vx_rate = -vx_rate_; + } + + if (wz_des > angvel) { + wz_rate = wz_rate_; + } else if (wz_des < angvel) { + wz_rate = -wz_rate_; + } + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + d_state(IDX::X) = vel * cos(yaw); + d_state(IDX::Y) = vel * sin(yaw); + d_state(IDX::YAW) = angvel; + d_state(IDX::VX) = vx_rate; + d_state(IDX::WZ) = wz_rate; + + return d_state; +} diff --git a/apollo_simulator/src/vehicle_sim_model/sim_model_ideal.cpp b/apollo_simulator/src/vehicle_sim_model/sim_model_ideal.cpp new file mode 100644 index 0000000..5a51812 --- /dev/null +++ b/apollo_simulator/src/vehicle_sim_model/sim_model_ideal.cpp @@ -0,0 +1,137 @@ +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_simulator/vehicle_sim_model/sim_model_ideal.h" + +SimModelIdealTwist::SimModelIdealTwist() + : SimModelInterface(3 /* dim x */, 2 /* dim u */) {} + +double SimModelIdealTwist::getX() { + return state_(IDX::X); +} +double SimModelIdealTwist::getY() { + return state_(IDX::Y); +} +double SimModelIdealTwist::getYaw() { + return state_(IDX::YAW); +} +double SimModelIdealTwist::getVx() { + return input_(IDX_U::VX_DES); +} +double SimModelIdealTwist::getWz() { + return input_(IDX_U::WZ_DES); +} +double SimModelIdealTwist::getSteer() { + return 0.0; +} +void SimModelIdealTwist::update(const double &dt) { + updateRungeKutta(dt, input_); +} +Eigen::VectorXd SimModelIdealTwist::calcModel( + const Eigen::VectorXd &state, const Eigen::VectorXd &input) { + const double yaw = state(IDX::YAW); + const double vx = input(IDX_U::VX_DES); + const double wz = input(IDX_U::WZ_DES); + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + d_state(IDX::X) = vx * cos(yaw); + d_state(IDX::Y) = vx * sin(yaw); + d_state(IDX::YAW) = wz; + + return d_state; +} + +SimModelIdealSteer::SimModelIdealSteer(double wheelbase) + : SimModelInterface(3 /* dim x */, 2 /* dim u */), wheelbase_(wheelbase) {} + +double SimModelIdealSteer::getX() { + return state_(IDX::X); +} +double SimModelIdealSteer::getY() { + return state_(IDX::Y); +} +double SimModelIdealSteer::getYaw() { + return state_(IDX::YAW); +} +double SimModelIdealSteer::getVx() { + return input_(IDX_U::VX_DES); +} +double SimModelIdealSteer::getWz() { + return input_(IDX_U::VX_DES) * std::tan(input_(IDX_U::STEER_DES)) / wheelbase_; +} +double SimModelIdealSteer::getSteer() { + return input_(IDX_U::STEER_DES); +} +void SimModelIdealSteer::update(const double &dt) { + updateRungeKutta(dt, input_); +} +Eigen::VectorXd SimModelIdealSteer::calcModel( + const Eigen::VectorXd &state, const Eigen::VectorXd &input) { + const double yaw = state(IDX::YAW); + const double vx = input(IDX_U::VX_DES); + const double steer = input(IDX_U::STEER_DES); + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + d_state(IDX::X) = vx * cos(yaw); + d_state(IDX::Y) = vx * sin(yaw); + d_state(IDX::YAW) = vx * std::tan(steer) / wheelbase_; + + return d_state; +} + +SimModelIdealAccel::SimModelIdealAccel(double wheelbase) + : SimModelInterface(4 /* dim x */, 2 /* dim u */), wheelbase_(wheelbase) {} + +double SimModelIdealAccel::getX() { + return state_(IDX::X); +} +double SimModelIdealAccel::getY() { + return state_(IDX::Y); +} +double SimModelIdealAccel::getYaw() { + return state_(IDX::YAW); +} +double SimModelIdealAccel::getVx() { + return state_(IDX::VX); +} +double SimModelIdealAccel::getWz() { + return state_(IDX::VX) * std::tan(input_(IDX_U::STEER_DES)) / wheelbase_; +} +double SimModelIdealAccel::getSteer() { + return input_(IDX_U::STEER_DES); +} +void SimModelIdealAccel::update(const double &dt) { + updateRungeKutta(dt, input_); + if (state_(IDX::VX) < 0) { + state_(IDX::VX) = 0; + } +} + +Eigen::VectorXd SimModelIdealAccel::calcModel( + const Eigen::VectorXd &state, const Eigen::VectorXd &input) { + const double vx = state(IDX::VX); + const double yaw = state(IDX::YAW); + const double ax = input(IDX_U::AX_DES); + const double steer = input(IDX_U::STEER_DES); + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + d_state(IDX::X) = vx * cos(yaw); + d_state(IDX::Y) = vx * sin(yaw); + d_state(IDX::VX) = ax; + d_state(IDX::YAW) = vx * std::tan(steer) / wheelbase_; + + return d_state; +} diff --git a/apollo_simulator/src/vehicle_sim_model/sim_model_interface.cpp b/apollo_simulator/src/vehicle_sim_model/sim_model_interface.cpp new file mode 100644 index 0000000..3142eea --- /dev/null +++ b/apollo_simulator/src/vehicle_sim_model/sim_model_interface.cpp @@ -0,0 +1,48 @@ +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_simulator/vehicle_sim_model/sim_model_interface.h" + +SimModelInterface::SimModelInterface(int dim_x, int dim_u) + : dim_x_(dim_x), dim_u_(dim_u) { + state_ = Eigen::VectorXd::Zero(dim_x_); + input_ = Eigen::VectorXd::Zero(dim_u_); +} + +void SimModelInterface::updateRungeKutta(const double &dt, const Eigen::VectorXd &input) { + Eigen::VectorXd k1 = calcModel(state_, input); + Eigen::VectorXd k2 = calcModel(state_ + k1 * 0.5 * dt, input); + Eigen::VectorXd k3 = calcModel(state_ + k2 * 0.5 * dt, input); + Eigen::VectorXd k4 = calcModel(state_ + k3 * dt, input); + + state_ += 1.0 / 6.0 * (k1 + 2.0 * k2 + 2.0 * k3 + k4) * dt; +} +void SimModelInterface::updateEuler(const double &dt, const Eigen::VectorXd &input) { + state_ += calcModel(state_, input) * dt; +} +void SimModelInterface::getState(Eigen::VectorXd &state) { + state = state_; +} +void SimModelInterface::getInput(Eigen::VectorXd &input) { + input = input_; +} +void SimModelInterface::setState(const Eigen::VectorXd &state) { + state_ = state; +} +void SimModelInterface::setInput(const Eigen::VectorXd &input) { + input_ = input; +} + diff --git a/apollo_simulator/src/vehicle_sim_model/sim_model_time_delay.cpp b/apollo_simulator/src/vehicle_sim_model/sim_model_time_delay.cpp new file mode 100644 index 0000000..18ba233 --- /dev/null +++ b/apollo_simulator/src/vehicle_sim_model/sim_model_time_delay.cpp @@ -0,0 +1,339 @@ +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_simulator/vehicle_sim_model/sim_model_time_delay.h" + +#include + +/* + * + * SimModelTimeDelayTwist + * + */ + +SimModelTimeDelayTwist::SimModelTimeDelayTwist( + double vx_lim, double wz_lim, double vx_rate_lim, double wz_rate_lim, double dt, double vx_delay, + double vx_time_constant, double wz_delay, double wz_time_constant, double deadzone_delta_steer) + : SimModelInterface(5 /* dim x */, 2 /* dim u */), + MIN_TIME_CONSTANT(0.03), + vx_lim_(vx_lim), + vx_rate_lim_(vx_rate_lim), + wz_lim_(wz_lim), + wz_rate_lim_(wz_rate_lim), + vx_delay_(vx_delay), + vx_time_constant_(std::max(vx_time_constant, MIN_TIME_CONSTANT)), + wz_delay_(wz_delay), + wz_time_constant_(std::max(wz_time_constant, MIN_TIME_CONSTANT)), + deadzone_delta_steer_(deadzone_delta_steer) { + if (vx_time_constant < MIN_TIME_CONSTANT) { + std::cout << "Settings vx_time_constant is too small, replace it by " << MIN_TIME_CONSTANT << + std::endl; + } + if (wz_time_constant < MIN_TIME_CONSTANT) { + std::cout << "Settings wz_time_constant is too small, replace it by " << MIN_TIME_CONSTANT << + std::endl; + } + initializeInputQueue(dt); +} + +double SimModelTimeDelayTwist::getX() { + return state_(IDX::X); +} +double SimModelTimeDelayTwist::getY() { + return state_(IDX::Y); +} +double SimModelTimeDelayTwist::getYaw() { + return state_(IDX::YAW); +} +double SimModelTimeDelayTwist::getVx() { + return state_(IDX::VX); +} +double SimModelTimeDelayTwist::getWz() { + return state_(IDX::WZ); +} +double SimModelTimeDelayTwist::getSteer() { + return 0.0; +} +void SimModelTimeDelayTwist::update(const double &dt) { + Eigen::VectorXd delayed_input = Eigen::VectorXd::Zero(dim_u_); + + vx_input_queue_.push_back(input_(IDX_U::VX_DES)); + delayed_input(IDX_U::VX_DES) = vx_input_queue_.front(); + vx_input_queue_.pop_front(); + wz_input_queue_.push_back(input_(IDX_U::WZ_DES)); + delayed_input(IDX_U::WZ_DES) = wz_input_queue_.front(); + wz_input_queue_.pop_front(); + // do not use deadzone_delta_steer (Steer IF does not exist in this model) + updateRungeKutta(dt, delayed_input); +} +void SimModelTimeDelayTwist::initializeInputQueue(const double &dt) { + size_t vx_input_queue_size = static_cast(round(vx_delay_ / dt)); + for (size_t i = 0; i < vx_input_queue_size; i++) { + vx_input_queue_.push_back(0.0); + } + size_t wz_input_queue_size = static_cast(round(wz_delay_ / dt)); + for (size_t i = 0; i < wz_input_queue_size; i++) { + wz_input_queue_.push_back(0.0); + } +} + +Eigen::VectorXd SimModelTimeDelayTwist::calcModel( + const Eigen::VectorXd &state, const Eigen::VectorXd &input) { + const double vx = state(IDX::VX); + const double wz = state(IDX::WZ); + const double yaw = state(IDX::YAW); + const double delay_input_vx = input(IDX_U::VX_DES); + const double delay_input_wz = input(IDX_U::WZ_DES); + const double delay_vx_des = std::max(std::min(delay_input_vx, vx_lim_), -vx_lim_); + const double delay_wz_des = std::max(std::min(delay_input_wz, wz_lim_), -wz_lim_); + double vx_rate = -(vx - delay_vx_des) / vx_time_constant_; + double wz_rate = -(wz - delay_wz_des) / wz_time_constant_; + vx_rate = std::min(vx_rate_lim_, std::max(-vx_rate_lim_, vx_rate)); + wz_rate = std::min(wz_rate_lim_, std::max(-wz_rate_lim_, wz_rate)); + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + d_state(IDX::X) = vx * cos(yaw); + d_state(IDX::Y) = vx * sin(yaw); + d_state(IDX::YAW) = wz; + d_state(IDX::VX) = vx_rate; + d_state(IDX::WZ) = wz_rate; + + return d_state; +} + +/* + * + * SimModelTimeDelaySteer + * + */ +SimModelTimeDelaySteer::SimModelTimeDelaySteer( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double vx_delay, double vx_time_constant, double steer_delay, + double steer_time_constant, double deadzone_delta_steer) + : SimModelInterface(5 /* dim x */, 2 /* dim u */), + MIN_TIME_CONSTANT(0.03), + vx_lim_(vx_lim), + vx_rate_lim_(vx_rate_lim), + steer_lim_(steer_lim), + steer_rate_lim_(steer_rate_lim), + wheelbase_(wheelbase), + vx_delay_(vx_delay), + vx_time_constant_(std::max(vx_time_constant, MIN_TIME_CONSTANT)), + steer_delay_(steer_delay), + steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), + deadzone_delta_steer_(deadzone_delta_steer) { + if (vx_time_constant < MIN_TIME_CONSTANT) { + std::cout << "Settings vx_time_constant is too small, replace it by " << MIN_TIME_CONSTANT << + std::endl; + } + if (steer_time_constant < MIN_TIME_CONSTANT) { + std::cout << "Settings steer_time_constant is too small, replace it by " << MIN_TIME_CONSTANT << + std::endl; + } + + initializeInputQueue(dt); +} + +double SimModelTimeDelaySteer::getX() { + return state_(IDX::X); +} +double SimModelTimeDelaySteer::getY() { + return state_(IDX::Y); +} +double SimModelTimeDelaySteer::getYaw() { + return state_(IDX::YAW); +} +double SimModelTimeDelaySteer::getVx() { + return state_(IDX::VX); +} +double SimModelTimeDelaySteer::getWz() { + return state_(IDX::VX) * std::tan(state_(IDX::STEER)) / wheelbase_; +} +double SimModelTimeDelaySteer::getSteer() { + return state_(IDX::STEER); +} +void SimModelTimeDelaySteer::update(const double &dt) { + Eigen::VectorXd delayed_input = Eigen::VectorXd::Zero(dim_u_); + + vx_input_queue_.push_back(input_(IDX_U::VX_DES)); + delayed_input(IDX_U::VX_DES) = vx_input_queue_.front(); + vx_input_queue_.pop_front(); + steer_input_queue_.push_back(input_(IDX_U::STEER_DES)); + const double raw_steer_command = steer_input_queue_.front(); + delayed_input(IDX_U::STEER_DES) = sim_model_util::getDummySteerCommandWithFriction( + getSteer(), raw_steer_command, deadzone_delta_steer_); + steer_input_queue_.pop_front(); + + updateRungeKutta(dt, delayed_input); +} +void SimModelTimeDelaySteer::initializeInputQueue(const double &dt) { + size_t vx_input_queue_size = static_cast(round(vx_delay_ / dt)); + for (size_t i = 0; i < vx_input_queue_size; i++) { + vx_input_queue_.push_back(0.0); + } + size_t steer_input_queue_size = static_cast(round(steer_delay_ / dt)); + for (size_t i = 0; i < steer_input_queue_size; i++) { + steer_input_queue_.push_back(0.0); + } +} + +Eigen::VectorXd SimModelTimeDelaySteer::calcModel( + const Eigen::VectorXd &state, const Eigen::VectorXd &input) { + const double vel = state(IDX::VX); + const double yaw = state(IDX::YAW); + const double steer = state(IDX::STEER); + const double delay_input_vel = input(IDX_U::VX_DES); + const double delay_input_steer = input(IDX_U::STEER_DES); + const double delay_vx_des = std::max(std::min(delay_input_vel, vx_lim_), -vx_lim_); + const double delay_steer_des = std::max(std::min(delay_input_steer, steer_lim_), -steer_lim_); + double vx_rate = -(vel - delay_vx_des) / vx_time_constant_; + double steer_rate = -(steer - delay_steer_des) / steer_time_constant_; + vx_rate = std::min(vx_rate_lim_, std::max(-vx_rate_lim_, vx_rate)); + steer_rate = std::min(steer_rate_lim_, std::max(-steer_rate_lim_, steer_rate)); + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + d_state(IDX::X) = vel * cos(yaw); + d_state(IDX::Y) = vel * sin(yaw); + d_state(IDX::YAW) = vel * std::tan(steer) / wheelbase_; + d_state(IDX::VX) = vx_rate; + d_state(IDX::STEER) = steer_rate; + + return d_state; +} + +SimModelTimeDelaySteerAccel::SimModelTimeDelaySteerAccel( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double acc_delay, double acc_time_constant, double steer_delay, + double steer_time_constant, double deadzone_delta_steer) + : SimModelInterface(6 /* dim x */, 3 /* dim u */), + MIN_TIME_CONSTANT(0.03), + vx_lim_(vx_lim), + vx_rate_lim_(vx_rate_lim), + steer_lim_(steer_lim), + steer_rate_lim_(steer_rate_lim), + wheelbase_(wheelbase), + acc_delay_(acc_delay), + acc_time_constant_(std::max(acc_time_constant, MIN_TIME_CONSTANT)), + steer_delay_(steer_delay), + steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), + deadzone_delta_steer_(deadzone_delta_steer) { + if (acc_time_constant < MIN_TIME_CONSTANT) { + std::cout << "Settings acc_time_constant is too small, replace it by" << MIN_TIME_CONSTANT << + std::endl; + } + if (steer_time_constant < MIN_TIME_CONSTANT) { + std::cout << "Settings steer_time_constant is too small, replace it by" << MIN_TIME_CONSTANT << + std::endl; + } + + initializeInputQueue(dt); +} + +double SimModelTimeDelaySteerAccel::getX() { + return state_(IDX::X); +} +double SimModelTimeDelaySteerAccel::getY() { + return state_(IDX::Y); +} +double SimModelTimeDelaySteerAccel::getYaw() { + return state_(IDX::YAW); +} +double SimModelTimeDelaySteerAccel::getVx() { + return state_(IDX::VX); +} +double SimModelTimeDelaySteerAccel::getWz() { + return state_(IDX::VX) * std::tan(state_(IDX::STEER)) / wheelbase_; +} +double SimModelTimeDelaySteerAccel::getSteer() { + return state_(IDX::STEER); +} +void SimModelTimeDelaySteerAccel::update(const double &dt) { + Eigen::VectorXd delayed_input = Eigen::VectorXd::Zero(dim_u_); + + acc_input_queue_.push_back(input_(IDX_U::ACCX_DES)); + delayed_input(IDX_U::ACCX_DES) = acc_input_queue_.front(); + acc_input_queue_.pop_front(); + steer_input_queue_.push_back(input_(IDX_U::STEER_DES)); + const double raw_steer_command = steer_input_queue_.front(); + delayed_input(IDX_U::STEER_DES) = sim_model_util::getDummySteerCommandWithFriction( + getSteer(), raw_steer_command, deadzone_delta_steer_); + steer_input_queue_.pop_front(); + delayed_input(IDX_U::DRIVE_SHIFT) = input_(IDX_U::DRIVE_SHIFT); + + updateRungeKutta(dt, delayed_input); + // clip velocity and accel + if (delayed_input(IDX_U::DRIVE_SHIFT) >= 0.0) { + state_(IDX::VX) = std::max(0.0, std::min(state_(IDX::VX), vx_lim_)); + if ( + std::abs((state_(IDX::VX) - 0.0)) < 10e-9 || std::abs((state_(IDX::VX) - vx_lim_)) < 10e-9) { + state_(IDX::ACCX) = 0.0; + } + } else { + state_(IDX::VX) = std::min(0.0, std::max(state_(IDX::VX), -vx_lim_)); + if ( + std::abs((state_(IDX::VX) - 0.0)) < 10e-9 || + std::abs((state_(IDX::VX) - (-vx_lim_))) < 10e-9) { + state_(IDX::ACCX) = 0.0; + } + } +} + +void SimModelTimeDelaySteerAccel::initializeInputQueue(const double &dt) { + size_t vx_input_queue_size = static_cast(round(acc_delay_ / dt)); + for (size_t i = 0; i < vx_input_queue_size; i++) { + acc_input_queue_.push_back(0.0); + } + size_t steer_input_queue_size = static_cast(round(steer_delay_ / dt)); + for (size_t i = 0; i < steer_input_queue_size; i++) { + steer_input_queue_.push_back(0.0); + } +} + +Eigen::VectorXd SimModelTimeDelaySteerAccel::calcModel( + const Eigen::VectorXd &state, const Eigen::VectorXd &input) { + double vel = state(IDX::VX); + double acc = state(IDX::ACCX); + const double yaw = state(IDX::YAW); + const double steer = state(IDX::STEER); + const double delay_input_acc = input(IDX_U::ACCX_DES); + const double delay_input_steer = input(IDX_U::STEER_DES); + const double drive_shift = input(IDX_U::DRIVE_SHIFT); + double delay_acc_des = std::max(std::min(delay_input_acc, vx_rate_lim_), -vx_rate_lim_); + if (!(drive_shift >= 0.0)) { + delay_acc_des *= -1; // reverse front-back + } + double delay_steer_des = std::max(std::min(delay_input_steer, steer_lim_), -steer_lim_); + double accx_rate = -(acc - delay_acc_des) / acc_time_constant_; + double steer_rate = -(steer - delay_steer_des) / steer_time_constant_; + acc = std::min(vx_rate_lim_, std::max(-vx_rate_lim_, acc)); + steer_rate = std::min(steer_rate_lim_, std::max(-steer_rate_lim_, steer_rate)); + + if (drive_shift >= 0.0) { + vel = std::max(0.0, std::min(vel, vx_lim_)); + } else { + vel = std::min(0.0, std::max(vel, -vx_lim_)); + } + + Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); + d_state(IDX::X) = vel * cos(yaw); + d_state(IDX::Y) = vel * sin(yaw); + d_state(IDX::YAW) = vel * std::tan(steer) / wheelbase_; + d_state(IDX::VX) = acc; + d_state(IDX::STEER) = steer_rate; + d_state(IDX::ACCX) = accx_rate; + + return d_state; +} diff --git a/apollo_simulator/src/vehicle_sim_model/sim_model_util.cpp b/apollo_simulator/src/vehicle_sim_model/sim_model_util.cpp new file mode 100644 index 0000000..e83ea42 --- /dev/null +++ b/apollo_simulator/src/vehicle_sim_model/sim_model_util.cpp @@ -0,0 +1,31 @@ +/****************************************************************************** + * Copyright 2022 The Zhou Zuhong Author. All Rights Reserved. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + *****************************************************************************/ + +#include "apollo_simulator/vehicle_sim_model/sim_model_util.h" + +namespace sim_model_util { + +double getDummySteerCommandWithFriction( + const double steer, const double steer_command, const double deadzone_delta_steer) { + const double delta_steer = std::fabs(steer_command - steer); + // if delta steer is too small, ignore steer command (send current steer as steer command) + if (delta_steer < deadzone_delta_steer) { + return steer; + } + return steer_command; +} + +} // namespace sim_model_util