From 53471359f8ddaf2501ec900d241454baaa5788cb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Sch=C3=BCtte?= Date: Mon, 13 Nov 2017 08:26:35 +0100 Subject: [PATCH] Convert all .proto files to proto3 syntax. (#653) [RFC=0000](https://github.com/googlecartographer/rfcs/blob/master/text/0000-proto3-transition.md) --- .../common/proto/ceres_solver_options.proto | 8 +-- .../ground_truth/proto/relations.proto | 8 +-- .../mapping/proto/connected_components.proto | 2 +- .../mapping/proto/map_builder_options.proto | 10 ++-- .../mapping/proto/serialization.proto | 22 ++++---- .../mapping/proto/sparse_pose_graph.proto | 22 ++++---- .../proto/sparse_pose_graph_options.proto | 20 +++---- cartographer/mapping/proto/submap.proto | 20 +++---- .../mapping/proto/submap_visualization.proto | 28 +++++----- cartographer/mapping/proto/trajectory.proto | 14 ++--- .../proto/trajectory_builder_options.proto | 16 +++--- .../mapping/proto/trajectory_node_data.proto | 14 ++--- cartographer/mapping/sparse_pose_graph.cc | 2 + .../proto/constraint_builder_options.proto | 24 ++++----- .../proto/optimization_problem_options.proto | 20 +++---- .../mapping_2d/proto/cell_limits.proto | 6 +-- .../local_trajectory_builder_options.proto | 34 ++++++------ .../mapping_2d/proto/map_limits.proto | 8 +-- .../mapping_2d/proto/probability_grid.proto | 14 ++--- .../proto/range_data_inserter_options.proto | 8 +-- .../mapping_2d/proto/submaps_options.proto | 8 +-- .../proto/ceres_scan_matcher_options.proto | 10 ++-- ...ast_correlative_scan_matcher_options.proto | 8 +-- ...ime_correlative_scan_matcher_options.proto | 10 ++-- .../mapping_3d/proto/hybrid_grid.proto | 4 +- .../local_trajectory_builder_options.proto | 28 +++++----- .../proto/motion_filter_options.proto | 8 +-- .../proto/range_data_inserter_options.proto | 8 +-- .../mapping_3d/proto/submaps_options.proto | 12 ++--- .../proto/ceres_scan_matcher_options.proto | 10 ++-- ...ast_correlative_scan_matcher_options.proto | 16 +++--- .../proto/adaptive_voxel_filter_options.proto | 8 +-- cartographer/sensor/proto/sensor.proto | 28 +++++----- cartographer/transform/proto/transform.proto | 54 +++++++++---------- 34 files changed, 257 insertions(+), 255 deletions(-) diff --git a/cartographer/common/proto/ceres_solver_options.proto b/cartographer/common/proto/ceres_solver_options.proto index c5f6bc5..60a00d1 100644 --- a/cartographer/common/proto/ceres_solver_options.proto +++ b/cartographer/common/proto/ceres_solver_options.proto @@ -12,14 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.common.proto; message CeresSolverOptions { // Configure the Ceres solver. See the Ceres documentation for more // information: https://code.google.com/p/ceres-solver/ - optional bool use_nonmonotonic_steps = 1; - optional int32 max_num_iterations = 2; - optional int32 num_threads = 3; + bool use_nonmonotonic_steps = 1; + int32 max_num_iterations = 2; + int32 num_threads = 3; } diff --git a/cartographer/ground_truth/proto/relations.proto b/cartographer/ground_truth/proto/relations.proto index 42c4e5a..e0a40b3 100644 --- a/cartographer/ground_truth/proto/relations.proto +++ b/cartographer/ground_truth/proto/relations.proto @@ -12,19 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.ground_truth.proto; import "cartographer/transform/proto/transform.proto"; message Relation { - optional int64 timestamp1 = 1; - optional int64 timestamp2 = 2; + int64 timestamp1 = 1; + int64 timestamp2 = 2; // The 'expected' relative transform of the tracking frame from 'timestamp2' // to 'timestamp1'. - optional transform.proto.Rigid3d expected = 3; + transform.proto.Rigid3d expected = 3; } message GroundTruth { diff --git a/cartographer/mapping/proto/connected_components.proto b/cartographer/mapping/proto/connected_components.proto index 2cdab4f..49e5006 100644 --- a/cartographer/mapping/proto/connected_components.proto +++ b/cartographer/mapping/proto/connected_components.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping.proto; diff --git a/cartographer/mapping/proto/map_builder_options.proto b/cartographer/mapping/proto/map_builder_options.proto index 18a6cac..e0d80fb 100644 --- a/cartographer/mapping/proto/map_builder_options.proto +++ b/cartographer/mapping/proto/map_builder_options.proto @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; import "cartographer/mapping/proto/sparse_pose_graph_options.proto"; package cartographer.mapping.proto; message MapBuilderOptions { - optional bool use_trajectory_builder_2d = 1; - optional bool use_trajectory_builder_3d = 2; + bool use_trajectory_builder_2d = 1; + bool use_trajectory_builder_3d = 2; // Number of threads to use for background computations. - optional int32 num_background_threads = 3; - optional SparsePoseGraphOptions sparse_pose_graph_options = 4; + int32 num_background_threads = 3; + SparsePoseGraphOptions sparse_pose_graph_options = 4; } diff --git a/cartographer/mapping/proto/serialization.proto b/cartographer/mapping/proto/serialization.proto index 78b56c3..73c0a10 100644 --- a/cartographer/mapping/proto/serialization.proto +++ b/cartographer/mapping/proto/serialization.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping.proto; @@ -22,24 +22,24 @@ import "cartographer/mapping/proto/trajectory_node_data.proto"; import "cartographer/sensor/proto/sensor.proto"; message Submap { - optional SubmapId submap_id = 1; - optional Submap2D submap_2d = 2; - optional Submap3D submap_3d = 3; + SubmapId submap_id = 1; + Submap2D submap_2d = 2; + Submap3D submap_3d = 3; } message Node { - optional NodeId node_id = 1; - optional TrajectoryNodeData node_data = 5; + NodeId node_id = 1; + TrajectoryNodeData node_data = 5; } message ImuData { - optional int32 trajectory_id = 1; - optional sensor.proto.ImuData imu_data = 2; + int32 trajectory_id = 1; + sensor.proto.ImuData imu_data = 2; } message SerializedData { - optional Submap submap = 1; - optional Node node = 2; - optional ImuData imu_data = 3; + Submap submap = 1; + Node node = 2; + ImuData imu_data = 3; // TODO(whess): Add odometry. } diff --git a/cartographer/mapping/proto/sparse_pose_graph.proto b/cartographer/mapping/proto/sparse_pose_graph.proto index 588ba83..c98e958 100644 --- a/cartographer/mapping/proto/sparse_pose_graph.proto +++ b/cartographer/mapping/proto/sparse_pose_graph.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping.proto; @@ -20,13 +20,13 @@ import "cartographer/mapping/proto/trajectory.proto"; import "cartographer/transform/proto/transform.proto"; message SubmapId { - optional int32 trajectory_id = 1; - optional int32 submap_index = 2; // Submap index in the given trajectory. + int32 trajectory_id = 1; + int32 submap_index = 2; // Submap index in the given trajectory. } message NodeId { - optional int32 trajectory_id = 1; - optional int32 node_index = 2; // Node index in the given trajectory. + int32 trajectory_id = 1; + int32 node_index = 2; // Node index in the given trajectory. } message SparsePoseGraph { @@ -39,16 +39,16 @@ message SparsePoseGraph { INTER_SUBMAP = 1; } - optional SubmapId submap_id = 1; // Submap ID. - optional NodeId node_id = 2; // Node ID. + SubmapId submap_id = 1; // Submap ID. + NodeId node_id = 2; // Node ID. // Pose of the node relative to submap, i.e. taking data from the node frame // into the submap frame. - optional transform.proto.Rigid3d relative_pose = 3; + transform.proto.Rigid3d relative_pose = 3; // Weight of the translational part of the constraint. - optional double translation_weight = 6; + double translation_weight = 6; // Weight of the rotational part of the constraint. - optional double rotation_weight = 7; - optional Tag tag = 5; + double rotation_weight = 7; + Tag tag = 5; } repeated Constraint constraint = 2; diff --git a/cartographer/mapping/proto/sparse_pose_graph_options.proto b/cartographer/mapping/proto/sparse_pose_graph_options.proto index 36a7df9..b614efd 100644 --- a/cartographer/mapping/proto/sparse_pose_graph_options.proto +++ b/cartographer/mapping/proto/sparse_pose_graph_options.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping.proto; @@ -22,37 +22,37 @@ import "cartographer/mapping/sparse_pose_graph/proto/optimization_problem_option message SparsePoseGraphOptions { // Online loop closure: If positive, will run the loop closure while the map // is built. - optional int32 optimize_every_n_scans = 1; + int32 optimize_every_n_scans = 1; // Options for the constraint builder. - optional mapping.sparse_pose_graph.proto.ConstraintBuilderOptions + mapping.sparse_pose_graph.proto.ConstraintBuilderOptions constraint_builder_options = 3; // Weight used in the optimization problem for the translational component of // non-loop-closure scan matcher constraints. - optional double matcher_translation_weight = 7; + double matcher_translation_weight = 7; // Weight used in the optimization problem for the rotational component of // non-loop-closure scan matcher constraints. - optional double matcher_rotation_weight = 8; + double matcher_rotation_weight = 8; // Options for the optimization problem. - optional mapping.sparse_pose_graph.proto.OptimizationProblemOptions + mapping.sparse_pose_graph.proto.OptimizationProblemOptions optimization_problem_options = 4; // Number of iterations to use in 'optimization_problem_options' for the final // optimization. - optional int32 max_num_final_iterations = 6; + int32 max_num_final_iterations = 6; // Rate at which we sample a single trajectory's scans for global // localization. - optional double global_sampling_ratio = 5; + double global_sampling_ratio = 5; // Whether to output histograms for the pose residuals. - optional bool log_residual_histograms = 9; + bool log_residual_histograms = 9; // If for the duration specified by this option no global contraint has been // added between two trajectories, loop closure searches will be performed // globally rather than in a smaller search window. - optional double global_constraint_search_after_n_seconds = 10; + double global_constraint_search_after_n_seconds = 10; } diff --git a/cartographer/mapping/proto/submap.proto b/cartographer/mapping/proto/submap.proto index 184a04e..57925d2 100644 --- a/cartographer/mapping/proto/submap.proto +++ b/cartographer/mapping/proto/submap.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping.proto; @@ -22,17 +22,17 @@ import "cartographer/transform/proto/transform.proto"; // Serialized state of a mapping_2d::Submap. message Submap2D { - optional transform.proto.Rigid3d local_pose = 1; - optional int32 num_range_data = 2; - optional bool finished = 3; - optional mapping_2d.proto.ProbabilityGrid probability_grid = 4; + transform.proto.Rigid3d local_pose = 1; + int32 num_range_data = 2; + bool finished = 3; + mapping_2d.proto.ProbabilityGrid probability_grid = 4; } // Serialized state of a mapping_3d::Submap. message Submap3D { - optional transform.proto.Rigid3d local_pose = 1; - optional int32 num_range_data = 2; - optional bool finished = 3; - optional mapping_3d.proto.HybridGrid high_resolution_hybrid_grid = 4; - optional mapping_3d.proto.HybridGrid low_resolution_hybrid_grid = 5; + transform.proto.Rigid3d local_pose = 1; + int32 num_range_data = 2; + bool finished = 3; + mapping_3d.proto.HybridGrid high_resolution_hybrid_grid = 4; + mapping_3d.proto.HybridGrid low_resolution_hybrid_grid = 5; } diff --git a/cartographer/mapping/proto/submap_visualization.proto b/cartographer/mapping/proto/submap_visualization.proto index e8c0cdc..4cd9498 100644 --- a/cartographer/mapping/proto/submap_visualization.proto +++ b/cartographer/mapping/proto/submap_visualization.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; import "cartographer/transform/proto/transform.proto"; @@ -20,8 +20,8 @@ package cartographer.mapping.proto; message SubmapList { message SubmapEntry { - optional int32 submap_version = 1; - optional transform.proto.Rigid3d pose = 3; + int32 submap_version = 1; + transform.proto.Rigid3d pose = 3; } message TrajectorySubmapList { @@ -34,40 +34,40 @@ message SubmapList { message SubmapQuery { message Request { // Index into 'SubmapList.trajectory(trajectory_id).submap'. - optional int32 submap_index = 1; + int32 submap_index = 1; // Index into 'TrajectoryList.trajectory'. - optional int32 trajectory_id = 2; + int32 trajectory_id = 2; } message Response { // Version of the given submap, higher means newer. - optional int32 submap_version = 2; + int32 submap_version = 2; // Texture that visualizes a grid of a submap. message SubmapTexture { // GZipped map data, in row-major order, starting with (0,0). Each cell // consists of two bytes: value (premultiplied by alpha) and alpha. - optional bytes cells = 1; + bytes cells = 1; // Dimensions of the grid in cells. - optional int32 width = 2; - optional int32 height = 3; + int32 width = 2; + int32 height = 3; // Size of one cell in meters. - optional double resolution = 4; + double resolution = 4; // Pose of the resolution*width x resolution*height rectangle in the // submap frame. - optional transform.proto.Rigid3d slice_pose = 5; + transform.proto.Rigid3d slice_pose = 5; } // When multiple textures are present, high resolution comes first. repeated SubmapTexture textures = 10; // Error message in response to malformed requests. - optional string error_message = 8; + string error_message = 8; } - optional Request request = 1; - optional Response response = 2; + Request request = 1; + Response response = 2; } diff --git a/cartographer/mapping/proto/trajectory.proto b/cartographer/mapping/proto/trajectory.proto index 2f72a47..8cd7d57 100644 --- a/cartographer/mapping/proto/trajectory.proto +++ b/cartographer/mapping/proto/trajectory.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping.proto; @@ -24,24 +24,24 @@ message Trajectory { // NEXT_ID: 8 message Node { // Index of this node within its trajectory. - optional int32 node_index = 7; + int32 node_index = 7; - optional int64 timestamp = 1; + int64 timestamp = 1; // Transform from tracking to global map frame. - optional transform.proto.Rigid3d pose = 5; + transform.proto.Rigid3d pose = 5; } message Submap { // Index of this submap within its trajectory. - optional int32 submap_index = 2; + int32 submap_index = 2; // Transform from submap to global map frame. - optional transform.proto.Rigid3d pose = 1; + transform.proto.Rigid3d pose = 1; } // ID of this trajectory. - optional int32 trajectory_id = 3; + int32 trajectory_id = 3; // Time-ordered sequence of Nodes. repeated Node node = 1; diff --git a/cartographer/mapping/proto/trajectory_builder_options.proto b/cartographer/mapping/proto/trajectory_builder_options.proto index 352b3df..18b72ae 100644 --- a/cartographer/mapping/proto/trajectory_builder_options.proto +++ b/cartographer/mapping/proto/trajectory_builder_options.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; import "cartographer/transform/proto/transform.proto"; import "cartographer/mapping_2d/proto/local_trajectory_builder_options.proto"; @@ -21,16 +21,16 @@ import "cartographer/mapping_3d/proto/local_trajectory_builder_options.proto"; package cartographer.mapping.proto; message InitialTrajectoryPose { - optional transform.proto.Rigid3d relative_pose = 1; - optional int32 to_trajectory_id = 2; - optional int64 timestamp = 3; + transform.proto.Rigid3d relative_pose = 1; + int32 to_trajectory_id = 2; + int64 timestamp = 3; } message TrajectoryBuilderOptions { - optional mapping_2d.proto.LocalTrajectoryBuilderOptions + mapping_2d.proto.LocalTrajectoryBuilderOptions trajectory_builder_2d_options = 1; - optional mapping_3d.proto.LocalTrajectoryBuilderOptions + mapping_3d.proto.LocalTrajectoryBuilderOptions trajectory_builder_3d_options = 2; - optional bool pure_localization = 3; - optional InitialTrajectoryPose initial_trajectory_pose = 4; + bool pure_localization = 3; + InitialTrajectoryPose initial_trajectory_pose = 4; } diff --git a/cartographer/mapping/proto/trajectory_node_data.proto b/cartographer/mapping/proto/trajectory_node_data.proto index e5dcffd..d8cb0b1 100644 --- a/cartographer/mapping/proto/trajectory_node_data.proto +++ b/cartographer/mapping/proto/trajectory_node_data.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping.proto; @@ -21,12 +21,12 @@ import "cartographer/transform/proto/transform.proto"; // Serialized state of a mapping::TrajectoryNode::Data. message TrajectoryNodeData { - optional int64 timestamp = 1; - optional transform.proto.Quaterniond gravity_alignment = 2; - optional sensor.proto.CompressedPointCloud + int64 timestamp = 1; + transform.proto.Quaterniond gravity_alignment = 2; + sensor.proto.CompressedPointCloud filtered_gravity_aligned_point_cloud = 3; - optional sensor.proto.CompressedPointCloud high_resolution_point_cloud = 4; - optional sensor.proto.CompressedPointCloud low_resolution_point_cloud = 5; + sensor.proto.CompressedPointCloud high_resolution_point_cloud = 4; + sensor.proto.CompressedPointCloud low_resolution_point_cloud = 5; repeated float rotational_scan_matcher_histogram = 6; - optional transform.proto.Rigid3d local_pose = 7; + transform.proto.Rigid3d local_pose = 7; } diff --git a/cartographer/mapping/sparse_pose_graph.cc b/cartographer/mapping/sparse_pose_graph.cc index f933fdc..821b1e8 100644 --- a/cartographer/mapping/sparse_pose_graph.cc +++ b/cartographer/mapping/sparse_pose_graph.cc @@ -42,6 +42,8 @@ SparsePoseGraph::Constraint::Tag FromProto( return SparsePoseGraph::Constraint::Tag::INTRA_SUBMAP; case proto::SparsePoseGraph::Constraint::INTER_SUBMAP: return SparsePoseGraph::Constraint::Tag::INTER_SUBMAP; + case ::google::protobuf::kint32max: + case ::google::protobuf::kint32min:; } LOG(FATAL) << "Unsupported tag."; } diff --git a/cartographer/mapping/sparse_pose_graph/proto/constraint_builder_options.proto b/cartographer/mapping/sparse_pose_graph/proto/constraint_builder_options.proto index f09ff50..38d37c9 100644 --- a/cartographer/mapping/sparse_pose_graph/proto/constraint_builder_options.proto +++ b/cartographer/mapping/sparse_pose_graph/proto/constraint_builder_options.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping.sparse_pose_graph.proto; @@ -24,37 +24,37 @@ import "cartographer/mapping_3d/scan_matching/proto/fast_correlative_scan_matche message ConstraintBuilderOptions { // A constraint will be added if the proportion of added constraints to // potential constraints drops below this number. - optional double sampling_ratio = 1; + double sampling_ratio = 1; // Threshold for poses to be considered near a submap. - optional double max_constraint_distance = 2; + double max_constraint_distance = 2; // Threshold for the scan match score below which a match is not considered. // Low scores indicate that the scan and map do not look similar. - optional double min_score = 4; + double min_score = 4; // Threshold below which global localizations are not trusted. - optional double global_localization_min_score = 5; + double global_localization_min_score = 5; // Weight used in the optimization problem for the translational component of // loop closure constraints. - optional double loop_closure_translation_weight = 13; + double loop_closure_translation_weight = 13; // Weight used in the optimization problem for the rotational component of // loop closure constraints. - optional double loop_closure_rotation_weight = 14; + double loop_closure_rotation_weight = 14; // If enabled, logs information of loop-closing constraints for debugging. - optional bool log_matches = 8; + bool log_matches = 8; // Options for the internally used scan matchers. - optional mapping_2d.scan_matching.proto.FastCorrelativeScanMatcherOptions + mapping_2d.scan_matching.proto.FastCorrelativeScanMatcherOptions fast_correlative_scan_matcher_options = 9; - optional mapping_2d.scan_matching.proto.CeresScanMatcherOptions + mapping_2d.scan_matching.proto.CeresScanMatcherOptions ceres_scan_matcher_options = 11; - optional mapping_3d.scan_matching.proto.FastCorrelativeScanMatcherOptions + mapping_3d.scan_matching.proto.FastCorrelativeScanMatcherOptions fast_correlative_scan_matcher_options_3d = 10; - optional mapping_3d.scan_matching.proto.CeresScanMatcherOptions + mapping_3d.scan_matching.proto.CeresScanMatcherOptions ceres_scan_matcher_options_3d = 12; } diff --git a/cartographer/mapping/sparse_pose_graph/proto/optimization_problem_options.proto b/cartographer/mapping/sparse_pose_graph/proto/optimization_problem_options.proto index 578ebef..fc98db2 100644 --- a/cartographer/mapping/sparse_pose_graph/proto/optimization_problem_options.proto +++ b/cartographer/mapping/sparse_pose_graph/proto/optimization_problem_options.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping.sparse_pose_graph.proto; @@ -21,28 +21,28 @@ import "cartographer/common/proto/ceres_solver_options.proto"; // NEXT ID: 13 message OptimizationProblemOptions { // Scaling parameter for Huber loss function. - optional double huber_scale = 1; + double huber_scale = 1; // Scaling parameter for the IMU acceleration term. - optional double acceleration_weight = 8; + double acceleration_weight = 8; // Scaling parameter for the IMU rotation term. - optional double rotation_weight = 9; + double rotation_weight = 9; // Penalty factors for translation changes to the relative pose between consecutive scans. - optional double consecutive_scan_translation_penalty_factor = 2; + double consecutive_scan_translation_penalty_factor = 2; // Penalty factors for rotation changes to the relative pose between consecutive scans. - optional double consecutive_scan_rotation_penalty_factor = 3; + double consecutive_scan_rotation_penalty_factor = 3; // Scaling parameter for the FixedFramePose translation. - optional double fixed_frame_pose_translation_weight = 11; + double fixed_frame_pose_translation_weight = 11; // Scaling parameter for the FixedFramePose rotation. - optional double fixed_frame_pose_rotation_weight = 12; + double fixed_frame_pose_rotation_weight = 12; // If true, the Ceres solver summary will be logged for every optimization. - optional bool log_solver_summary = 5; + bool log_solver_summary = 5; - optional common.proto.CeresSolverOptions ceres_solver_options = 7; + common.proto.CeresSolverOptions ceres_solver_options = 7; } diff --git a/cartographer/mapping_2d/proto/cell_limits.proto b/cartographer/mapping_2d/proto/cell_limits.proto index b655d23..72416bf 100644 --- a/cartographer/mapping_2d/proto/cell_limits.proto +++ b/cartographer/mapping_2d/proto/cell_limits.proto @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping_2d.proto; message CellLimits { - optional int32 num_x_cells = 1; - optional int32 num_y_cells = 2; + int32 num_x_cells = 1; + int32 num_y_cells = 2; } diff --git a/cartographer/mapping_2d/proto/local_trajectory_builder_options.proto b/cartographer/mapping_2d/proto/local_trajectory_builder_options.proto index eda7e9f..e5c35df 100644 --- a/cartographer/mapping_2d/proto/local_trajectory_builder_options.proto +++ b/cartographer/mapping_2d/proto/local_trajectory_builder_options.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping_2d.proto; @@ -24,39 +24,39 @@ import "cartographer/mapping_2d/scan_matching/proto/real_time_correlative_scan_m message LocalTrajectoryBuilderOptions { // Rangefinder points outside these ranges will be dropped. - optional float min_range = 14; - optional float max_range = 15; - optional float min_z = 1; - optional float max_z = 2; + float min_range = 14; + float max_range = 15; + float min_z = 1; + float max_z = 2; // Points beyond 'max_range' will be inserted with this length as empty space. - optional float missing_data_ray_length = 16; + float missing_data_ray_length = 16; // Number of scans to accumulate into one unwarped, combined scan to use for // scan matching. - optional int32 scans_per_accumulation = 19; + int32 scans_per_accumulation = 19; // Voxel filter that gets applied to the range data immediately after // cropping. - optional float voxel_filter_size = 3; + float voxel_filter_size = 3; // Voxel filter used to compute a sparser point cloud for matching. - optional sensor.proto.AdaptiveVoxelFilterOptions + sensor.proto.AdaptiveVoxelFilterOptions adaptive_voxel_filter_options = 6; // Voxel filter used to compute a sparser point cloud for finding loop // closures. - optional sensor.proto.AdaptiveVoxelFilterOptions + sensor.proto.AdaptiveVoxelFilterOptions loop_closure_adaptive_voxel_filter_options = 20; // Whether to solve the online scan matching first using the correlative scan // matcher to generate a good starting point for Ceres. - optional bool use_online_correlative_scan_matching = 5; - optional scan_matching.proto.RealTimeCorrelativeScanMatcherOptions + bool use_online_correlative_scan_matching = 5; + scan_matching.proto.RealTimeCorrelativeScanMatcherOptions real_time_correlative_scan_matcher_options = 7; - optional scan_matching.proto.CeresScanMatcherOptions + scan_matching.proto.CeresScanMatcherOptions ceres_scan_matcher_options = 8; - optional mapping_3d.proto.MotionFilterOptions motion_filter_options = 13; + mapping_3d.proto.MotionFilterOptions motion_filter_options = 13; // Time constant in seconds for the orientation moving average based on // observed gravity via the IMU. It should be chosen so that the error @@ -64,10 +64,10 @@ message LocalTrajectoryBuilderOptions { // the constant is reduced) and // 2. from integration of angular velocities (which gets worse when the // constant is increased) is balanced. - optional double imu_gravity_time_constant = 17; + double imu_gravity_time_constant = 17; - optional mapping_2d.proto.SubmapsOptions submaps_options = 11; + mapping_2d.proto.SubmapsOptions submaps_options = 11; // True if IMU data should be expected and used. - optional bool use_imu_data = 12; + bool use_imu_data = 12; } diff --git a/cartographer/mapping_2d/proto/map_limits.proto b/cartographer/mapping_2d/proto/map_limits.proto index 3b868c7..e011a65 100644 --- a/cartographer/mapping_2d/proto/map_limits.proto +++ b/cartographer/mapping_2d/proto/map_limits.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; import "cartographer/mapping_2d/proto/cell_limits.proto"; import "cartographer/transform/proto/transform.proto"; @@ -20,7 +20,7 @@ import "cartographer/transform/proto/transform.proto"; package cartographer.mapping_2d.proto; message MapLimits { - optional double resolution = 1; - optional cartographer.transform.proto.Vector2d max = 2; - optional CellLimits cell_limits = 3; + double resolution = 1; + cartographer.transform.proto.Vector2d max = 2; + CellLimits cell_limits = 3; } diff --git a/cartographer/mapping_2d/proto/probability_grid.proto b/cartographer/mapping_2d/proto/probability_grid.proto index b856784..c8f774e 100644 --- a/cartographer/mapping_2d/proto/probability_grid.proto +++ b/cartographer/mapping_2d/proto/probability_grid.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; import "cartographer/mapping_2d/proto/map_limits.proto"; @@ -20,15 +20,15 @@ package cartographer.mapping_2d.proto; message ProbabilityGrid { message CellBox { - optional int32 max_x = 1; - optional int32 max_y = 2; - optional int32 min_x = 3; - optional int32 min_y = 4; + int32 max_x = 1; + int32 max_y = 2; + int32 min_x = 3; + int32 min_y = 4; } - optional MapLimits limits = 1; + MapLimits limits = 1; // These values are actually int16s, but protos don't have a native int16 // type. repeated int32 cells = 2; - optional CellBox known_cells_box = 8; + CellBox known_cells_box = 8; } diff --git a/cartographer/mapping_2d/proto/range_data_inserter_options.proto b/cartographer/mapping_2d/proto/range_data_inserter_options.proto index 15b435c..db84c6e 100644 --- a/cartographer/mapping_2d/proto/range_data_inserter_options.proto +++ b/cartographer/mapping_2d/proto/range_data_inserter_options.proto @@ -12,20 +12,20 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping_2d.proto; message RangeDataInserterOptions { // Probability change for a hit (this will be converted to odds and therefore // must be greater than 0.5). - optional double hit_probability = 1; + double hit_probability = 1; // Probability change for a miss (this will be converted to odds and therefore // must be less than 0.5). - optional double miss_probability = 2; + double miss_probability = 2; // If 'false', free space will not change the probabilities in the occupancy // grid. - optional bool insert_free_space = 3; + bool insert_free_space = 3; } diff --git a/cartographer/mapping_2d/proto/submaps_options.proto b/cartographer/mapping_2d/proto/submaps_options.proto index 9e24649..e18e426 100644 --- a/cartographer/mapping_2d/proto/submaps_options.proto +++ b/cartographer/mapping_2d/proto/submaps_options.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; import "cartographer/mapping_2d/proto/range_data_inserter_options.proto"; @@ -20,12 +20,12 @@ package cartographer.mapping_2d.proto; message SubmapsOptions { // Resolution of the map in meters. - optional double resolution = 1; + double resolution = 1; // Number of scans before adding a new submap. Each submap will get twice the // number of scans inserted: First for initialization without being matched // against, then while being matched. - optional int32 num_range_data = 3; + int32 num_range_data = 3; - optional RangeDataInserterOptions range_data_inserter_options = 5; + RangeDataInserterOptions range_data_inserter_options = 5; } diff --git a/cartographer/mapping_2d/scan_matching/proto/ceres_scan_matcher_options.proto b/cartographer/mapping_2d/scan_matching/proto/ceres_scan_matcher_options.proto index b1fec7c..20f0a75 100644 --- a/cartographer/mapping_2d/scan_matching/proto/ceres_scan_matcher_options.proto +++ b/cartographer/mapping_2d/scan_matching/proto/ceres_scan_matcher_options.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping_2d.scan_matching.proto; @@ -21,11 +21,11 @@ import "cartographer/common/proto/ceres_solver_options.proto"; // NEXT ID: 10 message CeresScanMatcherOptions { // Scaling parameters for each cost functor. - optional double occupied_space_weight = 1; - optional double translation_weight = 2; - optional double rotation_weight = 3; + double occupied_space_weight = 1; + double translation_weight = 2; + double rotation_weight = 3; // Configure the Ceres solver. See the Ceres documentation for more // information: https://code.google.com/p/ceres-solver/ - optional common.proto.CeresSolverOptions ceres_solver_options = 9; + common.proto.CeresSolverOptions ceres_solver_options = 9; } diff --git a/cartographer/mapping_2d/scan_matching/proto/fast_correlative_scan_matcher_options.proto b/cartographer/mapping_2d/scan_matching/proto/fast_correlative_scan_matcher_options.proto index 5d57170..41cef1b 100644 --- a/cartographer/mapping_2d/scan_matching/proto/fast_correlative_scan_matcher_options.proto +++ b/cartographer/mapping_2d/scan_matching/proto/fast_correlative_scan_matcher_options.proto @@ -12,19 +12,19 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping_2d.scan_matching.proto; message FastCorrelativeScanMatcherOptions { // Minimum linear search window in which the best possible scan alignment // will be found. - optional double linear_search_window = 3; + double linear_search_window = 3; // Minimum angular search window in which the best possible scan alignment // will be found. - optional double angular_search_window = 4; + double angular_search_window = 4; // Number of precomputed grids to use. - optional int32 branch_and_bound_depth = 2; + int32 branch_and_bound_depth = 2; } diff --git a/cartographer/mapping_2d/scan_matching/proto/real_time_correlative_scan_matcher_options.proto b/cartographer/mapping_2d/scan_matching/proto/real_time_correlative_scan_matcher_options.proto index 29c4d15..0bd6c4e 100644 --- a/cartographer/mapping_2d/scan_matching/proto/real_time_correlative_scan_matcher_options.proto +++ b/cartographer/mapping_2d/scan_matching/proto/real_time_correlative_scan_matcher_options.proto @@ -12,20 +12,20 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping_2d.scan_matching.proto; message RealTimeCorrelativeScanMatcherOptions { // Minimum linear search window in which the best possible scan alignment // will be found. - optional double linear_search_window = 1; + double linear_search_window = 1; // Minimum angular search window in which the best possible scan alignment // will be found. - optional double angular_search_window = 2; + double angular_search_window = 2; // Weights applied to each part of the score. - optional double translation_delta_cost_weight = 3; - optional double rotation_delta_cost_weight = 4; + double translation_delta_cost_weight = 3; + double rotation_delta_cost_weight = 4; } diff --git a/cartographer/mapping_3d/proto/hybrid_grid.proto b/cartographer/mapping_3d/proto/hybrid_grid.proto index b6fc592..8caf1e8 100644 --- a/cartographer/mapping_3d/proto/hybrid_grid.proto +++ b/cartographer/mapping_3d/proto/hybrid_grid.proto @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping_3d.proto; message HybridGrid { - optional float resolution = 1; + float resolution = 1; // '{x, y, z}_indices[i]' is the index of 'values[i]'. repeated sint32 x_indices = 3 [packed = true]; repeated sint32 y_indices = 4 [packed = true]; diff --git a/cartographer/mapping_3d/proto/local_trajectory_builder_options.proto b/cartographer/mapping_3d/proto/local_trajectory_builder_options.proto index 968c555..74077b0 100644 --- a/cartographer/mapping_3d/proto/local_trajectory_builder_options.proto +++ b/cartographer/mapping_3d/proto/local_trajectory_builder_options.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping_3d.proto; @@ -25,31 +25,31 @@ import "cartographer/mapping_3d/scan_matching/proto/ceres_scan_matcher_options.p // NEXT ID: 18 message LocalTrajectoryBuilderOptions { // Rangefinder points outside these ranges will be dropped. - optional float min_range = 1; - optional float max_range = 2; + float min_range = 1; + float max_range = 2; // Number of scans to accumulate into one unwarped, combined scan to use for // scan matching. - optional int32 scans_per_accumulation = 3; + int32 scans_per_accumulation = 3; // Voxel filter that gets applied to the range data immediately after // cropping. - optional float voxel_filter_size = 4; + float voxel_filter_size = 4; // Voxel filter used to compute a sparser point cloud for matching. - optional sensor.proto.AdaptiveVoxelFilterOptions + sensor.proto.AdaptiveVoxelFilterOptions high_resolution_adaptive_voxel_filter_options = 5; - optional sensor.proto.AdaptiveVoxelFilterOptions + sensor.proto.AdaptiveVoxelFilterOptions low_resolution_adaptive_voxel_filter_options = 12; // Whether to solve the online scan matching first using the correlative scan // matcher to generate a good starting point for Ceres. - optional bool use_online_correlative_scan_matching = 13; - optional mapping_2d.scan_matching.proto.RealTimeCorrelativeScanMatcherOptions + bool use_online_correlative_scan_matching = 13; + mapping_2d.scan_matching.proto.RealTimeCorrelativeScanMatcherOptions real_time_correlative_scan_matcher_options = 14; - optional scan_matching.proto.CeresScanMatcherOptions + scan_matching.proto.CeresScanMatcherOptions ceres_scan_matcher_options = 6; - optional MotionFilterOptions motion_filter_options = 7; + MotionFilterOptions motion_filter_options = 7; // Time constant in seconds for the orientation moving average based on // observed gravity via the IMU. It should be chosen so that the error @@ -57,10 +57,10 @@ message LocalTrajectoryBuilderOptions { // the constant is reduced) and // 2. from integration of angular velocities (which gets worse when the // constant is increased) is balanced. - optional double imu_gravity_time_constant = 15; + double imu_gravity_time_constant = 15; // Number of histogram buckets for the rotational scan matcher. - optional int32 rotational_histogram_size = 17; + int32 rotational_histogram_size = 17; - optional SubmapsOptions submaps_options = 8; + SubmapsOptions submaps_options = 8; } diff --git a/cartographer/mapping_3d/proto/motion_filter_options.proto b/cartographer/mapping_3d/proto/motion_filter_options.proto index 539c19e..ff83cf7 100644 --- a/cartographer/mapping_3d/proto/motion_filter_options.proto +++ b/cartographer/mapping_3d/proto/motion_filter_options.proto @@ -12,17 +12,17 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping_3d.proto; message MotionFilterOptions { // Threshold above which a new scan is inserted based on time. - optional double max_time_seconds = 1; + double max_time_seconds = 1; // Threshold above which a new scan is inserted based on linear motion. - optional double max_distance_meters = 2; + double max_distance_meters = 2; // Threshold above which a new scan is inserted based on rotational motion. - optional double max_angle_radians = 3; + double max_angle_radians = 3; } diff --git a/cartographer/mapping_3d/proto/range_data_inserter_options.proto b/cartographer/mapping_3d/proto/range_data_inserter_options.proto index 0ea20c5..b421c57 100644 --- a/cartographer/mapping_3d/proto/range_data_inserter_options.proto +++ b/cartographer/mapping_3d/proto/range_data_inserter_options.proto @@ -12,20 +12,20 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping_3d.proto; message RangeDataInserterOptions { // Probability change for a hit (this will be converted to odds and therefore // must be greater than 0.5). - optional double hit_probability = 1; + double hit_probability = 1; // Probability change for a miss (this will be converted to odds and therefore // must be less than 0.5). - optional double miss_probability = 2; + double miss_probability = 2; // Up to how many free space voxels are updated for scan matching. // 0 disables free space. - optional int32 num_free_space_voxels = 3; + int32 num_free_space_voxels = 3; } diff --git a/cartographer/mapping_3d/proto/submaps_options.proto b/cartographer/mapping_3d/proto/submaps_options.proto index abc6696..293c7c8 100644 --- a/cartographer/mapping_3d/proto/submaps_options.proto +++ b/cartographer/mapping_3d/proto/submaps_options.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; import "cartographer/mapping_3d/proto/range_data_inserter_options.proto"; @@ -21,20 +21,20 @@ package cartographer.mapping_3d.proto; message SubmapsOptions { // Resolution of the 'high_resolution' map in meters used for local SLAM and // loop closure. - optional double high_resolution = 1; + double high_resolution = 1; // Maximum range to filter the point cloud to before insertion into the // 'high_resolution' map. - optional double high_resolution_max_range = 4; + double high_resolution_max_range = 4; // Resolution of the 'low_resolution' version of the map in meters used for // local SLAM only. - optional double low_resolution = 5; + double low_resolution = 5; // Number of scans before adding a new submap. Each submap will get twice the // number of scans inserted: First for initialization without being matched // against, then while being matched. - optional int32 num_range_data = 2; + int32 num_range_data = 2; - optional RangeDataInserterOptions range_data_inserter_options = 3; + RangeDataInserterOptions range_data_inserter_options = 3; } diff --git a/cartographer/mapping_3d/scan_matching/proto/ceres_scan_matcher_options.proto b/cartographer/mapping_3d/scan_matching/proto/ceres_scan_matcher_options.proto index a17ca86..fc590cc 100644 --- a/cartographer/mapping_3d/scan_matching/proto/ceres_scan_matcher_options.proto +++ b/cartographer/mapping_3d/scan_matching/proto/ceres_scan_matcher_options.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping_3d.scan_matching.proto; @@ -22,13 +22,13 @@ import "cartographer/common/proto/ceres_solver_options.proto"; message CeresScanMatcherOptions { // Scaling parameters for each cost functor. repeated double occupied_space_weight = 1; - optional double translation_weight = 2; - optional double rotation_weight = 3; + double translation_weight = 2; + double rotation_weight = 3; // Whether only to allow changes to yaw, keeping roll/pitch constant. - optional bool only_optimize_yaw = 5; + bool only_optimize_yaw = 5; // Configure the Ceres solver. See the Ceres documentation for more // information: https://code.google.com/p/ceres-solver/ - optional common.proto.CeresSolverOptions ceres_solver_options = 6; + common.proto.CeresSolverOptions ceres_solver_options = 6; } diff --git a/cartographer/mapping_3d/scan_matching/proto/fast_correlative_scan_matcher_options.proto b/cartographer/mapping_3d/scan_matching/proto/fast_correlative_scan_matcher_options.proto index 3615d88..4baa066 100644 --- a/cartographer/mapping_3d/scan_matching/proto/fast_correlative_scan_matcher_options.proto +++ b/cartographer/mapping_3d/scan_matching/proto/fast_correlative_scan_matcher_options.proto @@ -12,34 +12,34 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.mapping_3d.scan_matching.proto; message FastCorrelativeScanMatcherOptions { // Number of precomputed grids to use. - optional int32 branch_and_bound_depth = 2; + int32 branch_and_bound_depth = 2; // Number of full resolution grids to use, additional grids will reduce the // resolution by half each. - optional int32 full_resolution_depth = 8; + int32 full_resolution_depth = 8; // Minimum score for the rotational scan matcher. - optional double min_rotational_score = 4; + double min_rotational_score = 4; // Threshold for the score of the low resolution grid below which a match is // not considered. Only used for 3D. - optional double min_low_resolution_score = 9; + double min_low_resolution_score = 9; // Linear search window in the plane orthogonal to gravity in which the best // possible scan alignment will be found. - optional double linear_xy_search_window = 5; + double linear_xy_search_window = 5; // Linear search window in the gravity direction in which the best possible // scan alignment will be found. - optional double linear_z_search_window = 6; + double linear_z_search_window = 6; // Minimum angular search window in which the best possible scan alignment // will be found. - optional double angular_search_window = 7; + double angular_search_window = 7; } diff --git a/cartographer/sensor/proto/adaptive_voxel_filter_options.proto b/cartographer/sensor/proto/adaptive_voxel_filter_options.proto index 935f8c5..57c4770 100644 --- a/cartographer/sensor/proto/adaptive_voxel_filter_options.proto +++ b/cartographer/sensor/proto/adaptive_voxel_filter_options.proto @@ -12,18 +12,18 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.sensor.proto; message AdaptiveVoxelFilterOptions { // 'max_length' of a voxel edge. - optional float max_length = 1; + float max_length = 1; // If there are more points and not at least 'min_num_points' remain, the // voxel length is reduced trying to get this minimum number of points. - optional float min_num_points = 2; + float min_num_points = 2; // Points further away from the origin are removed. - optional float max_range = 3; + float max_range = 3; } diff --git a/cartographer/sensor/proto/sensor.proto b/cartographer/sensor/proto/sensor.proto index 2f4ddff..bd55ad6 100644 --- a/cartographer/sensor/proto/sensor.proto +++ b/cartographer/sensor/proto/sensor.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.sensor.proto; @@ -22,37 +22,37 @@ import "cartographer/transform/proto/transform.proto"; // Compressed collection of a 3D point cloud. message CompressedPointCloud { - optional int32 num_points = 1; + int32 num_points = 1; repeated int32 point_data = 3 [packed = true]; } // Proto representation of ::cartographer::sensor::ImuData. message ImuData { - optional int64 timestamp = 1; - optional transform.proto.Vector3d linear_acceleration = 2; - optional transform.proto.Vector3d angular_velocity = 3; + int64 timestamp = 1; + transform.proto.Vector3d linear_acceleration = 2; + transform.proto.Vector3d angular_velocity = 3; } // Proto representation of ::cartographer::sensor::OdometryData. message OdometryData { - optional int64 timestamp = 1; - optional transform.proto.Rigid3d pose = 2; + int64 timestamp = 1; + transform.proto.Rigid3d pose = 2; } // Proto representation of ::cartographer::sensor::FixedFramePoseData. message FixedFramePoseData { - optional int64 timestamp = 1; - optional transform.proto.Rigid3d pose = 2; + int64 timestamp = 1; + transform.proto.Rigid3d pose = 2; } // Proto representation of ::cartographer::sensor::LandmarkData. message LandmarkData { message Landmark { - optional bytes id = 1; - optional transform.proto.Rigid3d transform = 2; - optional double translation_weight = 3; - optional double rotation_weight = 4; + bytes id = 1; + transform.proto.Rigid3d transform = 2; + double translation_weight = 3; + double rotation_weight = 4; } - optional int64 timestamp = 1; + int64 timestamp = 1; repeated Landmark landmarks = 2; } diff --git a/cartographer/transform/proto/transform.proto b/cartographer/transform/proto/transform.proto index 346e14e..ba245ca 100644 --- a/cartographer/transform/proto/transform.proto +++ b/cartographer/transform/proto/transform.proto @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -syntax = "proto2"; +syntax = "proto3"; package cartographer.transform.proto; @@ -21,57 +21,57 @@ package cartographer.transform.proto; // mirror those used in the Eigen library. message Vector2d { - optional double x = 1; - optional double y = 2; + double x = 1; + double y = 2; } message Vector2f { - optional float x = 1; - optional float y = 2; + float x = 1; + float y = 2; } message Vector3d { - optional double x = 1; - optional double y = 2; - optional double z = 3; + double x = 1; + double y = 2; + double z = 3; } message Vector3f { - optional float x = 1; - optional float y = 2; - optional float z = 3; + float x = 1; + float y = 2; + float z = 3; } message Quaterniond { - optional double x = 1; - optional double y = 2; - optional double z = 3; - optional double w = 4; + double x = 1; + double y = 2; + double z = 3; + double w = 4; } message Quaternionf { - optional float x = 1; - optional float y = 2; - optional float z = 3; - optional float w = 4; + float x = 1; + float y = 2; + float z = 3; + float w = 4; } message Rigid2d { - optional Vector2d translation = 1; - optional double rotation = 2; + Vector2d translation = 1; + double rotation = 2; } message Rigid2f { - optional Vector2f translation = 1; - optional float rotation = 2; + Vector2f translation = 1; + float rotation = 2; } message Rigid3d { - optional Vector3d translation = 1; - optional Quaterniond rotation = 2; + Vector3d translation = 1; + Quaterniond rotation = 2; } message Rigid3f { - optional Vector3f translation = 1; - optional Quaternionf rotation = 2; + Vector3f translation = 1; + Quaternionf rotation = 2; }