Skip to content

Commit

Permalink
Allow sensor to generate it's own messages
Browse files Browse the repository at this point in the history
Signed-off-by: Michael Carroll <[email protected]>
  • Loading branch information
mjcarroll committed Aug 4, 2023
1 parent a516493 commit ede2475
Show file tree
Hide file tree
Showing 46 changed files with 1,285 additions and 12 deletions.
4 changes: 3 additions & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ set(GZ_COMMON_VER ${gz-common5_VERSION_MAJOR})

#--------------------------------------
# Find gz-transport
gz_find_package(gz-transport13 REQUIRED)
gz_find_package(gz-transport13 REQUIRED COMPONENTS msgs)
set(GZ_TRANSPORT_VER ${gz-transport13_VERSION_MAJOR})

#--------------------------------------
Expand Down Expand Up @@ -104,6 +104,8 @@ gz_configure_build(QUIT_IF_BUILD_ERRORS)
#============================================================================
gz_create_packages()

add_subdirectory(proto)

#============================================================================
# Configure documentation
#============================================================================
Expand Down
39 changes: 39 additions & 0 deletions proto/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
set(proto_files
${PROJECT_SOURCE_DIR}/proto/gz/msgs/air_speed_sensor.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/altimeter.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/annotated_axis_aligned_2d_box.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/annotated_axis_aligned_2d_box_v.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/annotated_oriented_3d_box.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/annotated_oriented_3d_box_v.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/axis_aligned_2d_box.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/axis_aligned_box.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/camera_info.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/dvl_beam_state.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/dvl_kinematic_estimate.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/dvl_range_estimate.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/dvl_tracking_target.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/dvl_velocity_tracking.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/fluid_pressure.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/imu.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/laserscan.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/logical_camera_image.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/magnetometer.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/navsat.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/oriented_3d_box.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/performance_sensor_metrics.proto
${PROJECT_SOURCE_DIR}/proto/gz/msgs/sensor_noise.proto
)

gz_msgs_generate_messages(
TARGET msgs
PROTO_PACKAGE "gz.msgs"
MSGS_PATH ${PROJECT_SOURCE_DIR}/proto
MSGS_PROTOS ${proto_files}
DEPENDENCIES gz-msgs${GZ_MSGS_VER}::gz-msgs${GZ_MSGS_VER}-msgs
)

install(
DIRECTORY gz
DESTINATION share/protos
COMPONENT proto
FILES_MATCHING PATTERN "*.proto")
44 changes: 44 additions & 0 deletions proto/gz/msgs/air_speed_sensor.proto
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
/*
* Copyright (C) 2023 Open Source Robotics Foundation
*
* 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 gz.msgs;
option java_package = "com.gz.msgs";
option java_outer_classname = "AirSpeedSensorProtos";

/// \ingroup gz.msgs
/// \interface AirSpeedSensor
/// \brief Definition of an air speed sensor

import "gz/msgs/header.proto";
import "gz/msgs/sensor_noise.proto";

/// \brief Message that describes an air speed sensor.
message AirSpeedSensor
{
/// \brief header data
Header header = 1;

/// \brief Differential pressure (hPa).
double diff_pressure = 2;

/// \brief Temperature (kelvin).
double temperature = 3;

/// \brief Sensor speed noise.
SensorNoise pressure_noise = 4;
}
43 changes: 43 additions & 0 deletions proto/gz/msgs/altimeter.proto
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
/*
* Copyright (C) 2017 Open Source Robotics Foundation
*
* 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 gz.msgs;
option java_package = "com.gz.msgs";
option java_outer_classname = "AltimeterProtos";

/// \ingroup gz.msgs
/// \interface Altimeter
/// \brief Data from an altimeter sensor

import "gz/msgs/header.proto";

/// \brief Altimeter sensor data
message Altimeter
{
// Other Optional header data
Header header = 1; /// Optional header data

/// \brief Vertical position data, in meters.
double vertical_position = 2;

/// \brief Vertical velocity data, in meters/second.
double vertical_velocity = 3;

/// \brief Vertical reference.
double vertical_reference = 4;
}
40 changes: 40 additions & 0 deletions proto/gz/msgs/annotated_axis_aligned_2d_box.proto
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* 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 gz.msgs;
option java_package = "com.gz.msgs";
option java_outer_classname = "AnnotatedAxisAligned2DBoxProtos";

/// \ingroup gz.msgs
/// \interface AnnotatedAxisAligned2DBox
/// \brief A 2D axis aligned box with label

import "gz/msgs/header.proto";
import "gz/msgs/axis_aligned_2d_box.proto";

message AnnotatedAxisAligned2DBox
{
/// \brief Optional header data
Header header = 1;

/// \brief Axis aligned 2d bounding box
AxisAligned2DBox box = 2;

/// \brief Label (class) of the box's object
uint32 label = 3;
}
37 changes: 37 additions & 0 deletions proto/gz/msgs/annotated_axis_aligned_2d_box_v.proto
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* 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 gz.msgs;
option java_package = "com.gz.msgs";
option java_outer_classname = "AnnotatedAxisAligned2DBox_VProtos";

/// \ingroup gz.msgs
/// \interface AnnotatedAxisAligned2DBox_V
/// \brief A message for a vector of annotated axis aligned 2d boxes

import "gz/msgs/header.proto";
import "gz/msgs/annotated_axis_aligned_2d_box.proto";

message AnnotatedAxisAligned2DBox_V
{
/// \brief Optional header data
Header header = 1;

/// \brief vector of 2d annotated boxes
repeated AnnotatedAxisAligned2DBox annotated_box = 2;
}
40 changes: 40 additions & 0 deletions proto/gz/msgs/annotated_oriented_3d_box.proto
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* 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 gz.msgs;
option java_package = "com.gz.msgs";
option java_outer_classname = "AnnotatedOriented3DBoxProtos";

/// \ingroup gz.msgs
/// \interface AnnotatedOriented3DBox
/// \brief A 3D oriented bounding box with label

import "gz/msgs/header.proto";
import "gz/msgs/oriented_3d_box.proto";

message AnnotatedOriented3DBox
{
/// \brief Optional header data
Header header = 1;

/// \brief oreinted 3d box
Oriented3DBox box = 2;

/// \brief Label (class) of the box's object
uint32 label = 3;
}
37 changes: 37 additions & 0 deletions proto/gz/msgs/annotated_oriented_3d_box_v.proto
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* 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 gz.msgs;
option java_package = "com.gz.msgs";
option java_outer_classname = "AnnotatedOriented3DBox_VProtos";

/// \ingroup gz.msgs
/// \interface AnnotatedOriented3DBox_V
/// \brief A message for a vector of annotated oriented 3d boxes

import "gz/msgs/header.proto";
import "gz/msgs/annotated_oriented_3d_box.proto";

message AnnotatedOriented3DBox_V
{
/// \brief Optional header data
Header header = 1;

/// \brief vector of 3d annotated oreinted boxes
repeated AnnotatedOriented3DBox annotated_box = 2;
}
40 changes: 40 additions & 0 deletions proto/gz/msgs/axis_aligned_2d_box.proto
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* 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 gz.msgs;
option java_package = "com.gz.msgs";
option java_outer_classname = "AxisAligned2DBoxProtos";

/// \ingroup gz.msgs
/// \interface AxisAligned2DBox
/// \brief A 2D axis aligned box

import "gz/msgs/header.proto";
import "gz/msgs/vector2d.proto";

message AxisAligned2DBox
{
/// \brief Optional header data
Header header = 1;

/// \brief Minimum corner of the axis aligned bound box in image coord.
Vector2d min_corner = 2;

/// \brief Maximum corner of the axis aligned bound box in the image coord.
Vector2d max_corner = 3;
}
40 changes: 40 additions & 0 deletions proto/gz/msgs/axis_aligned_box.proto
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
/*
* Copyright (C) 2019 Open Source Robotics Foundation
*
* 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 gz.msgs;
option java_package = "com.gz.msgs";
option java_outer_classname = "AxisAlignedBoxProtos";

/// \ingroup gz.msgs
/// \interface AxisAlignedBox
/// \brief An axis aligned box

import "gz/msgs/header.proto";
import "gz/msgs/vector3d.proto";

message AxisAlignedBox
{
/// \brief Optional header data
Header header = 1;

/// \brief Minimum corner of the axis aligned bound box in the global frame.
Vector3d min_corner = 2;

/// \brief Maximum corner of the axis aligned bound box in the global frame.
Vector3d max_corner = 3;
}
Loading

0 comments on commit ede2475

Please sign in to comment.