diff --git a/CMakeLists.txt b/CMakeLists.txt index db73937..3506741 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -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( REQUIRED) -# find_package(geometry_msgs REQUIRED) + +# Add more dependencies manually with: find_package( 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" @@ -31,9 +32,28 @@ 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" +) + +# 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) diff --git a/README.md b/README.md index 06fa42f..ba9158a 100644 --- a/README.md +++ b/README.md @@ -1,12 +1,21 @@ # 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. -| Topic | Type | Publisher | Subscriber | +## Project-wide Interfaces + +ROS messages and services used across many ROS packages in the project. + +### Project-wide External Interfaces + +| Topic | Type | Publisher | Subscriber(s) | | ---------------------- | -------------- | ------------------------ | ------------------------------------------- | | `ais_ships` | AISShips | AIS Receiver | Local Pathfinding | | `batteries` | Batteries | CAN Transceiver | Local/Remote Transceiver | @@ -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 | | ------------------- | ---------------------------------- | @@ -32,6 +39,23 @@ 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(s) | +| ---------------------- | -------------- | ------------------------ | ------------------------------------------- | +| `mock_kinematics` | SimWorldState | Simulator Physics Engine | Simulator Visualizer | + +### 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 @@ -50,3 +74,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). diff --git a/action/SimRudderActuation.action b/action/SimRudderActuation.action new file mode 100644 index 0000000..2bb0fdb --- /dev/null +++ b/action/SimRudderActuation.action @@ -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 diff --git a/action/SimSailTrimTabActuation.action b/action/SimSailTrimTabActuation.action new file mode 100644 index 0000000..7dc3148 --- /dev/null +++ b/action/SimSailTrimTabActuation.action @@ -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 diff --git a/msg/SimWorldState.msg b/msg/SimWorldState.msg new file mode 100644 index 0000000..cf092a6 --- /dev/null +++ b/msg/SimWorldState.msg @@ -0,0 +1,24 @@ +# GPS data of the simulated with respect to the Earth (in the global reference frame). +GPS global_gps + +# Contains both position and orientation (in quaternions, following a East-North-Up convention) +# of the simulated boat with respect to the Earth (in the global reference frame). +# Position Unit: km, distance from the origin +geometry_msgs/Pose global_pose + +# 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 the linear component of the velocity. +# Linear Velocity Unit: km/hr +geometry_msgs/Vector3 wind_velocity + +# Direction that the current is going TOWARDS. +# +# Contains the linear component of the velocity. +# Linear Velocity Unit: km/hr +geometry_msgs/Vector3 current_velocity + +# Timestamp. Contains time since start in seconds and the frame number. +std_msgs/Header header diff --git a/package.xml b/package.xml index 833b1b8..c8bc92d 100644 --- a/package.xml +++ b/package.xml @@ -13,7 +13,10 @@ ament_lint_auto ament_lint_common - + action_msgs + geometry_msgs + std_msgs + rosidl_default_generators rosidl_default_runtime rosidl_interface_packages