Skip to content

Updates for 24.04/Jazzy/Harmonic #92

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 15 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
73 changes: 73 additions & 0 deletions docs/docs/ROS2/cpp_api.md
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
- power_callback
- trefoil_callback
- powerbuoy_callback
- latent_callback (SIM ONLY)

Template argument: **ControllerImplCRTP** The concrete controller class that inherits from this
interface. It must implement any callbacks or parameter-setting routines it needs.
Expand Down Expand Up @@ -120,6 +121,19 @@ public void Interface<ControllerImplCRTP>(const std::string & node_name, const b
**check_for_services** If true, attempt to verify service availability before use.


### spin

```cpp
public void spin()
```

**brief** Sets up a `MultiThreadedExecutor` and spins the node (blocking).

If you need non-blocking control over program flow, you may skip calling this function, but a
`MultiThreadedExecutor` is required for this node. You may call non-blocking spin functions of a
`MultiThreadedExecutor` in your own loop.


### use_sim_time

```cpp
Expand Down Expand Up @@ -276,6 +290,54 @@ public shared_future send_pc_retract_command(const float & retract)
**return** A future containing the service response.


### get_inc_wave_height

```cpp
public buoy_interfaces::srv::IncWaveHeight::Response::SharedPtr get_inc_wave_height(
const float x,
const float y,
const float t,
const bool use_buoy_origin = false,
const bool use_relative_time = false
)
```

*Defined at buoy_api_cpp/include/buoy_api/interface.hpp#1164*

**brief** Get incident wave height at a single location and time

**x** float meters, x component of wave height location
**y** float meters, y component of wave height location
**t** float seconds, sim time to evaluate wave height
**use_buoy_origin** boolean, (x,y) are relative to buoy location
**use_relative_time** boolean, t is relative to current sim time

**return** vector of IncWaveHeight data (with a single index)

```cpp
public buoy_interfaces::srv::IncWaveHeight::Response::SharedPtr get_inc_wave_height(
const std::vector<float> x,
const std::vector<float> y,
const std::vector<float> t,
const bool use_buoy_origin = false,
const bool use_relative_time = false,
const float timeout = 2.0,
const bool use_callback = false
)
```

**brief** Get incident wave height at multiple locations and times

**x** std::vector<float> meters, x component of wave height location
**y** std::vector<float> meters, y component of wave height location
**t** std::vector<float> seconds, sim time to evaluate wave height
**use_buoy_origin** boolean, all (x,y) are relative to buoy location
**use_relative_time** boolean, all t are relative to current sim time

**return** vector of IncWaveHeight data
*/


### set_params

```cpp
Expand Down Expand Up @@ -363,3 +425,14 @@ protected void powerbuoy_callback(const buoy_interfaces::msg::PBRecord & )
**brief** Override this function to subscribe to /powerbuoy_data to receive PBRecord telemetry.

**data** Incoming PBRecord containing a slice of all microcontroller telemetry data.


### latent_callback

```cpp
protected void latent_callback(const buoy_interfaces::msg::LatentData & )
```
**brief** Override this function to subscribe to /latent_data to receive LatentData sim-only data.

**data** Incoming LatentData containing sim-only values e.g. losses, waves, etc.

53 changes: 53 additions & 0 deletions docs/docs/ROS2/python_api.md
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ one, a subscriber for that topic will not be set up:
- self.power_callback
- self.trefoil_callback
- self.powerbuoy_callback
- self.latent_callback (sim only)

<a id="buoy_api.interface.Interface.__init__"></a>

Expand All @@ -52,6 +53,20 @@ Initialize the Interface node.
- `wait_for_services` (`bool`): if True and if check_for_services, block until all services are available
- `kwargs`: additional keyword arguments forwarded to ROS 2 Node

<a id="buoy_api.interface.Interface.spin"></a>

#### spin

```python
def spin()
```

Sets up a `MultiThreadedExecutor` and spins the node (blocking).

If you need non-blocking control over program flow, you may skip calling this function, but a
`MultiThreadedExecutor` is required for this node. You may call non-blocking spin functions of a
`MultiThreadedExecutor` in your own loop.

<a id="buoy_api.interface.Interface.use_sim_time"></a>

#### use\_sim\_time
Expand Down Expand Up @@ -218,6 +233,30 @@ Set additional damping gain in the piston retract direction.
- `retract` (`float`): additional damping gain for retraction
- `blocking` (`bool`): if True, wait for the service call to complete

<a id="buoy_api.interface.Interface.get_inc_wave_height"></a>

#### get\_inc\_wave\_height

```python
def get_inc_wave_height(self, x, y, t, use_buoy_origin, use_relative_time, timeout=2.0)
```

Request incident wave height at specific location(s) and time(s).

**Arguments**:
- `x` (`float` or `list`): x position(s) of desired wave height(s)
- `y` (`float` or `list`): y position(s) of desired wave height(s)
- `t` (`float` or `list`): t time(s) in seconds of sim time of desired wave height(s)
- `use_buoy_origin` (`bool`): if True, x and y are relative to buoy origin
- `use_relative_time` (`bool`): if True, desired time(s) are relative to current sim time
else, time(s) will be absolute sim time
- `timeout` (`float`): if not None, wait for timeout sec for the service call to complete
else, wait forever

**Returns**:
- `list` of `IncWaveHeight` data


<a id="buoy_api.interface.Interface.set_params"></a>

#### set\_params
Expand Down Expand Up @@ -314,3 +353,17 @@ PBRecord contains a slice of all microcontroller's telemetry data

- `data`: incoming PBRecord

<a id="buoy_api.interface.Interface.latent_callback"></a>

#### latent\_callback

```python
def latent_callback(self, data)
```

Override this function to subscribe to /latent_data to receive sim-only LatentData.

**Arguments**:

- `data`: incoming LatentData

8 changes: 4 additions & 4 deletions docs/docs/Tutorials/Install/Install_docker.md
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,12 @@ MBARI maintains Docker images for the two most recent releases on their DockerHu

1. Get `run.bash` script.
```
git clone -b main https://github.com/osrf/mbari_wec.git
git clone -b andermi/jazzy_harmonic https://github.com/osrf/mbari_wec.git
cd ~/mbari_wec/docker/
```
Or
```
wget https://raw.githubusercontent.com/osrf/mbari_wec/main/docker/run.bash
wget https://raw.githubusercontent.com/osrf/mbari_wec/andermi/jazzy_harmonic/docker/run.bash
chmod +x run.bash
```

Expand All @@ -53,7 +53,7 @@ is convenient if you would like to make any changes.

1. Clone the mbari_wec repository to download the latest Dockerfile.
```
git clone -b main https://github.com/osrf/mbari_wec.git
git clone -b andermi/jazzy_harmonic https://github.com/osrf/mbari_wec.git
cd ~/mbari_wec/docker/
```

Expand Down Expand Up @@ -115,4 +115,4 @@ collected in the sim will also be the same ROS 2 messages collected on the physi
```

The simulation software should now be available. To run and test, proceed to the
[Run the Simulator](../../../tutorials/#running-the-simulator) tutorial series.
[Run the Simulator](../../tutorials.md#running-the-simulator) tutorial series.
Loading