Skip to content
This repository has been archived by the owner on Mar 23, 2024. It is now read-only.

Add boat simulator custom interfaces #9

Merged
merged 13 commits into from
Aug 31, 2023
38 changes: 31 additions & 7 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,15 +5,16 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
# Find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)
# find_package(geometry_msgs REQUIRED)

# Add more dependencies manually with: find_package(<dependency> REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
# Common custom messages
set(common_msg
# external
"msg/AISShips.msg"
"msg/Batteries.msg"
Expand All @@ -31,9 +32,32 @@ rosidl_generate_interfaces(${PROJECT_NAME}
"msg/HelperHeading.msg"
"msg/HelperLatLon.msg"
"msg/HelperSpeed.msg"
)

# Boat simulator custom messages
set(simulator_msg
# external
"msg/SimWorldState.msg"

# internal
"msg/SimHelperEnvironment.msg"
"msg/SimHelperKinematics.msg"
)

# Boat simulator custom actions
set(simulator_action
"action/SimRudderActuation.action"
"action/SimSailTrimTabActuation.action"
)

rosidl_generate_interfaces(${PROJECT_NAME}
# Add custom messages
${common_msg}
${simulator_msg}
${simulator_action}

# Add packages that above messages depend on below if needed
# DEPENDENCIES geometry_msgs
DEPENDENCIES std_msgs geometry_msgs
)

if(BUILD_TESTING)
Expand Down
44 changes: 38 additions & 6 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,19 @@
# Custom Interfaces

UBC Sailbot's custom interfaces ROS package.
UBC Sailbot's custom interfaces ROS package. To add `custom_interfaces` to another ROS package, follow the instructions
[here](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Custom-ROS2-Interfaces.html#test-the-new-interfaces).

## External Interfaces
The terminology that we use in this document are the following:

Used to communicate data between ROS packages.
- **External Interface**: An interface used to communicate data between nodes and ROS packages.
- **Internal Interface**: An interface used to standardize conventions across external interfaces. Standards are
documented in the `.msg` or `.srv` file associated with that interface.

## Project-wide Interfaces

ROS messages and services used across many ROS packages in the project.

### Project-wide External Interfaces

| Topic | Type | Publisher | Subscriber |
| ---------------------- | -------------- | ------------------------ | ------------------------------------------- |
Expand All @@ -19,9 +28,7 @@ Used to communicate data between ROS packages.
| `mock_wind_sensors` | WindSensors | Boat Simulator | CAN Transceiver |
| `wind_sensors` | WindSensors | CAN Transceiver | Local/Remote Transceiver |

## Internal Interfaces

Used to standardize conventions across external interfaces.
### Project-wide Internal Interfaces

| Interface | Used In |
| ------------------- | ---------------------------------- |
Expand All @@ -32,6 +39,30 @@ Used to standardize conventions across external interfaces.
| HelperLatLon | GlobalPath, GPS, HelperAISShip |
| HelperSpeed | GPS, HelperAISShip, WindSensor |

## Boat Simulator Interfaces

ROS messages and services used in our [boat simulator](https://github.com/UBCSailbot/boat_simulator).

### Boat Simulator External Interfaces

| Topic | Type | Publisher | Subscriber |
| ---------------------- | -------------- | ------------------------ | ------------------------------------------- |
| `mock_kinematics` | SimWorldState | Simulator Physics Engine | Simulator Visualizer |

### Boat Simulator Internal Interfaces

| Interface | Used In |
| -------------------- | ---------------------------------- |
| SimHelperEnvironment | SimWorldState |
| SimHelperKinematics | SimWorldState |
DFriend01 marked this conversation as resolved.
Show resolved Hide resolved

### Boat Simulator Actions

| Action | Client Node | Server Node |
| ----------------------- | ------------------------ | ------------------------------ |
| SimRudderActuation | Simulator Physics Engine | Simulator Low Level Controller |
| SimSailTrimTabActuation | Simulator Physics Engine | Simulator Low Level Controller |

## Resources

### Common Interfaces
Expand All @@ -50,3 +81,4 @@ These interfaces can be used in this repository or as a reference for ideas and
| visualization_msgs | Reference |

For more detail on the usefulness of each package, see [this issue comment](https://github.com/UBCSailbot/custom_interfaces/issues/3#issuecomment-1626875658).
If you are interested in creating your own custom message or service, see the [ROS Humble documentation](https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Custom-ROS2-Interfaces.html).
12 changes: 12 additions & 0 deletions action/SimRudderActuation.action
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
# Request: The desired heading to turn to
DesiredHeading desired_heading
---
# Result: The absolute angular distance between the current and desired heading
# Units: degrees
# Range: [0, 180]
float32 remaining_angular_distance
---
# Feedback: The rudder angle with respect to the boat
# Units: degrees, 0° south, increases CW
# Range: [-90, 90]
float32 rudder_angle
14 changes: 14 additions & 0 deletions action/SimSailTrimTabActuation.action
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
# Request: The desired position to turn to
# Units: degrees, 0° south, increases CW
# Range: [-90, 90] (TODO: Confirm desireable range with MECH team)
float32 desired_angular_position
---
# Result: The absolute angular distance between the current and desired heading
# Units: degrees
# Range: [0, 180] (TODO: Conform desireable range with MECH team)
float32 remaining_angular_distance
---
# Feedback: The trim tab angle with respect to the wingsail
# Units: degrees, 0° south, increases CW
# Range: [-90, 90] (TODO: Confirm desireable range with MECH team)
float32 current_angular_position
13 changes: 13 additions & 0 deletions msg/SimHelperEnvironment.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
# Direction that the wind is going TOWARDS. Note that this is difference from the WindSensor type
# in custom_interfaces, where WindSensor.direction gives us the direction where the wind is coming
# FROM (basically a 180 degree phase shift in the velocity direction).
#
# Contains both linear and angular components of the velocity, but the angular component is not used.
# Linear Velocity Unit: km/hr
geometry_msgs/Twist wind_velocity

# Direction that the current is going TOWARDS.
#
# Contains both linear and angular components of the velocity, but the angular component is not used.
# Linear Velocity Unit: km/hr
geometry_msgs/Twist current_velocity
18 changes: 18 additions & 0 deletions msg/SimHelperKinematics.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
# Contains both position and orientation (in quaternions, following a East-North-Up convention)
# Position Unit: km, distance from the origin
geometry_msgs/Pose pose

# Contains both linear and angular components of velocity
# Linear Velocity Unit: km/hr
# Angular Velocity Unit: rad/sec
geometry_msgs/Twist velocity

# Contains both linear and angular components of acceleration
# Linear Acceleration Unit: km/hr^2
# Angular Acceleration Unit: rad/sec^2
geometry_msgs/Accel acceleration

# Contains both linear and angular components of the net force
# Force Unit: N
# Torque Unit: N*m
geometry_msgs/Wrench net_wrench
14 changes: 14 additions & 0 deletions msg/SimWorldState.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
# GPS data with respect to the Earth
GPS global_gps

# Kinematics data with respect to the Earth
SimHelperKinematics global_reference_kinematics

# Kinematics data with respect to the boat
SimHelperKinematics relative_reference_kinematics

# Data from external factors outside the boat
SimHelperEnvironment environment

# Timestamp
std_msgs/Header header
5 changes: 4 additions & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,10 @@
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<!-- <depend>geometry_msgs</depend> -->
<depend>action_msgs</depend>
<depend>geometry_msgs</depend>
<depend>std_msgs</depend>

<buildtool_depend>rosidl_default_generators</buildtool_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>
Expand Down