Skip to content

Commit

Permalink
[ros2] new package ros_ign_interfaces, provide some Ignition-specific…
Browse files Browse the repository at this point in the history
… ROS messages. (#152)

* add new package ros_ign_interfaces,provide some Ignition-specific ros .msg and .srv files

Signed-off-by: gezp <[email protected]>

* modify to match ign-msgs

Signed-off-by: gezp <[email protected]>

* add author info

Signed-off-by: gezp <[email protected]>

* modify comments

Signed-off-by: gezp <[email protected]>

* update code and doc style

Signed-off-by: gezp <[email protected]>
  • Loading branch information
gezp authored and chapulina committed Jul 19, 2021
1 parent 7409934 commit cdec9ce
Show file tree
Hide file tree
Showing 14 changed files with 147 additions and 0 deletions.
4 changes: 4 additions & 0 deletions ros_ign_interfaces/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package ros_ign_interfaces
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

42 changes: 42 additions & 0 deletions ros_ign_interfaces/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
cmake_minimum_required(VERSION 3.5)
project(ros_ign_interfaces)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

find_package(ament_cmake REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)

set(msg_files
"msg/Contact.msg"
"msg/Contacts.msg"
"msg/Entity.msg"
"msg/EntityFactory.msg"
"msg/WorldControl.msg"
"msg/WorldReset.msg"
)

set(srv_files
"srv/ControlWorld.srv"
"srv/DeleteEntity.srv"
"srv/SetEntityPose.srv"
"srv/SpawnEntity.srv"
)

rosidl_generate_interfaces(${PROJECT_NAME}
${msg_files}
${srv_files}
DEPENDENCIES builtin_interfaces std_msgs geometry_msgs
ADD_LINTER_TESTS
)

ament_export_dependencies(rosidl_default_runtime)
ament_package()
20 changes: 20 additions & 0 deletions ros_ign_interfaces/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
# Message and service data structures for interacting with Ignition from ROS2

This package currently contains some Ignition-specific ROS message and service data structures (.msg and .srv)

## Messages (.msg)

* [Contact](msg/Contact.msg): related to [ignition::msgs::Contact](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/contact.proto). Contant info bewteen collisions in Ignition Gazebo.
* [Contacts](msg/Contacts.msg): related to [ignition::msgs::Contacts](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/contacts.proto).a list of contact.
* [Entity](msg/Entity.msg): related to [ignition::msgs::Entity](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/entity.proto). Entity of Ignition Gazebo.
* [EntityFactory](msg/EntityFactory.msg): related to [ignition::msgs::EntityFactory](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/entity_factory.proto). Message to create a new entity.
* [WorldControl](msg/WorldControl.msg): related to [ignition::msgs::WorldControl](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/world_control.proto). Message to control world of Ingition Gazebo.
* [WorldReset](msg/WorldReset.msg): related to [ignition::msgs::WorldReset](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/world_reset.proto). Reset time and model of simulation.

## Services (.srv)

* [ControlWorld](srv/ControlWorld.srv): Control world of Ignition Gazebo,for example,pasue,pasue with multiple steps,resume,etc.
* [DeleteEntity](srv/DeleteEntity.srv): Delete Entity in Ignition Gazebo
* [SetEntityPose](srv/SetEntityPose.srv): Set pose of Entity in Ignition Gazebo
* [SpawnEntity](srv/SpawnEntity.srv): Spawn a Entity in Ignition Gazebo

6 changes: 6 additions & 0 deletions ros_ign_interfaces/msg/Contact.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
ros_ign_interfaces/Entity collision1 # Contact collision1
ros_ign_interfaces/Entity collision2 # Contact collision2
geometry_msgs/Vector3[] positions # List of contact position
geometry_msgs/Vector3[] normals # List of contact normals
float64[] depths # List of penetration depths
geometry_msgs/Wrench[] wrenches # List of forces/torques
2 changes: 2 additions & 0 deletions ros_ign_interfaces/msg/Contacts.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
std_msgs/Header header # Time stamp
ros_ign_interfaces/Contact[] contacts # List of contacts
13 changes: 13 additions & 0 deletions ros_ign_interfaces/msg/Entity.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
# Entity type: constant definition
uint8 NONE = 0
uint8 LIGHT = 1
uint8 MODEL = 2
uint8 LINK = 3
uint8 VISUAL = 4
uint8 COLLISION = 5
uint8 SENSOR = 6
uint8 JOINT = 7

uint64 id # Entity unique identifier accross all types. Defaults to 0
string name # Entity name, which is not guaranteed to be unique.
uint8 type # Entity type.
11 changes: 11 additions & 0 deletions ros_ign_interfaces/msg/EntityFactory.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
string name # New name for the entity, overrides the name on the SDF
bool allow_renaming false # Whether the server is allowed to rename the entity in case of
# overlap with existing entities.

# Only one method is supported at a time (sdf,sdf_filename,clone_name)
string sdf # SDF description in string format
string sdf_filename # Full path to SDF file.
string clone_name # Name of entity to clone

geometry_msgs/Pose pose # Pose where the entity will be spawned in the world.
string relative_to "world" # Pose is defined relative to the frame of this entity.
7 changes: 7 additions & 0 deletions ros_ign_interfaces/msg/WorldControl.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
bool pause # Paused state.
bool step #
uint32 multi_step 0 # Paused after stepping multi_step.
ros_ign_interfaces/WorldReset reset #
uint32 seed #
builtin_interfaces/Time run_to_sim_time # A simulation time in the future to run to and
# then pause.
3 changes: 3 additions & 0 deletions ros_ign_interfaces/msg/WorldReset.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
bool all false # Reset time and model
bool time_only false # Reset time only
bool model_only false # Reset model only
26 changes: 26 additions & 0 deletions ros_ign_interfaces/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
<package format="3">
<name>ros_ign_interfaces</name>
<version>0.233.1</version>
<description>Message and service data structures for interacting with Ignition from ROS2.</description>
<license>Apache 2.0</license>
<maintainer email="[email protected]">Louise Poubel</maintainer>
<maintainer email="[email protected]">Zhenpeng Ge</maintainer>
<author>Zhenpeng Ge</author>
<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>rosidl_default_generators</buildtool_depend>

<build_depend>builtin_interfaces</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>

<exec_depend>builtin_interfaces</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>rosidl_default_runtime</exec_depend>

<test_depend>ament_lint_common</test_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
3 changes: 3 additions & 0 deletions ros_ign_interfaces/srv/ControlWorld.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
ros_ign_interfaces/WorldControl world_control # Message to Control world in Ignition Gazebo
---
bool success # Return true if control is successful.
3 changes: 3 additions & 0 deletions ros_ign_interfaces/srv/DeleteEntity.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
ros_ign_interfaces/Entity entity # Ignition Gazebo entity to be deleted.
---
bool success # Return true if deletion is successful.
4 changes: 4 additions & 0 deletions ros_ign_interfaces/srv/SetEntityPose.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
ros_ign_interfaces/Entity entity # Ignition Gazebo entity.
geometry_msgs/Pose pose # Pose of entity.
---
bool success # Return true if set successfully.
3 changes: 3 additions & 0 deletions ros_ign_interfaces/srv/SpawnEntity.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
ros_ign_interfaces/EntityFactory entity_factory # Message to create a new entity
---
bool success # Return true if spawned successfully.

0 comments on commit cdec9ce

Please sign in to comment.