From da9b3936e974605d07083b3c8d174c8fa53704a1 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Fri, 28 Jul 2023 21:57:23 +0000 Subject: [PATCH] Add message library generation to gui Signed-off-by: Michael Carroll --- CMakeLists.txt | 10 ++ include/gz/gui/CMakeLists.txt | 3 +- proto/CMakeLists.txt | 17 ++ proto/gz/msgs/air_pressure_sensor.proto | 45 +++++ proto/gz/msgs/altimeter_sensor.proto | 41 +++++ proto/gz/msgs/axis.proto | 80 +++++++++ proto/gz/msgs/battery.proto | 39 +++++ proto/gz/msgs/boxgeom.proto | 36 ++++ proto/gz/msgs/camerasensor.proto | 132 ++++++++++++++ proto/gz/msgs/capsulegeom.proto | 38 ++++ proto/gz/msgs/collision.proto | 48 ++++++ proto/gz/msgs/conegeom.proto | 39 +++++ proto/gz/msgs/contactsensor.proto | 35 ++++ proto/gz/msgs/cylindergeom.proto | 36 ++++ proto/gz/msgs/density.proto | 35 ++++ proto/gz/msgs/distortion.proto | 41 +++++ proto/gz/msgs/ellipsoidgeom.proto | 37 ++++ proto/gz/msgs/fog.proto | 48 ++++++ proto/gz/msgs/friction.proto | 84 +++++++++ proto/gz/msgs/geometry.proto | 80 +++++++++ proto/gz/msgs/gps_sensor.proto | 53 ++++++ proto/gz/msgs/gui_camera.proto | 43 +++++ proto/gz/msgs/heightmapgeom.proto | 65 +++++++ proto/gz/msgs/imagegeom.proto | 39 +++++ proto/gz/msgs/imu_sensor.proto | 162 ++++++++++++++++++ proto/gz/msgs/inertial.proto | 72 ++++++++ proto/gz/msgs/joint.proto | 91 ++++++++++ proto/gz/msgs/lens.proto | 92 ++++++++++ proto/gz/msgs/lidar_sensor.proto | 51 ++++++ proto/gz/msgs/light.proto | 76 ++++++++ proto/gz/msgs/link.proto | 67 ++++++++ proto/gz/msgs/log_playback_stats.proto | 40 +++++ proto/gz/msgs/logical_camera_sensor.proto | 45 +++++ proto/gz/msgs/magnetometer_sensor.proto | 43 +++++ proto/gz/msgs/meshgeom.proto | 39 +++++ proto/gz/msgs/model.proto | 76 ++++++++ proto/gz/msgs/navsat_sensor.proto | 53 ++++++ proto/gz/msgs/particle_emitter.proto | 117 +++++++++++++ proto/gz/msgs/planegeom.proto | 39 +++++ proto/gz/msgs/plugin.proto | 37 ++++ proto/gz/msgs/polylinegeom.proto | 37 ++++ proto/gz/msgs/projector.proto | 50 ++++++ proto/gz/msgs/raysensor.proto | 48 ++++++ proto/gz/msgs/scene.proto | 58 +++++++ proto/gz/msgs/sensor.proto | 104 +++++++++++ proto/gz/msgs/server_control.proto | 41 +++++ proto/gz/msgs/sky.proto | 47 +++++ proto/gz/msgs/spheregeom.proto | 36 ++++ proto/gz/msgs/surface.proto | 48 ++++++ proto/gz/msgs/track_visual.proto | 63 +++++++ proto/gz/msgs/visual.proto | 92 ++++++++++ proto/gz/msgs/world_control.proto | 44 +++++ proto/gz/msgs/world_reset.proto | 37 ++++ proto/gz/msgs/world_stats.proto | 77 +++++++++ src/CMakeLists.txt | 1 + src/plugins/CMakeLists.txt | 3 +- src/plugins/camera_tracking/CameraTracking.cc | 1 + src/plugins/image_display/ImageDisplay.cc | 2 +- src/plugins/navsat_map/CMakeLists.txt | 38 ++++ src/plugins/point_cloud/PointCloud.cc | 2 + test/integration/CMakeLists.txt | 1 + 61 files changed, 3051 insertions(+), 3 deletions(-) create mode 100644 proto/CMakeLists.txt create mode 100644 proto/gz/msgs/air_pressure_sensor.proto create mode 100644 proto/gz/msgs/altimeter_sensor.proto create mode 100644 proto/gz/msgs/axis.proto create mode 100644 proto/gz/msgs/battery.proto create mode 100644 proto/gz/msgs/boxgeom.proto create mode 100644 proto/gz/msgs/camerasensor.proto create mode 100644 proto/gz/msgs/capsulegeom.proto create mode 100644 proto/gz/msgs/collision.proto create mode 100644 proto/gz/msgs/conegeom.proto create mode 100644 proto/gz/msgs/contactsensor.proto create mode 100644 proto/gz/msgs/cylindergeom.proto create mode 100644 proto/gz/msgs/density.proto create mode 100644 proto/gz/msgs/distortion.proto create mode 100644 proto/gz/msgs/ellipsoidgeom.proto create mode 100644 proto/gz/msgs/fog.proto create mode 100644 proto/gz/msgs/friction.proto create mode 100644 proto/gz/msgs/geometry.proto create mode 100644 proto/gz/msgs/gps_sensor.proto create mode 100644 proto/gz/msgs/gui_camera.proto create mode 100644 proto/gz/msgs/heightmapgeom.proto create mode 100644 proto/gz/msgs/imagegeom.proto create mode 100644 proto/gz/msgs/imu_sensor.proto create mode 100644 proto/gz/msgs/inertial.proto create mode 100644 proto/gz/msgs/joint.proto create mode 100644 proto/gz/msgs/lens.proto create mode 100644 proto/gz/msgs/lidar_sensor.proto create mode 100644 proto/gz/msgs/light.proto create mode 100644 proto/gz/msgs/link.proto create mode 100644 proto/gz/msgs/log_playback_stats.proto create mode 100644 proto/gz/msgs/logical_camera_sensor.proto create mode 100644 proto/gz/msgs/magnetometer_sensor.proto create mode 100644 proto/gz/msgs/meshgeom.proto create mode 100644 proto/gz/msgs/model.proto create mode 100644 proto/gz/msgs/navsat_sensor.proto create mode 100644 proto/gz/msgs/particle_emitter.proto create mode 100644 proto/gz/msgs/planegeom.proto create mode 100644 proto/gz/msgs/plugin.proto create mode 100644 proto/gz/msgs/polylinegeom.proto create mode 100644 proto/gz/msgs/projector.proto create mode 100644 proto/gz/msgs/raysensor.proto create mode 100644 proto/gz/msgs/scene.proto create mode 100644 proto/gz/msgs/sensor.proto create mode 100644 proto/gz/msgs/server_control.proto create mode 100644 proto/gz/msgs/sky.proto create mode 100644 proto/gz/msgs/spheregeom.proto create mode 100644 proto/gz/msgs/surface.proto create mode 100644 proto/gz/msgs/track_visual.proto create mode 100644 proto/gz/msgs/visual.proto create mode 100644 proto/gz/msgs/world_control.proto create mode 100644 proto/gz/msgs/world_reset.proto create mode 100644 proto/gz/msgs/world_stats.proto diff --git a/CMakeLists.txt b/CMakeLists.txt index 229237a5e..19c3c4e61 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -60,6 +60,7 @@ set(GZ_PLUGIN_VER ${gz-plugin2_VERSION_MAJOR}) #-------------------------------------- # Find gz-transport +gz_find_package(gz-transport13-msgs REQUIRED) # TODO(mjcarroll) Eliminate this gz_find_package(gz-transport13 REQUIRED) set(GZ_TRANSPORT_VER ${gz-transport13_VERSION_MAJOR}) @@ -68,6 +69,13 @@ set(GZ_TRANSPORT_VER ${gz-transport13_VERSION_MAJOR}) gz_find_package(gz-rendering8 REQUIRED) set(GZ_RENDERING_VER ${gz-rendering8_VERSION_MAJOR}) +#-------------------------------------- +# Find gz-plugin +gz_find_package(gz-sensors8-msgs REQUIRED) +gz_find_package(gz-sensors8 REQUIRED) + +set(GZ_SENSORS_VER 8) + #-------------------------------------- # Find gz-msgs gz_find_package(gz-msgs10 REQUIRED) @@ -105,6 +113,8 @@ gz_configure_build(QUIT_IF_BUILD_ERRORS) #============================================================================ add_subdirectory(conf) +add_subdirectory(proto) + #============================================================================ # Create package information #============================================================================ diff --git a/include/gz/gui/CMakeLists.txt b/include/gz/gui/CMakeLists.txt index b3842959e..f5fe1f38a 100644 --- a/include/gz/gui/CMakeLists.txt +++ b/include/gz/gui/CMakeLists.txt @@ -64,7 +64,8 @@ target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME} ${Qt5QuickControls2_LIBRARIES} ${Qt5Widgets_LIBRARIES} TINYXML2::TINYXML2 + PRIVATE + gz-gui${PROJECT_VERSION_MAJOR}-msgs ) gz_install_all_headers() - diff --git a/proto/CMakeLists.txt b/proto/CMakeLists.txt new file mode 100644 index 000000000..f357e6c4f --- /dev/null +++ b/proto/CMakeLists.txt @@ -0,0 +1,17 @@ +file(GLOB proto_files + ${PROJECT_SOURCE_DIR}/proto/gz/msgs/*.proto +) + +gz_msgs_generate_messages( + TARGET gz-gui${PROJECT_VERSION_MAJOR}-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 gz-sensors${GZ_SENSORS_VER}::gz-sensors${GZ_SENSORS_VER}-msgs +) + +install( + DIRECTORY gz + DESTINATION share/protos + COMPONENT proto + FILES_MATCHING PATTERN "*.proto") diff --git a/proto/gz/msgs/air_pressure_sensor.proto b/proto/gz/msgs/air_pressure_sensor.proto new file mode 100644 index 000000000..5af61b653 --- /dev/null +++ b/proto/gz/msgs/air_pressure_sensor.proto @@ -0,0 +1,45 @@ +/* + * 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 = "AirPressureSensorProtos"; + +/// \ingroup gz.msgs +/// \interface AirPressureSensor +/// \brief Definition of an air pressure sensor + +import "gz/msgs/header.proto"; +import "gz/msgs/sensor_noise.proto"; + +/// \brief Message that describes an air pressure sensor. +message AirPressureSensor +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Reference altitude in meters. This value can be used by a sensor + /// implementation to augment the altitude of the sensor. For example, if + /// you are using simulation, instead of creating a 1000 m mountain model on + /// which to place your sensor, you could instead set this value to 1000 and + /// place your model on a ground plane with a Z height of zero. + double reference_altitude = 2; + + /// \brief Sensor pressure noise. + SensorNoise pressure_noise = 3; +} diff --git a/proto/gz/msgs/altimeter_sensor.proto b/proto/gz/msgs/altimeter_sensor.proto new file mode 100644 index 000000000..f939675f6 --- /dev/null +++ b/proto/gz/msgs/altimeter_sensor.proto @@ -0,0 +1,41 @@ +/* + * 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 = "AltimeterSensorProtos"; + +/// \ingroup gz.msgs +/// \interface AltimeterSensor +/// \brief Definition of an altimeter sensor + +import "gz/msgs/header.proto"; +import "gz/msgs/sensor_noise.proto"; + +/// \brief Message that describes an altimeter sensor. +message AltimeterSensor +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Noise parameters for the vertical position. + SensorNoise vertical_position_noise = 2; + + /// \brief Noise parameters for the vertical velocity. + SensorNoise vertical_velocity_noise = 3; +} diff --git a/proto/gz/msgs/axis.proto b/proto/gz/msgs/axis.proto new file mode 100644 index 000000000..9d23190c2 --- /dev/null +++ b/proto/gz/msgs/axis.proto @@ -0,0 +1,80 @@ +/* + * 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 = "AxisProtos"; + +/// \ingroup gz.msgs +/// \interface Axis +/// \brief msgs::Joint axis message + +import "gz/msgs/vector3d.proto"; +import "gz/msgs/header.proto"; + +message Axis +{ + /// \brief Optional header data + Header header = 1; + + /// \brief The x,y,z components of the axis unit vector. + Vector3d xyz = 2; + + /// \brief The lower joint axis limit (radians for revolute joints, + /// meters for prismatic joints). Not valid if the joint that uses this + /// axis is continuous. + double limit_lower = 3; + + /// \brief The upper joint axis limit (radians for revolute joints, + /// meters for prismatic joints). Not valid if the joint that uses this + /// axis is continuous. + double limit_upper = 4; + + /// \brief Value for enforcing the maximum joint effort applied. + /// Limit is not enforced if value is negative. + double limit_effort = 5; + + /// \brief Value for enforcing the maximum joint velocity. + double limit_velocity = 6; + + /// \brief The physical velocity dependent viscous damping coefficient + /// of the joint axis. + double damping = 7; + + /// \brief The physical static friction value of the joint. + double friction = 8; + + /// \brief Position of the joint. For angular joints, such as revolute + /// joints, the units are radians. For linear joints, such as prismatic + /// joints, the units are meters. + double position = 10; + + /// \brief Velocity of the joint in SI units (meter/second). + double velocity = 11; + + /// \brief Force applied to the joint in SI units (Newton). + double force = 12; + + /// \brief Acceleration of the joint is SI units (meter/second^2). + double acceleration = 13; + + /// \brief Set the name of the coordinate frame in which this joint axis's + /// unit vector is expressed. An empty value implies the parent (joint) + /// frame. + string xyz_expressed_in = 14; +} diff --git a/proto/gz/msgs/battery.proto b/proto/gz/msgs/battery.proto new file mode 100644 index 000000000..576b1b392 --- /dev/null +++ b/proto/gz/msgs/battery.proto @@ -0,0 +1,39 @@ +/* + * 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 = "BatteryProtos"; + +/// \ingroup gz.msgs +/// \interface Battery +/// \brief Message for a battery + +import "gz/msgs/header.proto"; + +message Battery +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Name of the battery + string name = 2; + + /// \brief Real voltage in volts. + double voltage = 3; +} diff --git a/proto/gz/msgs/boxgeom.proto b/proto/gz/msgs/boxgeom.proto new file mode 100644 index 000000000..36c7b909c --- /dev/null +++ b/proto/gz/msgs/boxgeom.proto @@ -0,0 +1,36 @@ +/* + * 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 = "BoxGeomProtos"; + +/// \ingroup gz.msgs +/// \interface BoxGeom +/// \brief Information about a box geometry + +import "gz/msgs/header.proto"; +import "gz/msgs/vector3d.proto"; + +message BoxGeom +{ + /// \brief Optional header data + Header header = 1; + + Vector3d size = 2; +} diff --git a/proto/gz/msgs/camerasensor.proto b/proto/gz/msgs/camerasensor.proto new file mode 100644 index 000000000..65cc19c32 --- /dev/null +++ b/proto/gz/msgs/camerasensor.proto @@ -0,0 +1,132 @@ +/* + * 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 = "CameraSensorProtos"; + +/// \ingroup gz.msgs +/// \interface CameraSensor +/// \brief Information about a camera sensor element + +import "gz/msgs/distortion.proto"; +import "gz/msgs/double.proto"; +import "gz/msgs/header.proto"; +import "gz/msgs/image.proto"; +import "gz/msgs/lens.proto"; +import "gz/msgs/sensor_noise.proto"; +import "gz/msgs/vector2d.proto"; + +message CameraSensor +{ + /// \brief Bounding box types. + enum BoundingBoxType + { + /// \brief No bounding box. + NO_BOUNDING_BOX = 0; + + /// \brief 2D box that shows the full box of occluded objects + FULL_BOX_2D = 1; + + /// \brief 2D box that shows the visible part of the occluded object + VISIBLE_BOX_2D = 2; + + /// \brief 3D oriented box + BOX_3D = 3; + } + + /// \brief Segmentation types. + enum SegmentationType + { + /// \brief No segmentation. + NO_SEGMENTATION = 0; + + /// \brief Pixels of same label from different items + /// have the same color & id. + SEMANTIC = 1; + + /// \brief Pixels of same label from different items, have different + /// color & id. 1 channel for label id & 2 channels for instance id + PANOPTIC = 2; + } + + /// \brief Optional header data + Header header = 1; + + /// \brief Horizontal field of view in radians + double horizontal_fov = 2; + + /// \brief Image size in pixels. + Vector2d image_size = 3; + + /// \brief Image format. This field is deprecated, please use pixel_format. + string image_format = 4; + + /// \brief Near clip distance in meters. + double near_clip = 5; + + /// \brief Far clip distance in meters. + double far_clip = 6; + + /// \brief True if frames should be saved. + bool save_enabled = 7; + + /// \brief Path in which to save frames. + string save_path = 8; + + /// \brief Optional distortion information. + Distortion distortion = 9; + + /// \brief Optional noise parameters for the image. + SensorNoise image_noise = 10; + + /// \brief Optional depth near clip in meters. + Double depth_near_clip = 11; + + /// \brief Optional depth far clip in meters. + Double depth_far_clip = 12; + + /// \brief Optional bounding box camera type. + BoundingBoxType bounding_box_type = 13; + + /// \brief Optional segmentation camera type. + SegmentationType segmentation_type = 14; + + /// \brief Optional lens information + Lens lens = 15; + + /// \brief True if the camera will be triggered by a topic + bool triggered = 16; + + /// \brief Name of the topic that will trigger the camera if enabled + string triggered_topic = 17; + + /// \brief Value used for anti-aliasing + int32 anti_aliasing = 18; + + /// \brief Visibility mask of a camera. When the camera's visibility_mask and + /// a visual's visibility_flags evaluates to non-zero, then the visual will + /// be visible to the camera. + uint32 visibility_mask = 19; + + /// \brief True if the camera is a depth camera. + bool is_depth_camera = 20; + + /// \brief Pixel format used by the camera. This replaces image_format. + PixelFormatType pixel_format = 21; +} diff --git a/proto/gz/msgs/capsulegeom.proto b/proto/gz/msgs/capsulegeom.proto new file mode 100644 index 000000000..1103221ad --- /dev/null +++ b/proto/gz/msgs/capsulegeom.proto @@ -0,0 +1,38 @@ +/* + * 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 = "CapsuleGeomProtos"; + +/// \ingroup gz.msgs +/// \interface CapsuleGeom +/// \brief Information about a capsule geometry + +import "gz/msgs/header.proto"; + +message CapsuleGeom +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Radius of the capsule + double radius = 2; + /// \brief Height of the cylinder + double length = 3; +} diff --git a/proto/gz/msgs/collision.proto b/proto/gz/msgs/collision.proto new file mode 100644 index 000000000..bcc2e42cd --- /dev/null +++ b/proto/gz/msgs/collision.proto @@ -0,0 +1,48 @@ +/* + * 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 = "CollisionProtos"; + +/// \ingroup gz.msgs +/// \interface Collision +/// \brief Information about a collision element + +import "gz/msgs/pose.proto"; +import "gz/msgs/geometry.proto"; +import "gz/msgs/surface.proto"; +import "gz/msgs/visual.proto"; +import "gz/msgs/header.proto"; + +message Collision +{ + /// \brief Optional header data + Header header = 1; + + uint32 id = 2; + string name = 3; + double laser_retro = 4; + double max_contacts = 5; + Pose pose = 6; + Geometry geometry = 7; + Surface surface = 8; + + repeated Visual visual = 9; +} + diff --git a/proto/gz/msgs/conegeom.proto b/proto/gz/msgs/conegeom.proto new file mode 100644 index 000000000..73adfa721 --- /dev/null +++ b/proto/gz/msgs/conegeom.proto @@ -0,0 +1,39 @@ +/* + * Copyright (C) 2020 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 = "ConeGeomProtos"; + +/// \ingroup gz.msgs +/// \interface ConeGeom +/// \brief Information about a cone geometry + +import "gz/msgs/header.proto"; + +message ConeGeom +{ + /// \brief Optional header data + Header header = 1; + + /// \brief The base radius of cone in meters + double radius = 2; + + /// \brief The distance in meters from the base to the apex of the cone + double length = 3; +} diff --git a/proto/gz/msgs/contactsensor.proto b/proto/gz/msgs/contactsensor.proto new file mode 100644 index 000000000..4ecd1de08 --- /dev/null +++ b/proto/gz/msgs/contactsensor.proto @@ -0,0 +1,35 @@ +/* + * 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 = "ContactSensorProtos"; + +/// \ingroup gz.msgs +/// \interface ContactSensor +/// \brief Information about a contact sensor element + +import "gz/msgs/header.proto"; + +message ContactSensor +{ + /// \brief Optional header data + Header header = 1; + + string collision_name = 2; +} diff --git a/proto/gz/msgs/cylindergeom.proto b/proto/gz/msgs/cylindergeom.proto new file mode 100644 index 000000000..8ecd03c7f --- /dev/null +++ b/proto/gz/msgs/cylindergeom.proto @@ -0,0 +1,36 @@ +/* + * 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 = "CylinderGeomProtos"; + +/// \ingroup gz.msgs +/// \interface CylinderGeom +/// \brief Information about a cylinder geometry + +import "gz/msgs/header.proto"; + +message CylinderGeom +{ + /// \brief Optional header data + Header header = 1; + + double radius = 2; + double length = 3; +} diff --git a/proto/gz/msgs/density.proto b/proto/gz/msgs/density.proto new file mode 100644 index 000000000..328392e08 --- /dev/null +++ b/proto/gz/msgs/density.proto @@ -0,0 +1,35 @@ +/* + * 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 = "DensityProtos"; + +/// \ingroup gz.msgs +/// \interface Density +/// \brief Information about density + +import "gz/msgs/header.proto"; + +message Density +{ + /// \brief Optional header data + Header header = 1; + + double density = 2; +} diff --git a/proto/gz/msgs/distortion.proto b/proto/gz/msgs/distortion.proto new file mode 100644 index 000000000..cd2689172 --- /dev/null +++ b/proto/gz/msgs/distortion.proto @@ -0,0 +1,41 @@ +/* + * 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 = "DistortionProtos"; + +/// \ingroup gz.msgs +/// \interface Distortion +/// \brief Information about a distortion element + +import "gz/msgs/vector2d.proto"; +import "gz/msgs/header.proto"; + +message Distortion +{ + /// \brief Optional header data + Header header = 1; + + Vector2d center = 2; + double k1 = 3; + double k2 = 4; + double k3 = 5; + double p1 = 6; + double p2 = 7; +} diff --git a/proto/gz/msgs/ellipsoidgeom.proto b/proto/gz/msgs/ellipsoidgeom.proto new file mode 100644 index 000000000..d0a0a314f --- /dev/null +++ b/proto/gz/msgs/ellipsoidgeom.proto @@ -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 = "EllipsoidGeomProtos"; + +/// \ingroup gz.msgs +/// \interface EllipsoidGeom +/// \brief Information about a ellipsoid geometry + +import "gz/msgs/header.proto"; +import "gz/msgs/vector3d.proto"; + +message EllipsoidGeom +{ + /// \brief Optional header data + Header header = 1; + + /// \brief 3D Vector with the three radius that define a ellipsoid + Vector3d radii = 2; +} diff --git a/proto/gz/msgs/fog.proto b/proto/gz/msgs/fog.proto new file mode 100644 index 000000000..3a1622da7 --- /dev/null +++ b/proto/gz/msgs/fog.proto @@ -0,0 +1,48 @@ +/* + * 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 = "FogProtos"; + +/// \ingroup gz.msgs +/// \interface Fog +/// \brief Message for fog data + +import "gz/msgs/color.proto"; +import "gz/msgs/header.proto"; + +message Fog +{ + enum FogType + { + NONE = 0; + LINEAR = 1; + EXPONENTIAL = 2; + EXPONENTIAL2 = 3; + } + + /// \brief Optional header data + Header header = 1; + + FogType type = 2; + Color color = 3; + float density = 4; + float start = 5; + float end = 6; +} diff --git a/proto/gz/msgs/friction.proto b/proto/gz/msgs/friction.proto new file mode 100644 index 000000000..9bb0a6522 --- /dev/null +++ b/proto/gz/msgs/friction.proto @@ -0,0 +1,84 @@ +/* + * 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 = "FrictionProtos"; + +/// \ingroup gz.msgs +/// \interface Friction +/// \brief Information about friction + +import "gz/msgs/vector3d.proto"; +import "gz/msgs/header.proto"; + +message Friction +{ + message Torsional + { + message ODE + { + /// \brief Force dependent slip for torsional friction, between the range + /// of [0..1]. + double slip = 1; + } + + /// \brief Torsional coefficient of friction in the range of [0..1]. + double coefficient = 1; + + /// \brief By default, torsional friction is calculated using the + /// "patch_radius", which is sqrt(R*d), where "R" is the radius of the + /// collision at the contact point (surface_radius) and "d" is the contact + /// depth. If this flag is set to false, surface_radius and contact depth + /// will be used instead of patch radius. + bool use_patch_radius = 2; + + /// \brief Radius of contact patch surface, used for torsional friction. + double patch_radius = 3; + + /// \brief Surface radius on the point of contact, used for torsional + /// friction. + double surface_radius = 4; + + /// \brief Torsional friction information exclusive to ODE physics engine. + ODE ode = 5; + } + + /// \brief Optional header data + Header header = 1; + + /// \brief Coefficient of friction in the range of [0..1]. + double mu = 2; + + /// \brief Second coefficient of friction in the range of [0..1]. + double mu2 = 3; + + /// \brief Direction of mu1 in the collision local reference frame. + Vector3d fdir1 = 4; + + /// \brief Force dependent slip direction 1 in collision local frame, between + /// the range of [0..1]. + double slip1 = 5; + + /// \brief Force dependent slip direction 2 in collision local frame, between + /// the range of [0..1]. + double slip2 = 6; + + /// \brief Torsional friction. + Torsional torsional = 7; +} diff --git a/proto/gz/msgs/geometry.proto b/proto/gz/msgs/geometry.proto new file mode 100644 index 000000000..23aa7ad4c --- /dev/null +++ b/proto/gz/msgs/geometry.proto @@ -0,0 +1,80 @@ +/* + * 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 = "GeometryProtos"; + +/// \ingroup gz.msgs +/// \interface Geometry +/// \brief Information about a geometry element + +import "gz/msgs/boxgeom.proto"; +import "gz/msgs/capsulegeom.proto"; +import "gz/msgs/conegeom.proto"; +import "gz/msgs/cylindergeom.proto"; +import "gz/msgs/ellipsoidgeom.proto"; +import "gz/msgs/header.proto"; +import "gz/msgs/heightmapgeom.proto"; +import "gz/msgs/imagegeom.proto"; +import "gz/msgs/meshgeom.proto"; +import "gz/msgs/planegeom.proto"; +import "gz/msgs/polylinegeom.proto"; +import "gz/msgs/spheregeom.proto"; +import "gz/msgs/vector3d.proto"; + +message Geometry +{ + enum Type + { + BOX = 0; + CYLINDER = 1; + SPHERE = 2; + PLANE = 3; + IMAGE = 4; + HEIGHTMAP = 5; + MESH = 6; + TRIANGLE_FAN = 7; + LINE_STRIP = 8; + POLYLINE = 9; + CONE = 10; + EMPTY = 11; + ARROW = 12; + AXIS = 13; + CAPSULE = 14; + ELLIPSOID = 15; + } + + /// \brief Optional header data + Header header = 1; + + Type type = 2; + BoxGeom box = 3; + CylinderGeom cylinder = 4; + PlaneGeom plane = 5; + SphereGeom sphere = 6; + ImageGeom image = 7; + HeightmapGeom heightmap = 8; + MeshGeom mesh = 9; + ConeGeom cone = 10; + CapsuleGeom capsule = 13; + EllipsoidGeom ellipsoid = 14; + + repeated Vector3d points = 11; + repeated Polyline polyline = 12; +} diff --git a/proto/gz/msgs/gps_sensor.proto b/proto/gz/msgs/gps_sensor.proto new file mode 100644 index 000000000..8a4d47e5e --- /dev/null +++ b/proto/gz/msgs/gps_sensor.proto @@ -0,0 +1,53 @@ +/* + * 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 = "Protos"; + +/// \ingroup gz.msgs +/// \interface GPSSensor +/// \brief Information about a GPS sensor element +/// This message will be deprecated in favor of NavSat sensor. + +import "gz/msgs/sensor_noise.proto"; +import "gz/msgs/header.proto"; + +message GPSSensor +{ + /// \brief Sensing information + message Sensing + { + /// \brief Horizontal noise + SensorNoise horizontal_noise = 1; + + /// \brief Vertical noise + SensorNoise vertical_noise = 2; + } + + /// \brief Optional header data + Header header = 1; + + /// \brief Position sensing. Consists of horizontal and vertical noise + /// properties + Sensing position = 2; + + /// \brief Velocity sensing. Consists of horizontal and vertical noise + /// properties + Sensing velocity = 3; +} diff --git a/proto/gz/msgs/gui_camera.proto b/proto/gz/msgs/gui_camera.proto new file mode 100644 index 000000000..96cfa121b --- /dev/null +++ b/proto/gz/msgs/gui_camera.proto @@ -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 = "GUICameraProtos"; + +/// \ingroup gz.msgs +/// \interface GUICamera +/// \brief Message for a GUI Camera + +import "gz/msgs/pose.proto"; +import "gz/msgs/track_visual.proto"; +import "gz/msgs/header.proto"; + +message GUICamera +{ + /// \brief Optional header data + Header header = 1; + + string name = 2; + string view_controller = 3; + Pose pose = 4; + TrackVisual track = 5; + + /// \brief Type of projection: "perspective" or "orthographic". + string projection_type = 6; +} diff --git a/proto/gz/msgs/heightmapgeom.proto b/proto/gz/msgs/heightmapgeom.proto new file mode 100644 index 000000000..87124ddbb --- /dev/null +++ b/proto/gz/msgs/heightmapgeom.proto @@ -0,0 +1,65 @@ +/* + * 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 = "HeightmapGeomProtos"; + +/// \ingroup gz.msgs +/// \interface HeightmapGeom +/// \brief Message for a heightmap geometry + +import "gz/msgs/image.proto"; +import "gz/msgs/vector3d.proto"; +import "gz/msgs/header.proto"; + +message HeightmapGeom +{ + /// \brief Optional header data + Header header = 1; + + Image image = 2; // The height data + Vector3d size = 3; // Size in meters + Vector3d origin = 4; // Origin in world coordinate frame + repeated float heights = 5; + int32 width = 6; + int32 height = 7; + + message Texture + { + string diffuse = 1; + string normal = 2; + double size = 3; + } + + message Blend + { + double min_height = 1; + double fade_dist = 2; + } + + repeated Texture texture = 8; // List of textures + repeated Blend blend = 9; // How to blend the textures + bool use_terrain_paging = 10; // Enable terrain paging in rendering + + // The image filename + string filename = 11; + + // Sample level + uint32 sampling = 12; +} diff --git a/proto/gz/msgs/imagegeom.proto b/proto/gz/msgs/imagegeom.proto new file mode 100644 index 000000000..06b344021 --- /dev/null +++ b/proto/gz/msgs/imagegeom.proto @@ -0,0 +1,39 @@ +/* + * 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 = "ImageGeomProtos"; + +/// \ingroup gz.msgs +/// \interface ImageGeom +/// \brief Message for a image geometry + +import "gz/msgs/header.proto"; + +message ImageGeom +{ + /// \brief Optional header data + Header header = 1; + + string uri = 2; + double scale = 3; + int32 threshold = 4; + double height = 5; + int32 granularity = 6; +} diff --git a/proto/gz/msgs/imu_sensor.proto b/proto/gz/msgs/imu_sensor.proto new file mode 100644 index 000000000..0e5d90f96 --- /dev/null +++ b/proto/gz/msgs/imu_sensor.proto @@ -0,0 +1,162 @@ +/* + * 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 = "IMUSensorProtos"; + +/// \ingroup gz.msgs +/// \interface IMUSensor +/// \brief Information about an imu sensor + +import "gz/msgs/sensor_noise.proto"; +import "gz/msgs/header.proto"; +import "gz/msgs/vector3d.proto"; + +message IMUSensor +{ + /// \brief Angular velocity information + message AngularVelocity + { + /// \brief Noise about the x-axis + SensorNoise x_noise = 1; + + /// \brief Noise about the y-axis + SensorNoise y_noise = 2; + + /// \brief Noise about the z-axis + SensorNoise z_noise = 3; + } + + /// \brief Linear acceleration information + message LinearAcceleration + { + /// \brief Noise about the x-axis + SensorNoise x_noise = 1; + + /// \brief Noise about the y-axis + SensorNoise y_noise = 2; + + /// \brief Noise about the z-axis + SensorNoise z_noise = 3; + } + + /// \brief Orientation reference frame information + message OrientationReferenceFrame + { + /// \brief This string represents special hardcoded use cases that are + /// commonly seen with typical robot IMU's: + /// - CUSTOM: use Euler angle custom_rpy orientation specification. + /// The orientation of the IMU's reference frame is defined + /// by adding the custom_rpy rotation + /// to the parent_frame. + /// - NED: The IMU XYZ aligns with NED, where NED orientation relative + /// to the world + /// is defined by the SphericalCoordinates class. + /// - ENU: The IMU XYZ aligns with ENU, where ENU orientation relative + /// to the world is defined by the SphericalCoordinates class. + /// - NWU: The IMU XYZ aligns with NWU, where NWU orientation relative + /// to the world is defined by the SphericalCoordinates class. + /// - GRAV_UP: where direction of gravity maps to IMU reference frame + /// Z-axis with Z-axis pointing in the opposite direction of + /// gravity. IMU reference frame X-axis direction is defined + /// by GravityDirX(). Note if GravityDirX() is parallel to + /// gravity direction, this configuration fails. Otherwise, + /// IMU reference frame X-axis is defined by projection of + /// GravtyDirX onto a plane normal to the gravity vector. + /// IMU reference frame Y-axis is a vector orthogonal to + /// both X and Z axis following the right hand rule. + /// - GRAV_DOWN: where direction of gravity maps to IMU reference frame + /// Z-axis with Z-axis pointing in the direction of gravity. + /// IMU reference frame X-axis direction is defined by + /// GravityDirX(). Note if GravityDirX() is parallel to + /// gravity direction, this configuration fails. Otherwise, + /// IMU reference frame X-axis is defined by projection of + /// GravityDirX() onto a plane normal to the gravity vector. + /// IMU reference frame Y-axis is a vector orthogonal to both + /// X and Z axis following the right hand rule. + string localization = 1; + + /// \brief This field and custom_rpy_parent_frame are used when + /// Localization is set to CUSTOM. Orientation + /// (fixed axis roll, pitch yaw) transform from ParentFrame to this IMU's + /// reference frame. + /// + /// Some common examples are: + /// - IMU reports in its local frame on boot. IMU sensor frame is the + /// reference frame. Example: parent_frame="", custom_rpy="0 0 0" + /// - IMU reports in Gazebo world frame. + /// Example sdf: parent_frame="world", custom_rpy="0 0 0" + /// - IMU reports in NWU frame. Uses SphericalCoordinates class to + /// determine world frame in relation to magnetic north and gravity; + /// i.e. rotation between North-West-Up and world (+X,+Y,+Z) frame is + /// defined by SphericalCoordinates class. + /// Example sdf given world is NWU: parent_frame="world", + /// custom_rpy="0 0 0" + /// - IMU reports in NED frame. Uses SphericalCoordinates class to + /// determine world frame in relation to magnetic north and gravity; + /// i.e. rotation between North-East-Down and world (+X,+Y,+Z) frame is + /// defined by SphericalCoordinates class. + /// Example sdf given world is NWU: parent_frame="world", + /// custom_rpy="M_PI 0 0" + /// - IMU reports in ENU frame. Uses SphericalCoordinates class to + /// determine world frame in relation to magnetic north and gravity; + /// i.e. rotation between East-North-Up and world (+X,+Y,+Z) frame is + /// defined by SphericalCoordinates class. + /// Example sdf given world is NWU: parent_frame="world", + /// custom_rpy="0 0 -0.5*M_PI" + /// - IMU reports in ROS optical frame as described in + /// http://www.ros.org/reps/rep-0103.html#suffix-frames, which is + /// (z-forward, x-left to right when facing +z, y-top to bottom when + /// facing +z). (default gazebo camera is +x:view direction, +y:left, + /// +z:up). + /// Example sdf: parent_frame="local", custom_rpy="-0.5*M_PI 0 -0.5*M_PI" + Vector3d custom_rpy = 2; + + /// \brief The name of parent frame which the custom_rpy transform is + /// defined relative to. It can be any valid fully scoped link name or the + /// special reserved "world" frame. If left empty, use the sensor's own + /// local frame. + string custom_rpy_parent_frame = 3; + + /// \brief Used when localization is set to GRAV_UP or GRAV_DOWN, a + /// projection of this vector into a plane that is orthogonal to the + /// gravity vector defines the direction of the IMU reference frame's + /// X-axis. grav_dir_x is defined in the coordinate frame as defined by + /// the parent_frame element. + Vector3d gravity_dir_x = 4; + + /// \brief The name of parent frame which the GravityDirX vector is + /// defined relative to. It can be any valid fully scoped link name or the + /// special reserved "world" frame. If left empty, use the sensor's own + /// local frame. + string gravity_dir_x_parent_frame = 5; + } + + /// \brief Optional header data + Header header = 1; + + /// \brief Angular velocity information + AngularVelocity angular_velocity = 2; + + /// \brief Linear acceleration information + LinearAcceleration linear_acceleration = 3; + + /// \brief Orientation reference frame information. + OrientationReferenceFrame orientation_ref_frame = 4; +} diff --git a/proto/gz/msgs/inertial.proto b/proto/gz/msgs/inertial.proto new file mode 100644 index 000000000..d88ab0f53 --- /dev/null +++ b/proto/gz/msgs/inertial.proto @@ -0,0 +1,72 @@ +/* + * 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 = "InertialProtos"; + +/// \ingroup gz.msgs +/// \interface Inertial +/// \brief Information about inertia + +import "gz/msgs/pose.proto"; +import "gz/msgs/header.proto"; + +message Inertial +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Mass in kg + double mass = 2; + + /// \brief CoM pose with respect to the link origin. In meters. + Pose pose = 3; + + /// \brief Inertia matrix's XX element, in kg * m^2. + double ixx = 4; + + /// \brief Inertia matrix's XY element, in kg * m^2. + double ixy = 5; + + /// \brief Inertia matrix's XZ element, in kg * m^2. + double ixz = 6; + + /// \brief Inertia matrix's YY element, in kg * m^2. + double iyy = 7; + + /// \brief Inertia matrix's YZ element, in kg * m^2. + double iyz = 8; + + /// \brief Inertia matrix's ZZ element, in kg * m^2. + double izz = 9; + + /// \brief Fluid added mass matrix. The matrix is symmetric, so only the 21 + /// elements of the top-half need to be set, organized as follows: + /// + /// 00, 01, 02, 03, 04, 05, + /// 11, 12, 13, 14, 15, + /// 22, 23, 24, 25, + /// 33, 34, 35, + /// 44, 45, + /// 55, + /// + /// Elements on the top-left 3x3 corner are in kg, the bottom-right ones are + /// in kg * m^2, and the rest are in kg * m. + repeated double fluid_added_mass = 10; +} diff --git a/proto/gz/msgs/joint.proto b/proto/gz/msgs/joint.proto new file mode 100644 index 000000000..d3a9169ad --- /dev/null +++ b/proto/gz/msgs/joint.proto @@ -0,0 +1,91 @@ +/* + * 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 = "JointProtos"; + +/// \ingroup gz.msgs +/// \interface Joint +/// \brief Message for creating joint + +import "gz/msgs/header.proto"; +import "gz/msgs/axis.proto"; +import "gz/msgs/pose.proto"; +import "gz/msgs/sensor.proto"; + +message Joint +{ + + message Gearbox + { + /// \brief Gearbox joint reference body link + string gearbox_reference_body = 1; + + /// \brief Gearbox ratio. + double gearbox_ratio = 2; + } + + message Screw + { + /// \brief Screw joint thread pitch. + double thread_pitch = 1; + } + + enum Type + { + REVOLUTE = 0; + REVOLUTE2 = 1; + PRISMATIC = 2; + UNIVERSAL = 3; + BALL = 4; + SCREW = 5; + GEARBOX = 6; + FIXED = 7; + CONTINUOUS = 8; + } + + /// \brief Optional header data + Header header = 1; + + string name = 2; + uint32 id = 3; + + Type type = 4; + string parent = 5; + uint32 parent_id = 6; + string child = 7; + uint32 child_id = 8; + Pose pose = 9; + Axis axis1 = 10; + Axis axis2 = 11; + + double cfm = 12; + double bounce = 13; + + double fudge_factor = 14; + double limit_cfm = 15; + double limit_erp = 16; + double suspension_cfm = 17; + double suspension_erp = 18; + + Gearbox gearbox = 19; + Screw screw = 20; + + repeated Sensor sensor = 21; +} diff --git a/proto/gz/msgs/lens.proto b/proto/gz/msgs/lens.proto new file mode 100644 index 000000000..1ed08f2b1 --- /dev/null +++ b/proto/gz/msgs/lens.proto @@ -0,0 +1,92 @@ +/* + * Copyright (C) 2022 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 = "LensProtos"; + +/// \ingroup gz.msgs +/// \interface Lens +/// \brief Information about a lens element + +message Lens +{ + /// \brief Types of lens models. + enum Type + { + TYPE_NOT_SPECIFIED = 0; + GNOMONICAL = 1; + STEREOGRAPHIC = 2; + EQUIDISTANT = 3; + EQUISOLID_ANGLE = 4; + ORTHOGRAPHIC = 5; + CUSTOM = 6; + } + + /// \brief Lens custom function type. + enum FunctionType + { + FUNCTION_NOT_SPECIFIED = 0; + SIN = 1; + TAN = 2; + ID = 3; + } + + /// \brief Lens type + Type type = 1; + + /// \brief Lens scale to horizontal field of view. + bool scale_to_hfov = 2; + + /// \brief Lens custom function linear scaling constant + double c1 = 3; + + /// \brief Lens custom function angular scaling constant. + double c2 = 4; + + /// \brief Lens custom function angle offset constant. + double c3 = 5; + + /// \brief Lens custom function focal length. + double focal_length = 6; + + /// \brief Lens custom function type. + FunctionType function_type = 7; + + /// \brief Lens cutoff angle in radians. Everything outside of the specified + /// angle will be hidden. + double cutoff_angle = 8; + + /// \brief The resolution of the environment cube map used to draw the world. + int32 environment_texture_size = 9; + + /// \brief Lens X focal length in pixels. + double intrinsics_fx = 10; + + /// \brief Lens Y focal length in pixels. + double intrinsics_fy = 11; + + /// \brief Lens X principal point in pixels. + double intrinsics_cx = 12; + + /// \brief Lens Y principal point in pixels. + double intrinsics_cy = 13; + + /// \brief Lens XY axis skew. + double intrinsics_skew = 14; +} diff --git a/proto/gz/msgs/lidar_sensor.proto b/proto/gz/msgs/lidar_sensor.proto new file mode 100644 index 000000000..103cb5707 --- /dev/null +++ b/proto/gz/msgs/lidar_sensor.proto @@ -0,0 +1,51 @@ +/* + * 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 = "LidarSensorProtos"; + +/// \ingroup gz.msgs +/// \interface LidarSensor +/// \brief Information about a lidar sensor element + +import "gz/msgs/header.proto"; +import "gz/msgs/sensor_noise.proto"; + +message LidarSensor +{ + /// \brief Optional header data + Header header = 1; + + bool display_scan = 2; + int32 horizontal_samples = 3; + double horizontal_resolution = 4; + double horizontal_min_angle = 5; + double horizontal_max_angle = 6; + + int32 vertical_samples = 7; + double vertical_resolution = 8; + double vertical_min_angle = 9; + double vertical_max_angle = 10; + + double range_min = 11; + double range_max = 12; + double range_resolution = 13; + + SensorNoise noise = 14; +} diff --git a/proto/gz/msgs/light.proto b/proto/gz/msgs/light.proto new file mode 100644 index 000000000..da39057a0 --- /dev/null +++ b/proto/gz/msgs/light.proto @@ -0,0 +1,76 @@ +/* + * 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 = "LightProtos"; + +/// \ingroup gz.msgs +/// \interface Light +/// \brief Message for a light + +import "gz/msgs/header.proto"; +import "gz/msgs/pose.proto"; +import "gz/msgs/vector3d.proto"; +import "gz/msgs/color.proto"; + +message Light +{ + /// \brief Optional header data + Header header = 1; + + string name = 2; + enum LightType + { + POINT = 0; + SPOT = 1; + DIRECTIONAL = 2; + } + LightType type = 3; + + Pose pose = 4; + Color diffuse = 5; + Color specular = 6; + float attenuation_constant = 7; + float attenuation_linear = 8; + float attenuation_quadratic = 9; + Vector3d direction = 10; + float range = 11; + bool cast_shadows = 12; + float spot_inner_angle = 13; + float spot_outer_angle = 14; + float spot_falloff = 15; + + /// \brief Unique id of the light + uint32 id = 16; + + /// \brief Unique id of light's parent + uint32 parent_id = 17; + + /// \brief light intensity + float intensity = 18; + + /// \brief is the light on or off + /// true is off, otherwise is on + bool is_light_off = 19; + + /// \brief Set if the visual of the light + /// is visible, true is visible, + /// otherwise is invisible + bool visualize_visual = 20; +} diff --git a/proto/gz/msgs/link.proto b/proto/gz/msgs/link.proto new file mode 100644 index 000000000..4cd450dfc --- /dev/null +++ b/proto/gz/msgs/link.proto @@ -0,0 +1,67 @@ +/* + * 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 = "LinkProtos"; + +/// \ingroup gz.msgs +/// \interface Link +/// \brief Information about a link + +import "gz/msgs/inertial.proto"; +import "gz/msgs/collision.proto"; +import "gz/msgs/visual.proto"; +import "gz/msgs/light.proto"; +import "gz/msgs/sensor.proto"; +import "gz/msgs/particle_emitter.proto"; +import "gz/msgs/projector.proto"; +import "gz/msgs/pose.proto"; +import "gz/msgs/battery.proto"; +import "gz/msgs/density.proto"; +import "gz/msgs/header.proto"; + +message Link +{ + /// \brief Optional header data + Header header = 1; + + uint32 id = 2; + string name = 3; + bool self_collide = 4; + bool gravity = 5; + bool kinematic = 6; + bool enabled = 7; + Density density = 8; + Inertial inertial = 9; + Pose pose = 10; + repeated Visual visual = 11; + repeated Collision collision = 12; + repeated Sensor sensor = 13; + repeated Projector projector = 14; + bool canonical = 15; + + /// \brief A vector of batteries attached to this link. + repeated Battery battery = 16; + + /// \brief A vector of lights attached to this link + repeated Light light = 17; + + /// \brief A vector of particle emitters attached to this link. + repeated ParticleEmitter particle_emitter = 18; +} diff --git a/proto/gz/msgs/log_playback_stats.proto b/proto/gz/msgs/log_playback_stats.proto new file mode 100644 index 000000000..d59252aad --- /dev/null +++ b/proto/gz/msgs/log_playback_stats.proto @@ -0,0 +1,40 @@ +/* + * 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 = "LogPlaybackStatisticsProtos"; + +/// \ingroup gz.msgs +/// \interface LogPlaybackStatistics +/// \brief A message with statistics about a log during playback. + +import "gz/msgs/time.proto"; +import "gz/msgs/header.proto"; + +message LogPlaybackStatistics +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Log start time + Time start_time = 2; + + /// \brief Log end time + Time end_time = 3; +} diff --git a/proto/gz/msgs/logical_camera_sensor.proto b/proto/gz/msgs/logical_camera_sensor.proto new file mode 100644 index 000000000..6b538aa6d --- /dev/null +++ b/proto/gz/msgs/logical_camera_sensor.proto @@ -0,0 +1,45 @@ +/* + * 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 = "LogicalCameraSensorProtos"; + +/// \ingroup gz.msgs +/// \interface LogicalCameraSensor +/// \brief Information about a logical camera sensor element + +import "gz/msgs/header.proto"; + +message LogicalCameraSensor +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Near clipping plane of the view frustum in meters. + double near_clip = 2; + + /// \brief Far clipping plane of the view frustum in meters. + double far_clip = 3; + + /// \brief Horizontal field of view in radians. + double horizontal_fov = 4; + + /// \brief Near and far clipping plane aspect ratio (width/height). + double aspect_ratio = 5; +} diff --git a/proto/gz/msgs/magnetometer_sensor.proto b/proto/gz/msgs/magnetometer_sensor.proto new file mode 100644 index 000000000..6f2e77eda --- /dev/null +++ b/proto/gz/msgs/magnetometer_sensor.proto @@ -0,0 +1,43 @@ +/* + * 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 = "MagnetometerSensorProtos"; + +/// \ingroup gz.msgs +/// \interface MagnetometerSensor +/// \brief Information about a magnetometer sensor + +import "gz/msgs/header.proto"; +import "gz/msgs/sensor_noise.proto"; + +message MagnetometerSensor +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Noise about the x-axis + SensorNoise x_noise = 2; + + /// \brief Noise about the y-axis + SensorNoise y_noise = 3; + + /// \brief Noise about the z-axis + SensorNoise z_noise = 4; +} diff --git a/proto/gz/msgs/meshgeom.proto b/proto/gz/msgs/meshgeom.proto new file mode 100644 index 000000000..139ea83aa --- /dev/null +++ b/proto/gz/msgs/meshgeom.proto @@ -0,0 +1,39 @@ +/* + * 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 = "MeshGeomProtos"; + +/// \ingroup gz.msgs +/// \interface MeshGeom +/// \brief Message for a mesh geometry + +import "gz/msgs/vector3d.proto"; +import "gz/msgs/header.proto"; + +message MeshGeom +{ + /// \brief Optional header data + Header header = 1; + + string filename = 2; + Vector3d scale = 3; + string submesh = 4; + bool center_submesh = 5; +} diff --git a/proto/gz/msgs/model.proto b/proto/gz/msgs/model.proto new file mode 100644 index 000000000..1202e7493 --- /dev/null +++ b/proto/gz/msgs/model.proto @@ -0,0 +1,76 @@ +/* + * 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 = "ModelProtos"; + +/// \ingroup gz.msgs +/// \interface Model +/// \brief Information about a model + +import "gz/msgs/axis_aligned_box.proto"; +import "gz/msgs/joint.proto"; +import "gz/msgs/link.proto"; +import "gz/msgs/pose.proto"; +import "gz/msgs/visual.proto"; +import "gz/msgs/vector3d.proto"; +import "gz/msgs/header.proto"; + +message Model +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Name of the model. + string name = 2; + + /// \brief Unique ID associated with the model + uint32 id = 3; + + /// \brief True if the model is statc. + bool is_static = 4; + + /// \brief Pose of the model. + Pose pose = 5; + + /// \brief Information about the joints in this model. + repeated Joint joint = 6; + + /// \brief Information about the links in this model. + repeated Link link = 7; + + /// \brief True if the model was deleted. + bool deleted = 8; + + /// \brief Information about the visuals in this model. + repeated Visual visual = 9; + + /// \brief Scaling factor applied to the model + Vector3d scale = 10; + + /// \brief True if self collide is enabled. + bool self_collide = 11; + + /// \brief An array of nested models. + repeated Model model = 12; + + /// \brief Axis aligned bounding box for the model. The center of the + /// bounding box should coincide with the model's pose. + AxisAlignedBox bounding_box = 13; +} diff --git a/proto/gz/msgs/navsat_sensor.proto b/proto/gz/msgs/navsat_sensor.proto new file mode 100644 index 000000000..3691ef848 --- /dev/null +++ b/proto/gz/msgs/navsat_sensor.proto @@ -0,0 +1,53 @@ +/* + * 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 = "NavSatSensorProtos"; + +/// \ingroup gz.msgs +/// \interface NavSatSensor +/// \brief Information about a NavSat sensor +/// This replaces the GPS sensor message + +import "gz/msgs/sensor_noise.proto"; +import "gz/msgs/header.proto"; + +message NavSatSensor +{ + /// \brief Sensing information + message Sensing + { + /// \brief Horizontal noise + SensorNoise horizontal_noise = 1; + + /// \brief Vertical noise + SensorNoise vertical_noise = 2; + } + + /// \brief Optional header data + Header header = 1; + + /// \brief Position sensing. Consists of horizontal and vertical noise + /// properties + Sensing position = 2; + + /// \brief Velocity sensing. Consists of horizontal and vertical noise + /// properties + Sensing velocity = 3; +} diff --git a/proto/gz/msgs/particle_emitter.proto b/proto/gz/msgs/particle_emitter.proto new file mode 100644 index 000000000..564b88ff4 --- /dev/null +++ b/proto/gz/msgs/particle_emitter.proto @@ -0,0 +1,117 @@ +/* + * 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 = "ParticleEmitterProtos"; + +/// \ingroup gz.msgs +/// \interface ParticleEmitter +/// \brief Message for a particle emitter. + +import "gz/msgs/boolean.proto"; +import "gz/msgs/color.proto"; +import "gz/msgs/float.proto"; +import "gz/msgs/header.proto"; +import "gz/msgs/material.proto"; +import "gz/msgs/pose.proto"; +import "gz/msgs/stringmsg.proto"; +import "gz/msgs/vector3d.proto"; + +message ParticleEmitter +{ + /// \brief Optional header data. + Header header = 1; + + /// \brief The emitter name. + string name = 2; + + /// \brief Unique Id. + uint32 id = 3; + + /// \brief All possible emitter types. + enum EmitterType + { + /// \brief Point emitter. + POINT = 0; + /// \brief Box emitter. + BOX = 1; + /// \brief Cylinder emitter. + CYLINDER = 2; + /// \brief Ellipsoid emitter. + ELLIPSOID = 3; + } + /// \brief The emitter type. + EmitterType type = 4; + + /// \brief The position of the emitter. + Pose pose = 5; + + /// The size of the emitter where the particles are sampled. + Vector3d size = 6; + + /// \brief How many particles per second should be emitted. + Float rate = 7; + + /// \brief The number of seconds the emitter is active. + Float duration = 8; + + /// \brief Whether particle emitter is enabled or not. + Boolean emitting = 9; + + /// \brief The particle dimensions (width, height, depth). + Vector3d particle_size = 10; + + /// \brief The number of seconds each particle will ’live’ for before + /// being destroyed. + Float lifetime = 11; + + /// \brief The material which all particles in the emitter will use. + Material material = 12; + + /// \brief The minimum velocity each particle is emitted (m/s). + Float min_velocity = 13; + + /// \brief The maximum velocity each particle is emitted (m/s). + Float max_velocity = 14; + + /// \brief The starting color of the particles. + Color color_start = 15; + + /// \brief The end color of the particles. + Color color_end = 16; + + /// \brief The amount by which to scale the particles in both x and y + /// direction per second (screen coordinates). + Float scale_rate = 17; + + /// \brief The path to the color image used as an affector. + StringMsg color_range_image = 18; + + /// \brief The topic name used by the particle emitter for control and + /// modification. + StringMsg topic = 19; + + /// \brief The ratio of particles that will be detected by sensors. + /// Increasing the ratio means there is a higher chance of particles + /// reflecting and interfering with depth sensing, making the emitter + /// appear more dense. Decreasing the ratio decreases the chance of + /// particles reflecting and interfering with depth sensing, making it + /// appear less dense. Value is in the range of [0, 1]. + Float particle_scatter_ratio = 20; +} diff --git a/proto/gz/msgs/planegeom.proto b/proto/gz/msgs/planegeom.proto new file mode 100644 index 000000000..e8e45d184 --- /dev/null +++ b/proto/gz/msgs/planegeom.proto @@ -0,0 +1,39 @@ +/* + * 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 = "PlaneGeomProtos"; + +/// \ingroup gz.msgs +/// \interface PlaneGeom +/// \brief Message for a plane geometry + +import "gz/msgs/vector3d.proto"; +import "gz/msgs/vector2d.proto"; +import "gz/msgs/header.proto"; + +message PlaneGeom +{ + /// \brief Optional header data + Header header = 1; + + Vector3d normal = 2; + Vector2d size = 3; + double d = 4; +} diff --git a/proto/gz/msgs/plugin.proto b/proto/gz/msgs/plugin.proto new file mode 100644 index 000000000..441ae1d3a --- /dev/null +++ b/proto/gz/msgs/plugin.proto @@ -0,0 +1,37 @@ +/* + * 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 = "PluginProtos"; + +/// \ingroup gz.msgs +/// \interface Plugin +/// \brief A message containing visual information for gazebo::Plugin + +import "gz/msgs/header.proto"; + +message Plugin +{ + /// \brief Optional header data + Header header = 1; + + string name = 2; + string filename = 3; + string innerxml = 4; +} diff --git a/proto/gz/msgs/polylinegeom.proto b/proto/gz/msgs/polylinegeom.proto new file mode 100644 index 000000000..a99cbe1a4 --- /dev/null +++ b/proto/gz/msgs/polylinegeom.proto @@ -0,0 +1,37 @@ +/* + * 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 = "Protos"; + +/// \ingroup gz.msgs +/// \interface Polyline +/// \brief Information about Polyline geometry + +import "gz/msgs/vector2d.proto"; +import "gz/msgs/header.proto"; + +message Polyline +{ + /// \brief Optional header data + Header header = 1; + + double height = 2; + repeated Vector2d point = 3; +} diff --git a/proto/gz/msgs/projector.proto b/proto/gz/msgs/projector.proto new file mode 100644 index 000000000..9194ede13 --- /dev/null +++ b/proto/gz/msgs/projector.proto @@ -0,0 +1,50 @@ +/* + * 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 = "ProjectorProtos"; + +/// \ingroup gz.msgs +/// \interface Projector +/// \brief Information about a projector + +import "gz/msgs/pose.proto"; +import "gz/msgs/header.proto"; + +message Projector +{ + /// \brief Optional header data + Header header = 1; + + string name = 2; + string texture = 3; + Pose pose = 4; + double fov = 5; + double near_clip = 6; + double far_clip = 7; + bool enabled = 8; + + /// \brief Unique ID associated with the projector + uint32 id = 9; + + /// \brief Visibility flags of a projector. When a camera's visibility_mask + /// & (bitwise AND) the projector's visibility_flags evaluates to non-zero, + /// the projected pattern will be visible to the camera. + uint32 visibility_flags = 10; +} diff --git a/proto/gz/msgs/raysensor.proto b/proto/gz/msgs/raysensor.proto new file mode 100644 index 000000000..9ef38424a --- /dev/null +++ b/proto/gz/msgs/raysensor.proto @@ -0,0 +1,48 @@ +/* + * 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 = "RaySensorProtos"; + +/// \ingroup gz.msgs +/// \interface RaySensor +/// \brief Information about a ray sensor element + +import "gz/msgs/header.proto"; + +message RaySensor +{ + /// \brief Optional header data + Header header = 1; + + bool display_scan = 2; + int32 horizontal_samples = 3; + double horizontal_resolution = 4; + double horizontal_min_angle = 5; + double horizontal_max_angle = 6; + + int32 vertical_samples = 7; + double vertical_resolution = 8; + double vertical_min_angle = 9; + double vertical_max_angle = 10; + + double range_min = 11; + double range_max = 12; + double range_resolution = 13; +} diff --git a/proto/gz/msgs/scene.proto b/proto/gz/msgs/scene.proto new file mode 100644 index 000000000..b2579ac13 --- /dev/null +++ b/proto/gz/msgs/scene.proto @@ -0,0 +1,58 @@ +/* + * 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 = "SceneProtos"; + +/// \ingroup gz.msgs +/// \interface Scene +/// \brief A message containing a description of a scene + +import "gz/msgs/color.proto"; +import "gz/msgs/fog.proto"; +import "gz/msgs/sky.proto"; +import "gz/msgs/light.proto"; +import "gz/msgs/joint.proto"; +import "gz/msgs/material.proto"; +import "gz/msgs/model.proto"; +import "gz/msgs/header.proto"; + +message Scene +{ + /// \brief Optional header data + Header header = 1; + + string name = 2; + Color ambient = 3; + Color background = 4; + Sky sky = 5; + bool shadows = 6; + Fog fog = 7; + bool grid = 8; + + repeated Model model = 9; + repeated Light light = 10; + repeated Joint joint = 11; + + /// \brief Show/hide world origin indicator. + bool origin_visual = 12; + + /// \brief Shadow caster material script. + Material.Script shadow_caster_material_script = 13; +} diff --git a/proto/gz/msgs/sensor.proto b/proto/gz/msgs/sensor.proto new file mode 100644 index 000000000..aae3a1fe8 --- /dev/null +++ b/proto/gz/msgs/sensor.proto @@ -0,0 +1,104 @@ +/* + * 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 = "SensorProtos"; + +/// \ingroup gz.msgs +/// \interface Sensor +/// \brief Information about a sensor element + +import "gz/msgs/altimeter_sensor.proto"; +import "gz/msgs/camerasensor.proto"; +import "gz/msgs/contactsensor.proto"; +import "gz/msgs/air_pressure_sensor.proto"; +import "gz/msgs/gps_sensor.proto"; +import "gz/msgs/header.proto"; +import "gz/msgs/imu_sensor.proto"; +import "gz/msgs/lidar_sensor.proto"; +import "gz/msgs/logical_camera_sensor.proto"; +import "gz/msgs/magnetometer_sensor.proto"; +import "gz/msgs/pose.proto"; + +message Sensor +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Name of the sensor + string name = 2; + + /// \brief Id of the sensor + uint32 id = 3; + + /// \brief Name of the parent, usually a link or joint. + string parent = 4; + + /// \brief Id of the parent, usually a link or joint. + uint32 parent_id = 5; + + /// \brief Sensor type + string type = 6; + + /// \brief True indicates that the sensor should always + /// produce data, instead of producing data only when + /// a consumer is connected to the data topic + bool always_on = 7; + + /// \brief Refresh rate + double update_rate = 8; + + /// \brief Sensor pose + Pose pose = 9; + + /// \brief Description of a camera sensor + CameraSensor camera = 10; + + /// \brief Description of a contact sensor + ContactSensor contact = 11; + + /// \brief True value indicates that sensor data should be + /// visualized in the GUI + bool visualize = 12; + + /// \brief Topic on which sensor data is published + string topic = 13; + + /// \brief Description of a logical camera sensor + LogicalCameraSensor logical_camera = 14; + + /// \brief Description of a gps sensor + /// TODO(chapulina) Migrate to NavSat + GPSSensor gps = 15; + + /// \brief Description of an IMU sensor + IMUSensor imu = 16; + + /// \brief Description of a Magnetometer sensor + MagnetometerSensor magnetometer = 17; + + /// \brief Description of an Altimeter sensor. + AltimeterSensor altimeter = 18; + + /// \brief Description of an Air Pressure sensor. + AirPressureSensor air_pressure = 19; + + /// \brief Description of a lidar sensor + LidarSensor lidar = 20; +} diff --git a/proto/gz/msgs/server_control.proto b/proto/gz/msgs/server_control.proto new file mode 100644 index 000000000..6986481c8 --- /dev/null +++ b/proto/gz/msgs/server_control.proto @@ -0,0 +1,41 @@ +/* + * 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 = "ServerControlProtos"; + +/// \ingroup gz.msgs +/// \interface ServerControl +/// \brief A message that allows for control of the server functions + +import "gz/msgs/header.proto"; + +message ServerControl +{ + /// \brief Optional header data + Header header = 1; + + string save_world_name = 2; + string save_filename = 3; + string open_filename = 4; + bool new_world = 5; + bool stop = 6; + bool clone = 7; + uint32 new_port = 8; +} diff --git a/proto/gz/msgs/sky.proto b/proto/gz/msgs/sky.proto new file mode 100644 index 000000000..bff84752e --- /dev/null +++ b/proto/gz/msgs/sky.proto @@ -0,0 +1,47 @@ +/* + * 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 = "SkyProtos"; + +/// \ingroup gz.msgs +/// \interface Sky +/// \brief Information about the sky + +import "gz/msgs/color.proto"; +import "gz/msgs/header.proto"; + +message Sky +{ + /// \brief Optional header data + Header header = 1; + + double time = 2; + double sunrise = 3; + double sunset = 4; + + double wind_speed = 5; + double wind_direction = 6; + Color cloud_ambient = 7; + double humidity = 8; + double mean_cloud_size = 9; + + /// \brief Cubemap URI for the sky, usually a .dds file. + string cubemap_uri = 10; +} diff --git a/proto/gz/msgs/spheregeom.proto b/proto/gz/msgs/spheregeom.proto new file mode 100644 index 000000000..1acdabbfe --- /dev/null +++ b/proto/gz/msgs/spheregeom.proto @@ -0,0 +1,36 @@ +/* + * 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 = "SphereGeomProtos"; + +/// \ingroup gz.msgs +/// \interface SphereGeom +/// \brief Information about a sphere geometry + +import "gz/msgs/header.proto"; + +message SphereGeom +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Radius of the sphere. + double radius = 2; +} diff --git a/proto/gz/msgs/surface.proto b/proto/gz/msgs/surface.proto new file mode 100644 index 000000000..2d6efc1ec --- /dev/null +++ b/proto/gz/msgs/surface.proto @@ -0,0 +1,48 @@ +/* + * 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 = "SurfaceProtos"; + +/// \ingroup gz.msgs +/// \interface Surface +/// \brief Information about a surface element + +import "gz/msgs/header.proto"; +import "gz/msgs/friction.proto"; + +message Surface +{ + /// \brief Optional header data + Header header = 1; + + Friction friction = 2; + double restitution_coefficient = 3; + double bounce_threshold = 4; + double soft_cfm = 5; + double soft_erp = 6; + double kp = 7; + double kd = 8; + double max_vel = 9; + double min_depth = 10; + bool collide_without_contact = 11; + uint32 collide_without_contact_bitmask = 12; + uint32 collide_bitmask = 13; + double elastic_modulus = 14; +} diff --git a/proto/gz/msgs/track_visual.proto b/proto/gz/msgs/track_visual.proto new file mode 100644 index 000000000..85dd7db4e --- /dev/null +++ b/proto/gz/msgs/track_visual.proto @@ -0,0 +1,63 @@ +/* + * 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 = "TrackVisualProtos"; + +/// \ingroup gz.msgs +/// \interface TrackVisual +/// \brief Message for a tracking a rendering::Visual with a rendering::Camera + +import "gz/msgs/vector3d.proto"; +import "gz/msgs/header.proto"; + +message TrackVisual +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Name of the visual to track + string name = 2; + + /// \brief Id of the visual to track + uint32 id = 3; + + /// \brief True to have the tracking camera inherit the orientation of + /// the tracked visual. + bool inherit_orientation = 4; + + /// \brief Minimum follow distance + double min_dist = 5; + + /// \brief Maximum follow distance + double max_dist = 6; + + /// \brief If set to true, the position of the camera is fixed. + bool static = 7; + + /// \brief If set to true, the position of the camera is relative to the + /// model reference frame. + bool use_model_frame = 8; + + /// \brief Position of the camera. + Vector3d xyz = 9; + + /// \brief If set to true, the camera inherits the yaw rotation of the model. + bool inherit_yaw = 10; +} diff --git a/proto/gz/msgs/visual.proto b/proto/gz/msgs/visual.proto new file mode 100644 index 000000000..ad37b23aa --- /dev/null +++ b/proto/gz/msgs/visual.proto @@ -0,0 +1,92 @@ +/* + * 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 = "VisualProtos"; + +/// \ingroup gz.msgs +/// \interface Visual +/// \brief A message containing visual information for rendering::Visual + +import "gz/msgs/header.proto"; +import "gz/msgs/pose.proto"; +import "gz/msgs/geometry.proto"; +import "gz/msgs/material.proto"; +import "gz/msgs/plugin.proto"; +import "gz/msgs/vector3d.proto"; + +message Visual +{ + /// \brief Optional meta information for the visual. The information + /// contained within this element should be used to provide additional + /// feedback to an end user. + message Meta + { + /// \brief The layer in which this visual is displayed. The layer number + /// is useful for programs, such as Gazebo, that put visuals in different + /// layers for enhanced visualization. + int32 layer = 1; + } + + enum Type + { + /// \brief Entity visual + ENTITY = 0; + /// \brief Model visual + MODEL = 1; + /// \brief Link visual + LINK = 2; + /// \brief Visual visual + VISUAL = 3; + /// \brief Collision visual + COLLISION = 4; + /// \brief Sensor visual + SENSOR = 5; + /// \brief GUI visual + GUI = 6; + /// \brief Physics data visual + PHYSICS = 7; + } + + /// \brief Optional header data + Header header = 1; + + string name = 2; + uint32 id = 3; + string parent_name = 4; + uint32 parent_id = 5; + bool cast_shadows = 6; + double transparency = 7; + double laser_retro = 8; + Pose pose = 9; + Geometry geometry = 10; + Material material = 11; + + bool visible = 12; + bool delete_me = 13; + bool is_static = 14; + repeated Plugin plugin = 15; + Vector3d scale = 16; + + /// \brief Option meta information associated with this visual. + Meta meta = 17; + + /// \brief Type of visual. + Type type = 18; +} diff --git a/proto/gz/msgs/world_control.proto b/proto/gz/msgs/world_control.proto new file mode 100644 index 000000000..6977d0696 --- /dev/null +++ b/proto/gz/msgs/world_control.proto @@ -0,0 +1,44 @@ +/* + * 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 = "WorldControlProtos"; + +/// \ingroup gz.msgs +/// \interface WorldControl +/// \brief A message that allows for control of world functions + +import "gz/msgs/world_reset.proto"; +import "gz/msgs/header.proto"; +import "gz/msgs/time.proto"; + +message WorldControl +{ + /// \brief Optional header data + Header header = 1; + + bool pause = 2; + bool step = 3; + uint32 multi_step = 4; + WorldReset reset = 5; + uint32 seed = 6; + + // \brief A simulation time in the future to run to and then pause. + Time run_to_sim_time = 7; +} diff --git a/proto/gz/msgs/world_reset.proto b/proto/gz/msgs/world_reset.proto new file mode 100644 index 000000000..b7e2c1ac3 --- /dev/null +++ b/proto/gz/msgs/world_reset.proto @@ -0,0 +1,37 @@ +/* + * 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 = "WorldResetProtos"; + +/// \ingroup gz.msgs +/// \interface WorldReset +/// \brief A message that controls how the world is reset + +import "gz/msgs/header.proto"; + +message WorldReset +{ + /// \brief Optional header data + Header header = 1; + + bool all = 2; + bool time_only = 3; + bool model_only = 4; +} diff --git a/proto/gz/msgs/world_stats.proto b/proto/gz/msgs/world_stats.proto new file mode 100644 index 000000000..20ad459a7 --- /dev/null +++ b/proto/gz/msgs/world_stats.proto @@ -0,0 +1,77 @@ +/* + * 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 = "WorldStatsProtos"; + +/// \ingroup gz.msgs +/// \interface WorldStatistics +/// \brief A message statiscs about a world + +import "gz/msgs/log_playback_stats.proto"; +import "gz/msgs/time.proto"; +import "gz/msgs/header.proto"; + +message WorldStatistics +{ + /// \brief Optional header data + Header header = 1; + + /// \brief Current simulation time + Time sim_time = 2; + + /// \brief Total time spent paused + Time pause_time = 3; + + /// \brief Current real time + Time real_time = 4; + + /// \brief Whether currently paused + bool paused = 5; + + /// \brief Current iteration count + uint64 iterations = 6; + + /// \brief Total number of models in the world + int32 model_count = 7; + + /// \brief Statistics for log playback + LogPlaybackStatistics log_playback_stats = 8; + + /// \brief This factor expresses how much real time elapses with each step + /// of simulation time. + /// E.g.: 0.5 means that 1 second in real time takes 2 seconds in simulation. + double real_time_factor = 9; + + /// \brief Iteration step size. It's zero when paused. + Time step_size = 10; + + /// \brief True if the simulator is stepping, as opposed to running. This + /// field can be ignored if the paused field is true. + /// + /// When `paused == true`, then simulation is paused and not updating at all + /// and the `stepping` field can be ignored. + /// + /// When `paused == false` and + /// * `stepping == true` then Simulation is updating for a fixed number of + /// iterations, or + /// * `stepping == false` then Simulation is running for an unbounded + /// number of iterations. + bool stepping = 11; +} diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 6e4fc869b..e41305f80 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -50,6 +50,7 @@ gz_build_tests(TYPE UNIT LIB_DEPS gz-common${GZ_COMMON_VER}::events gz-math${GZ_MATH_VER}::gz-math${GZ_MATH_VER} + gz-gui${PROJECT_VERSION_MAJOR}-msgs TINYXML2::TINYXML2 TEST_LIST gtest_targets diff --git a/src/plugins/CMakeLists.txt b/src/plugins/CMakeLists.txt index 36ede3212..e064b68d1 100644 --- a/src/plugins/CMakeLists.txt +++ b/src/plugins/CMakeLists.txt @@ -76,7 +76,7 @@ function(gz_gui_add_plugin plugin_name) SOURCES ${gz_gui_add_plugin_SOURCES} QT_HEADERS ${gz_gui_add_plugin_QT_HEADERS} PUBLIC_LINK_LIBS ${gz_gui_add_plugin_PUBLIC_LINK_LIBS} - PRIVATE_LINK_LIBS ${gz_gui_add_plugin_PRIVATE_LINK_LIBS} gz-plugin${GZ_PLUGIN_VER}::register + PRIVATE_LINK_LIBS ${gz_gui_add_plugin_PRIVATE_LINK_LIBS} gz-plugin${GZ_PLUGIN_VER}::register gz-gui${PROJECT_VERSION_MAJOR}-msgs ) if(gz_gui_add_plugin_TEST_SOURCES) @@ -87,6 +87,7 @@ function(gz_gui_add_plugin plugin_name) ${GZ-GUI_LIBRARIES} TINYXML2::TINYXML2 ${plugin_name} + gz-gui${PROJECT_VERSION_MAJOR}-msgs INCLUDE_DIRS # Used to make internal source file headers visible to the unit tests ${CMAKE_CURRENT_SOURCE_DIR} diff --git a/src/plugins/camera_tracking/CameraTracking.cc b/src/plugins/camera_tracking/CameraTracking.cc index 88f183972..8b0427b3f 100644 --- a/src/plugins/camera_tracking/CameraTracking.cc +++ b/src/plugins/camera_tracking/CameraTracking.cc @@ -18,6 +18,7 @@ #include #include +#include #include #include diff --git a/src/plugins/image_display/ImageDisplay.cc b/src/plugins/image_display/ImageDisplay.cc index 80de5232e..0a9afaa07 100644 --- a/src/plugins/image_display/ImageDisplay.cc +++ b/src/plugins/image_display/ImageDisplay.cc @@ -26,7 +26,7 @@ #include #include -#include +#include #include #include diff --git a/src/plugins/navsat_map/CMakeLists.txt b/src/plugins/navsat_map/CMakeLists.txt index 887601742..b9ab0d47e 100644 --- a/src/plugins/navsat_map/CMakeLists.txt +++ b/src/plugins/navsat_map/CMakeLists.txt @@ -3,5 +3,43 @@ gz_gui_add_plugin(NavSatMap NavSatMap.cc QT_HEADERS NavSatMap.hh + PRIVATE_LINK_LIBS gz-sensors8::gz-sensors8-msgs ) +# Get all propreties that cmake supports +if(NOT CMAKE_PROPERTY_LIST) + execute_process(COMMAND cmake --help-property-list OUTPUT_VARIABLE CMAKE_PROPERTY_LIST) + + # Convert command output into a CMake list + string(REGEX REPLACE ";" "\\\\;" CMAKE_PROPERTY_LIST "${CMAKE_PROPERTY_LIST}") + string(REGEX REPLACE "\n" ";" CMAKE_PROPERTY_LIST "${CMAKE_PROPERTY_LIST}") + list(REMOVE_DUPLICATES CMAKE_PROPERTY_LIST) +endif() + +function(print_properties) + message("CMAKE_PROPERTY_LIST = ${CMAKE_PROPERTY_LIST}") +endfunction() + +function(print_target_properties target) + if(NOT TARGET ${target}) + message(STATUS "There is no target named '${target}'") + return() + endif() + + foreach(property ${CMAKE_PROPERTY_LIST}) + string(REPLACE "" "${CMAKE_BUILD_TYPE}" property ${property}) + + # Fix https://stackoverflow.com/questions/32197663/how-can-i-remove-the-the-location-property-may-not-be-read-from-target-error-i + if(property STREQUAL "LOCATION" OR property MATCHES "^LOCATION_" OR property MATCHES "_LOCATION$") + continue() + endif() + + get_property(was_set TARGET ${target} PROPERTY ${property} SET) + if(was_set) + get_target_property(value ${target} ${property}) + message("${target} ${property} = ${value}") + endif() + endforeach() +endfunction() + +print_target_properties(gz-sensors8::gz-sensors8-msgs) diff --git a/src/plugins/point_cloud/PointCloud.cc b/src/plugins/point_cloud/PointCloud.cc index 328b06616..4353efb99 100644 --- a/src/plugins/point_cloud/PointCloud.cc +++ b/src/plugins/point_cloud/PointCloud.cc @@ -15,6 +15,8 @@ * */ +#include +#include #include "gz/msgs/pointcloud_packed.pb.h" #include diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index 55170ef0c..5c58f2a29 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -9,5 +9,6 @@ gz_build_tests( ${PROJECT_NAME}_test_helpers gz-plugin${GZ_PLUGIN_VER}::loader gz-rendering${GZ_RENDERING_VER}::gz-rendering${GZ_RENDERING_VER} + gz-gui${PROJECT_VERSION_MAJOR}-msgs Qt5::Test )