From b3a38c04948ba39d944259eb77cccf934c2c7fb5 Mon Sep 17 00:00:00 2001 From: Teppo Kurki Date: Sat, 14 Dec 2024 19:57:39 +0200 Subject: [PATCH 1/2] feature: add Autopilot API --- .../plugins/autopilot_provider_plugins.md | 442 +++++++++- docs/src/develop/rest-api/autopilot_api.md | 369 ++++++++- docs/src/develop/rest-api/open_api.md | 2 +- docs/src/img/autopilot_provider.dia | Bin 0 -> 3183 bytes docs/src/img/autopilot_provider.svg | 705 ++++++++++++++++ packages/server-api/.gitignore | 1 + packages/server-api/package.json | 4 +- packages/server-api/src/autopilotapi.ts | 103 ++- packages/server-api/src/index.ts | 9 +- src/api/autopilot/index.ts | 770 ++++++++++++++++++ src/api/autopilot/openApi.json | 732 +++++++++++++++++ src/api/autopilot/openApi.ts | 8 + src/api/index.ts | 18 +- src/api/swagger.ts | 6 +- src/interfaces/plugins.ts | 26 +- 15 files changed, 3143 insertions(+), 52 deletions(-) create mode 100644 docs/src/img/autopilot_provider.dia create mode 100644 docs/src/img/autopilot_provider.svg create mode 100644 src/api/autopilot/index.ts create mode 100644 src/api/autopilot/openApi.json create mode 100644 src/api/autopilot/openApi.ts diff --git a/docs/src/develop/plugins/autopilot_provider_plugins.md b/docs/src/develop/plugins/autopilot_provider_plugins.md index b8692ab4e..94558389a 100644 --- a/docs/src/develop/plugins/autopilot_provider_plugins.md +++ b/docs/src/develop/plugins/autopilot_provider_plugins.md @@ -1,12 +1,442 @@ -# Autopilot Provider Plugins +# Autopilot Provider plugins -#### (Under Development) +_This document should be read in conjunction with the [SERVER PLUGINS](./server_plugin.md) document as it contains additional information regarding the development of plugins that implement the Signal K Autopilot API._ -_Note: This API is currently under development and the information provided here is likely to change._ +--- +## Overview -The Signal K server [Autopilot API](../rest-api/autopilot_api.md) will provide a common set of operations for interacting with autopilot devices and (like the Resources API) will rely on a "provider plugin" to facilitate communication with the autopilot device. +The Signal K Autopilot API defines endpoints under the path `/signalk/v2/api/vessels/self/autopilots` providing a way for all Signal K clients to perform common autopilot operations independent of the autopilot device in use. The API is defined in an [OpenAPI](/doc/openapi/?urls.primaryName=autopilot) document. -By de-coupling the operation requests from device communication provides the ability to support a wide variety of devices. +Requests made to the Autopilot API are received by the Signal K Server, where they are validated and an authorisation check performed, before being passed on to a **provider plugin** to action the request on the autopilot device. -[View the PR](https://github.com/SignalK/signalk-server/pull/1596) for more details. +This de-coupling of request handling and autopilot communication provides the flexibility to support a variety of autopilot devices and ensures interoperability and reliabilty. + +Autopilot API requests are passed to a **provider plugin** which will process and action the request facilitating communication with the autopilot device. + +The following diagram provides an overview of the Autopilot API architectue. + + + +_Autopilot API architecture_ + + +## Provider Plugins: + +An autopilot provider plugin is a Signal K server plugin that implements the **Autopilot Provider Interface** which: +- Tells server the autopilot devices provided for by the plugin +- Registers the methods used to action requests passed from the server to perform autopilot operations. + +The `AutopilotProvider` interface is defined in _`@signalk/server-api`_ + +Multiple providers can be registered and each provider can manage one or more autopilot devices. + + +**Note: An Autopilot Provider plugin MUST:** +- Implement all Autopilot API interface methods. +- Facilitate communication on the target autopilot device to send commands and retrieve both status and configuration information +- Ensure the `engaged` path attribute value is maintained to reflect the operational status of the autopilot. +- Map the `engage` and `disengage` operations to an appropriate autopilot device `state`. +- Set the state as `off-line` if the autopilot device is not connected or unreachable. +- Set the mode as `dodge` when the autopilot device is is in dodge mode. + + +### Registering as an Autopilot Provider + +A provider plugin must register itself with the Autopilot API during start up by calling the `registerAutopilotProvider`. + +The function has the following signature: + +```typescript +app.registerAutopilotProvider(provider: AutopilotProvider, devices: string[]) +``` +where: + +- `provider`: is a valid **AutopilotProvider** object +- `devices`: is an array of identifiers indicating the autopilot devices managed by the plugin. + +_Example: Plugin registering as an autopilot provider._ +```javascript +import { AutopilotProvider } from '@signalk/server-api' + +module.exports = function (app) { + + const plugin = { + id: 'mypluginid', + name: 'My autopilot Provider plugin' + } + + const autopilotProvider: AutopilotProvider = { + getData: (deviceId) => { return ... }, + getState: (deviceId) => { return ... }, + setState: (state, deviceId) => { ... }, + getMode: (deviceId) => { return ... }, + setMode: (mode, deviceId) => { ... }, + getTarget: (deviceId) => { return ... }, + setTarget(value, deviceId) => { ... }, + adjustTarget(value, deviceId) => { ... }, + engage: (deviceId) => { ... }, + disengage: (deviceId) => { ... }, + tack:(direction, deviceId) => { ... }, + gybe:(direction, deviceId) => { ... }, + dodge:(value, deviceId) => { ... } + } + + const pilots = ['pilot1', 'pilot2'] + + plugin.start = function(options) { + ... + try { + app.registerAutopilotProvider(autopilotProvider, pilots) + } + catch (error) { + // handle error + } + } + + return plugin +} +``` + +### Sending Updates and Notifications from Autopilot device + +The Autopilot API is responsible for sending both update and notification `deltas` to Signal K clients. + +Data received from an autopilot device, regardless of the communications protocol (NMEA2000, etc), should be sent to the Autopilot API by calling the `autopilotUpdate` interface method. + +This will ensure: +- Default pilot status is correctly maintained +- `steering.autopilot.*` both V1 and V2 deltas are sent + +**_Important! The values provided via `autopilotUpdate` will be sent in the relevant delta message, so ensure they are in the correct units (e.g. angles in radians, etc)._** + +The function has the following signature: + +```typescript +app.autopilotUpdate(deviceID: string, apInfo: {[key:string]: Value}) +``` +where: + +- `deviceId`: is the autopilot device identifier +- `appInfo`: object containing values keyed by attributes _(as defined in @signalk/server-api)_ + +_Example Update:_ +```javascript +app.autopilotUpdate('my-pilot', { + target: 1.52789, + mode: 'compass' +}) +``` + +Notifications / Alarms are sent using one of the normalised alarm names below as the path and a `Notification` as the value. + +- waypointAdvance +- waypointArrival +- routeComplete +- xte +- heading +- wind + +_Example Notification:_ +```javascript +app.autopilotUpdate('my-pilot', { + alarm: { + path: 'waypointAdvance', + value: { + state: 'alert' + method: ['sound'] + message: 'Waypoint Advance' + } + } +}) +``` + + +### Provider Methods: + +**`getData(deviceId)`**: This method returns an AutopilotInfo object containing the current data values and valid options for the supplied autopilot device identifier. + +- `deviceId:` identifier of the autopilot device to query. + +returns: `Promise<{AutopilotInfo}>` + +_Note: It is the responsibility of the autopilot provider plugin to map the value of `engaged` to the current `state`._ + + +_Example:_ +```javascript +// API request +GET /signalk/v2/api/vessels/self/autopilots/mypilot1 + +// AutopilotProvider method invocation +getData('mypilot1'); + +// Returns: +{ + options: { + states: [ + { + name: 'auto' // autopilot state name + engaged: true // actively steering + }, + { + name: 'standby' // autopilot state name + engaged: false // not actively steering + } + ] + modes: ['compass', 'gps', 'wind'] +}, + target: 0.326 + mode: 'compass' + state: 'auto' + engaged: true +} +``` + +--- +**`getState(deviceId)`**: This method returns the current state of the supplied autopilot device identifier. If the autopilot device is not connected or unreachable then `off-line` should be returned. + +- `deviceId:` identifier of the autopilot device to query. + +returns: `Promise<{string}>` + +_Example:_ +```javascript +// API request +GET /signalk/v2/api/vessels/self/autopilots/mypilot1/state + +// AutopilotProvider method invocation +getState('mypilot1'); + +// Returns: +'auto' +``` + +--- +**`setState(state, deviceId?)`**: This method sets the autopilot device with the supplied identifier to the supplied state value. + +- `state:` state value to set. Must be a valid state value. +- `deviceId:` identifier of the autopilot device to query. + +returns: `Promise<{void}>` + +throws on error or if supplied state value is invalid. + +_Example:_ +```javascript +// API request +PUT /signalk/v2/api/vessels/self/autopilots/mypilot1/state {value: "standby"} + +// AutopilotProvider method invocation +setState('standby', 'mypilot1'); +``` + +--- +**`getMode(deviceId)`**: This method returns the current mode of the supplied autopilot device identifier. + +- `deviceId:` identifier of the autopilot device to query. + +returns: `Promise<{string}>` + +_Example:_ +```javascript +// API request +GET /signalk/v2/api/vessels/self/autopilots/mypilot1/mode + +// AutopilotProvider method invocation +getMode('mypilot1'); + +// Returns: +'compass' +``` + +--- +**`setMode(mode, deviceId)`**: This method sets the autopilot device with the supplied identifier to the supplied mode value. + +- `mode:` mode value to set. Must be a valid mode value. +- `deviceId:` identifier of the autopilot device to query. + +returns: `Promise<{void}>` + +throws on error or if supplied mode value is invalid. + +_Example:_ +```javascript +// API request +PUT /signalk/v2/api/vessels/self/autopilots/mypilot1/mode {value: "gps"} + +// AutopilotProvider method invocation +setMode('gps', 'mypilot1'); +``` + +--- +**`setTarget(value, deviceId)`**: This method sets target for the autopilot device with the supplied identifier to the supplied value. + +- `value:` target value in radians. +- `deviceId:` identifier of the autopilot device to query. + +returns: `Promise<{void}>` + +throws on error or if supplied target value is outside the valid range. + +_Example:_ +```javascript +// API request +PUT /signalk/v2/api/vessels/self/autopilots/mypilot1/target {value: 129} + +// AutopilotProvider method invocation +setTarget(129, 'mypilot1'); +``` + +--- +**`adjustTarget(value, deviceId)`**: This method adjusts target for the autopilot device with the supplied identifier by the supplied value. + +- `value:` value in radians to add to current target value. +- `deviceId:` identifier of the autopilot device to query. + +returns: `Promise<{void}>` + +throws on error or if supplied target value is outside the valid range. + +_Example:_ +```javascript +// API request +PUT /signalk/v2/api/vessels/self/autopilots/mypilot1/target {value: 2} + +// AutopilotProvider method invocation +adjustTarget(2, 'mypilot1'); +``` + +--- +**`engage(deviceId)`**: This method sets the state of the autopilot device with the supplied identifier to a state that is actively steering the vessel. + +- `deviceId:` identifier of the autopilot device to query. + +returns: `Promise<{void}>` + +throws on error. + +_Example:_ +```javascript +// API request +POST /signalk/v2/api/vessels/self/autopilots/mypilot1/engage + +// AutopilotProvider method invocation +engage('mypilot1'); +``` + +--- +**`disengage(deviceId)`**: This method sets the state of the autopilot device with the supplied identifier to a state that is NOT actively steering the vessel. + +- `deviceId:` identifier of the autopilot device to query. + +returns: `Promise<{void}>` + +throws on error. + +_Example:_ +```javascript +// API request +POST /signalk/v2/api/vessels/self/autopilots/mypilot1/disengage + +// AutopilotProvider method invocation +disengage('mypilot1'); +``` + +--- +**`tack(direction, deviceId)`**: This method instructs the autopilot device with the supplied identifier to perform a tack in the supplied direction. + +- `direction`: 'port' or 'starboard' +- `deviceId:` identifier of the autopilot device to query. + +returns: `Promise<{void}>` + +throws on error. + +_Example:_ +```javascript +// API request +POST /signalk/v2/api/vessels/self/autopilots/mypilot1/tack/port + +// AutopilotProvider method invocation +tack('port', 'mypilot1'); +``` + +--- +**`gybe(direction, deviceId)`**: This method instructs the autopilot device with the supplied identifier to perform a gybe in the supplied direction. + +- `direction`: 'port' or 'starboard' +- `deviceId:` identifier of the autopilot device to query. + +returns: `Promise<{void}>` + +throws on error. + +_Example:_ +```javascript +// API request +POST /signalk/v2/api/vessels/self/autopilots/mypilot1/gybe/starboard + +// AutopilotProvider method invocation +gybe('starboard', 'mypilot1'); +``` + +--- +**`dodge(value, deviceId)`**: This method instructs the autopilot device with the supplied identifier to enter / exit dodge mode and alter the current course by the supplied value (radians) direction. + +- `value`: +/- value in radians 'port (-ive)' or 'starboard' to change direction. _Setting the value to `null` indicates exit of dodge mode._ +- `deviceId:` identifier of the autopilot device to query. + +returns: `Promise<{void}>` + +throws on error. + + +To address different pilot behaviour, the `dodge` function can be used in the following ways: + + + +**1. Enter dodge mode at the current course** +```javascript +// API request +POST /signalk/v2/api/vessels/self/autopilots/mypilot1/dodge + +// _AutopilotProvider method invocation +dodge(0, 'mypilot1'); +``` + +**2. Enter dodge mode and change course** +```javascript +// API request +PUT /signalk/v2/api/vessels/self/autopilots/mypilot1/dodge {"value": 5} + +// AutopilotProvider method invocation +dodge(5, 'mypilot1'); +``` + +**3. Cancel dodge mode** +```javascript +// API request +DELETE /signalk/v2/api/vessels/self/autopilots/mypilot1/dodge + +// AutopilotProvider method invocation +dodge(null, 'mypilot1'); +``` + +--- + +### Unhandled Operations + +A provider plugin **MUST** implement **ALL** Autopilot API interface methods, regardless of whether the operation is supported or not. + +For an operation that is not supported by the autopilot device, then the plugin should `throw` an exception. + +_Example:_ +```typescript +{ + // unsupported operation method definition + gybe: async (d, id) => { + throw new Error('Unsupprted operation!) + } +} +``` diff --git a/docs/src/develop/rest-api/autopilot_api.md b/docs/src/develop/rest-api/autopilot_api.md index 21e5229a7..693b202b4 100644 --- a/docs/src/develop/rest-api/autopilot_api.md +++ b/docs/src/develop/rest-api/autopilot_api.md @@ -1,38 +1,371 @@ -# Autopilot API +# Working with the Autopilot API -#### (Under Development) -_Note: This API is currently under development and the information provided here is likely to change._ +## Overview -The Signal K server Autopilot API will provide a common set of operations for interacting with autopilot devices and (like the Resources API) will rely on a "provider plugin" to facilitate communication with the autopilot device. +The Autopilot API defines the `autopilots` path under `self` _(e.g. `/signalk/v2/api/vessels/self/autopilots`)_ for representing information from one or more autopilot devices. -The Autopilot API will handle requests to `/steering/autopilot` paths and pass them to an Autopilot Provider plugin which will send the commands to the autopilot device. +The Autopilot API provides a mechanism for applications to issue requests to autopilot devices to perform common operations. Additionally, when multiple autopilot devices are present, each autopilot device is individually addressable. -The following operations are an example of the operations identified for implementation via HTTP `GET` and `PUT` requests: + _Note: Autopilot provider plugins are required to enable the API operation and provide communication with autopilot devices. See [Autopilot Provider Plugins](../plugins/autopilot_provider_plugins.md) for details._ -PUT `/steering/autopilot/engage` (engage / activate the autopilot) -PUT `/steering/autopilot/disengage` (disengage / deactivate the autopilot) +## Common Operations -GET `/steering/autopilot/state` (retrieve the current autopilot state) +The following operations are supported: +- Setting the operating mode +- Engaging / Disengaging the pilot +- Setting / adjusting the course +- Dodging port / starboard +- Tacking / Gybing -PUT `/steering/autopilot/state` (set the autopilot state) -GET `/steering/autopilot/mode` (retrieve the current autopilot mode) +## The _Default_ Autopilot -PUT `/steering/autopilot/mode` (set autopilot mode) +To ensure a consistent API calling profile and to simplify client operations, the Autopilot API will assign a _default_ autopilot device which is accessible using the path `/signalk/v2/api/vessels/self/autopilots/_default`. -GET `/steering/autopilot/target` (get currrent target value) +- When only one autopilot is present, it will be automatically assigned as the _default_. -PUT `/steering/autopilot/target` (set the target value based on the selected mode) +- When multiple autopilots are present, and a _default_ is yet to be assigned, one will be assigned when: + - An update is received from a provider plugin, the autopilot which is the source of the update will be assigned as the _default_. + - An API request is received, the first autopilot device registered, is assigned as the _default_. + - A request is sent to the `/_providers/_default` API endpoint _(see [Setting the Default Autopilot](#setting-the-default-provider))_. -PUT `/steering/autopilot/target/adjust` (increment / decrement target value) -PUT `/steering/autopilot/tack/port` (perform a port tack) +### Getting the Default Autopilot Identifier -PUT `/steering/autopilot/tack/starboard` (perform a starboard tack) +To get the id of the _default_ autopilot, submit an HTTP `GET` request to `/signalk/v2/api/vessels/self/autopilots/_providers/_default`. +_Example:_ +```typescript +HTTP GET "/signalk/v2/api/vessels/self/autopilots/_providers/_default" +``` +_Response:_ +```JSON +{ + "id":"raymarine-id" +} +``` -[View the PR](https://github.com/SignalK/signalk-server/pull/1596) for more details. +### Setting an Autopilot as the Default +To set / change the _default_ autopilot, submit an HTTP `POST` request to `/signalk/v2/api/vessels/self/autopilots/_providers/_default/{id}` where `{id}` is the identifier of the autopilot to use as the _default_. + +_Example:_ +```typescript +HTTP POST "/signalk/v2/api/vessels/self/autopilots/_providers/_default/raymarine-id" +``` + +The autopilot with the supplied id will now be the target of requests made to `/signalk/v2/api/vessels/self/autopilots/_default/*`. + + +## Listing the available Autopilots + +To retrieve a list of installed autopilot devices, submit an HTTP `GET` request to `/signalk/v2/api/vessels/self/autopilots`. + +The response will be an object containing all the registered autopilot devices, keyed by their identifier, detailing the `provider` it is registered by and whether it is assigned as the _default_. + +```typescript +HTTP GET "/signalk/v2/api/vessels/self/autopilots" +``` +_Example: List of registered autopilots showing that `pypilot-id` is assigned as the default._ + +```JSON +{ + "pypilot-id": { + "provider":"pypilot-provider", + "isDefault": true + }, + "raymarine-id": { + "provider":"raymarine-provider", + "isDefault": false + } +} +``` + +## Autopilot Deltas + +Deltas emitted by the Autopilot API will have the base path `steering.autopilot` with the `$source` containing the autopilot device identifier. + +_Example: Deltas for `autopilot.engaged` from two autopilots (`raymarine-id`)._ +```JSON +{ + "context":"vessels.self", + "updates":[ + { + "$source":"pypilot-id", + "timestamp":"2023-11-19T06:12:47.820Z", + "values":[ + {"path":"steering.autopilot.engaged","value":false} + ] + }, + { + "$source":"raymarine-id", + "timestamp":"2023-11-19T06:12:47.820Z", + "values":[ + {"path":"steering.autopilot.engaged","value":true} + ] + } + ] +} +``` + + +## Autopilot Notifications + +The Autopilot API will provide notifications under the path `notifications.steering.autopilot` with the `$source` containing the autopilot device identifier. + +A set of normalised notification paths are defined to provide a consistant way for client apps to receive and process alarm messages. + +- `waypointAdvance` +- `waypointArrival` +- `routeComplete` +- `xte` +- `heading` +- `wind` + +_Example:_ +```JSON +{ + "context":"vessels.self", + "updates":[ + { + "$source":"pypilot-id", + "timestamp":"2023-11-19T06:12:47.820Z", + "values":[ + { + "path": "notifications.steering.autopilot.waypointAdvance", + "value": { + "state": "alert", + "method": ["sound"], + "message": "Waypoint Advance" + } + } + ] + } + ] +} + +``` + +## Autopilot offline / unreachable + +If an autopilot device is not connected or unreachable, the provider for that autopilot device will set the `state` of the device to `off-line`. + + +## Autopilot Operations + +All API operations are invoked by issuing requests to: +1. `/signalk/v2/api/vessels/self/autopilots/_default/*` + +Targets the default autopilot device. + +OR + +2. `/signalk/v2/api/vessels/self/autopilots/{id}/*` + +Target the autopilot with the supplied `{id}` + +_Example:_ +```typescript +HTTP GET "/signalk/v2/api/vessels/self/autopilots/_default/state" + +HTTP GET "/signalk/v2/api/vessels/self/autopilots/pypilot-id/mode" +``` + +### Retrieving Autopilot Status + +To retrieve the current autopilot configuration as well as a list of available options for `state` and `mode` selections, submit an HTTP `GET` request to `/signalk/v2/api/vessels/self/autopilots/{id}`. + +```typescript +HTTP GET "/signalk/v2/api/vessels/self/autopilots/{id}" +``` +_Response:_ + +```JSON +{ + "options":{ + "state":["enabled","disabled"], + "mode":["gps","compass","wind"] + }, + "state":"disabled", + "mode":"gps", + "target": 0, + "engaged": false +} +``` + +Where: +- `options` contains arrays of valid `state` and `mode` selection options +- `state` represents the current state of the device +- `mode` represents the current mode of the device +- `target` represents the current target value with respect to the selected `mode` +- `engaged` will be true when the autopilot is actively steering the vessel. + + +### Setting the Autopilot State + +Autopilot state can be set by submitting an HTTP `PUT` request to the `/signalk/v2/api/vessels/self/autopilots/{id}/state` endpoint containing a value from the list of available states. + +```typescript +HTTP PUT "/signalk/v2/api/vessels/self/autopilots/{id}/state" {"value": "disabled"} +``` + +### Getting the Autopilot State + +The current autopilot state can be retrieved by submitting an HTTP `GET` request to the `/signalk/v2/api/vessels/self/autopilots/{id}/state` endpoint. + +```typescript +HTTP GET "/signalk/v2/api/vessels/self/autopilots/{id}/state" +``` + +_Response:_ + +```JSON +{ + "value":"enabled", +} +``` + +### Setting the Autopilot Mode + +Autopilot mode can be set by submitting an HTTP `PUT` request to the `/signalk/v2/api/vessels/self/autopilots/{id}/mode` endpoint containing a value from the list of available modes. + +```typescript +HTTP PUT "/signalk/v2/api/vessels/self/autopilots/{id}/mode" {"value": "gps"} +``` + +### Getting the Autopilot Mode + +The current autopilot mode can be retrieved by submitting an HTTP `GET` request to the `mode` endpoint. + +```typescript +HTTP GET "/signalk/v2/api/vessels/self/autopilots/{id}/mode" +``` + +_Response:_ + +```JSON +{ + "value":"gps", +} +``` + +### Setting the Target value + +Autopilot target value can be set by submitting an HTTP `PUT` request to the `/signalk/v2/api/vessels/self/autopilots/{id}/target` endpoint containing the desired value. + +_Note: The value supplied should be a number within the valid range for the selected `mode`._ + +```typescript +// Set target to 129 degrees +HTTP PUT "signalk/v2/api/vessels/self/autopilots/{id}/target" {"value": 129, "units": "deg"} + +// Set target to 0.349066 radians (20 degrees) +HTTP PUT "signalk/v2/api/vessels/self/autopilots/{id}/target" {"value": 0.349066} +``` + +The target value can be adjusted a +/- value by submitting an HTTP `PUT` request to the `/signalk/v2/api/vessels/self/autopilots/{id}/target/adjust` endpoint with the value to add to the current `target` value. + +```typescript +// Adjust target 2 degrees port +HTTP PUT "signalk/v2/api/vessels/self/autopilots/{id}/target/adjust" {"value": -2, , "units": "deg"} + +// Adjust target 0.0349066 radians (2 degrees) starboard +HTTP PUT "signalk/v2/api/vessels/self/autopilots/{id}/target/adjust" {"value": 0.0349066} +``` + +### Getting the current Target value + +The current autopilot target value _(in radians)_ can be retrieved by submitting an HTTP `GET` request to the `target` endpoint. + +```typescript +HTTP GET "/signalk/v2/api/vessels/self/autopilots/{id}/target" +``` + +_Response:_ + +```JSON +{ + "value": 2.2345, +} +``` + +### Engaging / Disengaging the Autopilot + +#### Engaging the autopilot + +An autopilot can be engaged by [setting it to a speciifc `state`](#setting-the-state) but it can also be engaged more generically by submitting an HTTP `POST` request to the `/signalk/v2/api/vessels/self/autopilots/{id}/engage` endpoint. + +```typescript +HTTP POST "/signalk/v2/api/vessels/self/autopilots/{id}/engage" +``` + +_Note: The resultant `state` into which the autopilot is placed will be determined by the **provider plugin** and the autopilot device it is communicating with._ + +#### Disengaging the autopilot + +An autopilot can be disengaged by [setting it to a speciifc `state`](#setting-the-state) but it can also be disengaged more generically by submitting an HTTP `POST` request to the `/signalk/v2/api/vessels/self/autopilots/{id}/disengage` endpoint. + +```typescript +HTTP POST "/signalk/v2/api/vessels/self/autopilots/{id}/disengage" +``` + +_Note: The resultant `state` into which the autopilot is placed will be determined by the **provider plugin** and the autopilot device it is communicating with._ + +### Perform a Tack + +To send a command to the autopilot to perform a tack in the required direction, submit an HTTP `POST` request to `./autopilots/{id}/tack/{direction}` where _direction_ is either `port` or `starboard`. + +_Example: Tack to Port_ +```typescript +HTTP POST "/signalk/v2/api/vessels/self/autopilots/{id}/tack/port" +``` + +_Example: Tack to Starboard_ +```typescript +HTTP POST "/signalk/v2/api/vessels/self/autopilots/{id}/tack/starboard" +``` + + +### Perform a Gybe + +To send a command to the autopilot to perform a gybe in the required direction, submit an HTTP `POST` request to `/signalk/v2/api/vessels/self/autopilots/{id}/gybe/{direction}` where _direction_ is either `port` or `starboard`. + +_Example: Gybe to Port_ +```typescript +HTTP POST "/signalk/v2/api/vessels/self/autopilots/{id}/gybe/port" +``` + +_Example: Gybe to Starboard_ +```typescript +HTTP POST "/signalk/v2/api/vessels/self/autopilots/{id}/gybe/starboard" +``` + + + +### Dodging Obstacles + +To address the various methods that the `dodge` function could be invoked on pilot devices, the API provides the following endpoints to provide the widest coverage possible: + + +**To enter dodge mode at the current course** +```javascript +POST /signalk/v2/api/vessels/self/autopilots/{id}/dodge +``` + +**To enter dodge mode and change course by 5 degrees starboard** +```javascript +PUT /signalk/v2/api/vessels/self/autopilots/{id}/dodge {"value": 5, "units": "deg"} +``` + +**To enter dodge mode and change course by 5 degrees port** +```javascript +PUT /signalk/v2/api/vessels/self/autopilots/{id}/dodge {"value": -5, "units": "deg"} +``` + +**To cancel dodge mode** +```javascript +DELETE /signalk/v2/api/vessels/self/autopilots/{id}/dodge +``` \ No newline at end of file diff --git a/docs/src/develop/rest-api/open_api.md b/docs/src/develop/rest-api/open_api.md index 82f5c6f02..661cf6425 100644 --- a/docs/src/develop/rest-api/open_api.md +++ b/docs/src/develop/rest-api/open_api.md @@ -13,6 +13,7 @@ APIs are available via `/signalk/v2/api/` |--- |--- |--- | | [Course](./course_api.md) | Set a course, follow a route, advance to next point, etc. | `vessels/self/navigation/course` | | [Resources](./resources_api.md) | Create, view, update and delete waypoints, routes, etc. | `resources` | +| [`Autopilot`](./autopilot_api.md) | Provide the ability to send common commands to an autopilot via a provider plugin. | `vessels/self/autopilot` | --- @@ -23,7 +24,6 @@ APIs are available via `/signalk/v2/api/` | Proposed API | Description | Endpoint | |--- |--- |--- | | _[`Notifications`](notifications_api.md)_ | Provide the ability to raise, update and clear notifications from multiple sources. _[View PR](https://github.com/SignalK/signalk-server/pull/1560)_| `notifications` | -| _[`Autopilot`](./autopilot_api.md)_ | Provide the ability to send common commands to an autopilot via a provider plugin. _[View PR](https://github.com/SignalK/signalk-server/pull/1596)_ | `vessels/self/steering/autopilot` | | _[`Anchor`](./anchor_api.md)_ | Provide endpoints to perform operations and facilitate an anchor alarm. | `vessels/self/navigation/anchor` | --- diff --git a/docs/src/img/autopilot_provider.dia b/docs/src/img/autopilot_provider.dia new file mode 100644 index 0000000000000000000000000000000000000000..7518cc3a1a0a2060bb2130e7af7bda25686303ee GIT binary patch literal 3183 zcmV-#43P65iwFP!000021MOW~bK|xZe)q4?XkRTDIJigI%{Xb(cG@PHN!rfj#Y0Q9 z%!U$GiniB%=x;ATaxF_Dbs-6^wSi{VwzMEV0y_N81vm#^fAeu34<5sG6(x)JLxS*d z5H2RkG+NBw5C8GY_aim@=EKF;(9vOG9Z`OPFr7rWMZ=d+k&<(hVPCfC*?#aJo=OxqV1 zZLsdcXm+2~gE1s9;iAOSgf_!6reb(#To@6&`64aAtj2succo&}nZtOkM^6K}i{khw zkh{C)AeR1aD!ksqtatK!t+MAh+y)325A*WN*-`bCX5UFO7)Q&S`y`G2n=G;*-aEK0 zy?8Q=Va+U>xC2=|+**ey95$Y$;=_Xf>lDJzhD)bGIyD;MZ{|CDr3`SX3`kpLKoFBu zD$8P=YvEECFhm%a(n4WP^w=Ou#x4PjCLppIvQ@P=;bOXDCmcP_3T9^rGfsHkR#V;V z&difES#IA@mG99#twKqspcMuRz#7VU7NprtkfzB~Jx>6%?))YW7qk5%;_X2W&RSEg zx|q6}qnEDT&CnX6tNB?Q@2ed(`RRWK_lDQ3acpQTODv6%7pu9Xx2wY!lk#G=d9B)Y zKDX}ZMC$z|{FqhP;n3a=*N8GsFNsDPq;zVBuc1I|V}^4?m3a>sY1-5b&+Nn;FvGXn z)IO-`c5HDg(*1KZTNqjV>&16*6q*^lUM_1w-+NrnI*Y;BBURY;^TAy(kK$)@i@{VN4T{ z<_f3)38DD8>Ln5D9NtU40ok<@&|MnM#w6M+6-4tTIP7?fN`ZqB6N-&T7y-*+fl&7LDdmU1|MA*0Nl#2tEs;JF zbe2JI*_NOHNwCHzRn+CuT>)c$ay}LaxXdkH&d!0IUJM?;RM$_ux>_bZL%nT=s@dD6 zI`YfyJ}Yn4%Q*sJ(4uIo&u?cJEh7U& z1JyE@ys#5Xq|$*wma)o_FEY8^{)##~YZ;Wnz3Z#1G(jSVc;TINqH1rDy6 zp>mW}K?06)Cs0uee!r(@g_f+awIz|CvYl~@QAAJM8A%6uMFiP>IbgjLxAsN>M68h^ zjkTeXw4OO2p_zR9ZjmjOFz`{Eo}xB2Qt6$dH|P|77p0SjC<8-N|12|j2G{d>m{n#% zlGfQT*zW3LJtV&vb@K{n42XfSxq}=L+7$RLWI=W@fybWfc1E!kzk;52iZ`mdi&O^>343v zk(IY#d)vWKBb?rZJ;MqdJw)Y&_ydg<@NL z!eEQW*lBiub9m9AcAR_K5{7^hIJA0cEAs5NJ$Veq|JaoCeftXQ<^L31n^0l=xvXLv zZ$}=TU%&A6Dn8Hp4xF;SL$(%pXeSFi$JLG_yo=&-!1*Nsq=j@{JB}7e${^*X<5W(6 z9C6LhyK-FXDLgJ{3WCa)Bug#aCX{e^g{8paT|^-iHasQ~ z)xvcUB1aNPGP{ci1Oi!9b5o$sV9Ebaq0tG^B(DQ&^!it}rLmEMSyA2NrRYayp5XkC zFq@!(FZI!9sgD|I_EC%TjIzou>a&5B2wMiyF~5~aIJXFMQx`MHO+npSMTA8gkr{$Gzo36 zWD?!2O*3zG^~zv%^6DAvEbFV0E)r7+WlY!;A}9#yw#XV$B@{>@^Ezvw1+k0WST@Bz zy3Se$<9vg)*5qbnuAvUPP15Oc#n$Y@+%#%-WJNa%;48ZMif+E5+o=`ZFqby@Pa-C9 zUm59}bnpdM-#INy0&oXe5=w%tye7?Ginz^_*nqN`5}IgrN$p~mB4?c`(ZM7(%9UV! z=1P27tA5Q*ixXD;e5!`!BBTOqs$oLivgao# z<8l*CjP*(h5M`l>IET|hZH2AN!PDxp*hl;O-Otf~@^77#dY}6|eeU)dV?}LEupH7) zsZoLyBjQ!9Q9x2D*IswcIO~d%ns$_O?{IsEyJK^x&DrU?FLOwAQL%{-Qn+}MOUEUf z3MfEKSz^(~yAm|7v~Lg3di(a!!*UvAp|63`XUV2&>GWpM8P`C8_BlmFBGE?x%;3n} z8qpkbOQ_guYByqW>NEsaJ;M5i#!kFUsZn^momIIrOwOIt<{VoEi z?soXw0w2Vw=>|sbB^A3ws1W0=nBd_@u%*N%PH0!o?RM2$zpe5C}6)le;z_g%g3daQJM-}NlB%4z$P zeF#HXahWd&Dz}w84HUtQ+ARz=Um_2-DN3}(780~CknS1lXz}!n^_dx~cpnGPVfx{s Vcw_#}(qR7K;{O^?Vjpp=006*3PAC8X literal 0 HcmV?d00001 diff --git a/docs/src/img/autopilot_provider.svg b/docs/src/img/autopilot_provider.svg new file mode 100644 index 000000000..cdf601e15 --- /dev/null +++ b/docs/src/img/autopilot_provider.svg @@ -0,0 +1,705 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/packages/server-api/.gitignore b/packages/server-api/.gitignore index 1521c8b76..a6c9ee411 100644 --- a/packages/server-api/.gitignore +++ b/packages/server-api/.gitignore @@ -1 +1,2 @@ dist +src/autopilotapi.guard.ts diff --git a/packages/server-api/package.json b/packages/server-api/package.json index 8dd4fe513..1eb79ea8d 100644 --- a/packages/server-api/package.json +++ b/packages/server-api/package.json @@ -5,7 +5,8 @@ "main": "dist/index.js", "types": "dist/index.d.ts", "scripts": { - "build": "tsc --declaration", + "generate": "ts-auto-guard src/autopilotapi.ts 2>/dev/null", + "build": "npm run generate && tsc --declaration", "watch": "tsc --declaration --watch", "prepublishOnly": "npm run build", "typedoc": "typedoc --out docs src", @@ -32,6 +33,7 @@ "express": "^4.10.4", "mocha": "^10.2.0", "prettier": "^2.8.4", + "ts-auto-guard": "^4.1.4", "ts-node": "^10.9.1", "typedoc": "^0.23.23", "typescript": "^4.1.5" diff --git a/packages/server-api/src/autopilotapi.ts b/packages/server-api/src/autopilotapi.ts index 8c9bf54ac..de55908a1 100644 --- a/packages/server-api/src/autopilotapi.ts +++ b/packages/server-api/src/autopilotapi.ts @@ -1,27 +1,96 @@ +import { Value } from './deltas' + +export type AutopilotUpdateAttrib = + | 'mode' + | 'state' + | 'target' + | 'engaged' + | 'options' + | 'alarm' + +const AUTOPILOTUPDATEATTRIBS: AutopilotUpdateAttrib[] = [ + 'mode', + 'state', + 'target', + 'engaged', + 'options', + 'alarm' +] + +export const isAutopilotUpdateAttrib = (s: string) => + AUTOPILOTUPDATEATTRIBS.includes(s as AutopilotUpdateAttrib) + +export type AutopilotAlarm = + | 'waypointAdvance' + | 'waypointArrival' + | 'routeComplete' + | 'xte' + | 'heading' + | 'wind' + +const AUTOPILOTALARMS: AutopilotAlarm[] = [ + 'waypointAdvance', + 'waypointArrival', + 'routeComplete', + 'xte', + 'heading', + 'wind' +] + +export const isAutopilotAlarm = (s: string) => + AUTOPILOTALARMS.includes(s as AutopilotAlarm) + +export type TackGybeDirection = 'port' | 'starboard' + export interface AutopilotApi { - register: (pluginId: string, provider: AutopilotProvider) => void - unRegister: (pluginId: string) => void + register(pluginId: string, provider: AutopilotProvider): void + unRegister(pluginId: string): void + apUpdate( + pluginId: string, + deviceId: string, + apInfo: { [path: string]: Value } + ): void } +/** @see {isAutopilotProvider} ts-auto-guard:type-guard */ export interface AutopilotProvider { - pilotType: string - methods: AutopilotProviderMethods + getData(deviceId: string): Promise + getState(deviceId: string): Promise + setState(state: string, deviceId: string): Promise + getMode(deviceId: string): Promise + setMode(mode: string, deviceId: string): Promise + getTarget(deviceId: string): Promise + setTarget(value: number, deviceId: string): Promise + adjustTarget(value: number, deviceId: string): Promise + engage(deviceId: string): Promise + disengage(deviceId: string): Promise + tack(direction: TackGybeDirection, deviceId: string): Promise + gybe(direction: TackGybeDirection, deviceId: string): Promise + dodge(value: number | null, deviceId: string): Promise +} + +export interface AutopilotStateDef { + name: string // autopilot state + engaged: boolean // true if state indicates actively steering +} + +export interface AutopilotOptions { + states: AutopilotStateDef[] + modes: string[] } -export interface AutopilotProviderMethods { - pluginId?: string - engage: (enable: boolean) => Promise - // eslint-disable-next-line @typescript-eslint/no-explicit-any - getConfig: () => Promise<{ [key: string]: any }> - getState: () => Promise - setState: (state: string) => Promise - getMode: () => Promise - setMode: (mode: string) => Promise - setTarget: (value: number) => Promise - adjustTarget: (value: number) => Promise - tack: (port: boolean) => Promise +export interface AutopilotInfo { + options: AutopilotOptions + target: number | null + mode: string | null + state: string | null + engaged: boolean } export interface AutopilotProviderRegistry { - registerAutopilotProvider: (provider: AutopilotProvider) => void + registerAutopilotProvider( + provider: AutopilotProvider, + devices: string[] + ): void + autopilotUpdate(deviceId: string, apInfo: { [path: string]: Value }): void } diff --git a/packages/server-api/src/index.ts b/packages/server-api/src/index.ts index fc7a6c532..87930f2be 100644 --- a/packages/server-api/src/index.ts +++ b/packages/server-api/src/index.ts @@ -27,9 +27,11 @@ export * from './resourcetypes' export * from './resourcesapi' export { ResourceProviderRegistry } from './resourcesapi' import { ResourceProviderRegistry } from './resourcesapi' -import { PointDestination, RouteDestination, CourseInfo } from './coursetypes' - export * from './autopilotapi' +import { AutopilotProviderRegistry } from './autopilotapi' +export { AutopilotProviderRegistry } from './autopilotapi' +export * from './autopilotapi.guard' +import { PointDestination, RouteDestination, CourseInfo } from './coursetypes' export type SignalKApiId = | 'resources' @@ -63,7 +65,8 @@ export interface PropertyValuesEmitter { export interface PluginServerApp extends PropertyValuesEmitter, - ResourceProviderRegistry {} + ResourceProviderRegistry, + AutopilotProviderRegistry {} /** * This is the API that a [server plugin](https://github.com/SignalK/signalk-server/blob/master/SERVERPLUGINS.md) must implement. diff --git a/src/api/autopilot/index.ts b/src/api/autopilot/index.ts new file mode 100644 index 000000000..c47595c95 --- /dev/null +++ b/src/api/autopilot/index.ts @@ -0,0 +1,770 @@ +/* eslint-disable @typescript-eslint/no-explicit-any */ +import { createDebug } from '../../debug' +const debug = createDebug('signalk-server:api:autopilot') + +import { IRouter, NextFunction, Request, Response } from 'express' +import { WithSecurityStrategy } from '../../security' + +import { Responses } from '../' +import { SignalKMessageHub } from '../../app' + +import { + AutopilotProvider, + AutopilotInfo, + SKVersion, + Path, + Value, + Delta, + isAutopilotProvider, + isAutopilotUpdateAttrib, + isAutopilotAlarm, + PathValue, + SourceRef +} from '@signalk/server-api' + +const AUTOPILOT_API_PATH = `/signalk/v2/api/vessels/self/autopilots` +const DEFAULTIDPATH = '_default' + +interface AutopilotApplication + extends WithSecurityStrategy, + SignalKMessageHub, + IRouter {} + +interface AutopilotList { + [id: string]: { provider: string; isDefault: boolean } +} + +interface AutopilotApiSettings { + maxTurn: number // maximum course adjust / steer angle value (degrees) +} + +export class AutopilotApi { + private autopilotProviders: Map = new Map() + + private defaultProviderId?: string + private defaultDeviceId?: string + private deviceToProvider: Map = new Map() + + private settings: AutopilotApiSettings = { + maxTurn: 20 * (Math.PI / 180) + } + + constructor(private server: AutopilotApplication) {} + + async start() { + this.initApiEndpoints() + return Promise.resolve() + } + + // ***** Plugin Interface methods ***** + + // Register plugin as provider. + register(pluginId: string, provider: AutopilotProvider, devices: string[]) { + debug(`** Registering provider(s)....${pluginId}`) + + if (!provider) { + throw new Error(`Error registering provider ${pluginId}!`) + } + if (!devices) { + throw new Error(`${pluginId} has not supplied a device list!`) + } + if (!isAutopilotProvider(provider)) { + throw new Error( + `${pluginId} is missing AutopilotProvider properties/methods!` + ) + } else { + if (!this.autopilotProviders.has(pluginId)) { + this.autopilotProviders.set(pluginId, provider) + } + devices.forEach((id: string) => { + if (!this.deviceToProvider.has(id)) { + this.deviceToProvider.set(id, pluginId) + } + }) + } + debug( + `No. of AutoPilotProviders registered =`, + this.autopilotProviders.size + ) + } + + // Unregister plugin as provider. + unRegister(pluginId: string) { + if (!pluginId) { + return + } + debug(`** Request to un-register plugin.....${pluginId}`) + + if (!this.autopilotProviders.has(pluginId)) { + debug(`** NOT FOUND....${pluginId}... cannot un-register!`) + return + } + + debug(`** Un-registering autopilot provider....${pluginId}`) + this.autopilotProviders.delete(pluginId) + + debug(`** Update deviceToProvider Map .....${pluginId}`) + this.deviceToProvider.forEach((v: string, k: string) => { + debug('k', k, 'v', v) + if (v === pluginId) { + this.deviceToProvider.delete(k) + } + }) + + // update default if required + if (pluginId === this.defaultProviderId) { + debug(`** Resetting defaults .....`) + this.defaultDeviceId = undefined + this.defaultProviderId = undefined + this.initDefaults() + /*this.emitUpdates( + [ + this.buildPathValue( + 'defaultPilot' as Path, + this.defaultDeviceId ?? null + ) + ], + 'autopilotApi' as SourceRef + )*/ + } + + debug( + `Remaining number of AutoPilot Providers registered =`, + this.autopilotProviders.size, + 'defaultProvider =', + this.defaultProviderId + ) + } + + /** Emit updates from autopilot device as `steering.autopilot.*` deltas. + * This should be used by provider plugins to: + * - Ensure API state is consistant + * - trigger the sending of deltas. + */ + apUpdate( + pluginId: string, + deviceId: SourceRef = pluginId as SourceRef, + apInfo: { [path: string]: Value } + ) { + try { + if (deviceId && !this.deviceToProvider.has(deviceId)) { + this.deviceToProvider.set(deviceId, pluginId) + } + if (!this.defaultDeviceId) { + this.initDefaults(deviceId) + } + } catch (err) { + debug(`ERROR apUpdate(): ${pluginId}->${deviceId}`, err) + return + } + + const values: any[] = [] + Object.keys(apInfo).forEach((attrib: string) => { + if (isAutopilotUpdateAttrib(attrib) && attrib !== 'options') { + if (attrib === 'alarm') { + const alarm: PathValue = apInfo[attrib] as PathValue + if (isAutopilotAlarm(alarm.path)) { + values.push({ + path: `notifications.steering.autopilot.${alarm.path}` as Path, + value: alarm.value + }) + } + } else { + values.push({ + path: `steering.autopilot.${attrib}`, + value: apInfo[attrib] + }) + } + } + }) + if (values.length !== 0) { + this.emitUpdates(values, deviceId) + } + } + + // ***** /Plugin Interface methods ***** + + private updateAllowed(request: Request): boolean { + return this.server.securityStrategy.shouldAllowPut( + request, + 'vessels.self', + null, + 'autopilot' + ) + } + + private initApiEndpoints() { + debug(`** Initialise ${AUTOPILOT_API_PATH} endpoints. **`) + + this.server.use( + `${AUTOPILOT_API_PATH}/*`, + (req: Request, res: Response, next: NextFunction) => { + debug(`Autopilot path`, req.method, req.params) + try { + if (['PUT', 'POST'].includes(req.method)) { + debug(`Autopilot`, req.method, req.path, req.body) + if (!this.updateAllowed(req)) { + res.status(403).json(Responses.unauthorised) + } else { + next() + } + } else { + debug(`Autopilot`, req.method, req.path, req.query, req.body) + next() + } + } catch (err: any) { + res.status(500).json({ + state: 'FAILED', + statusCode: 500, + message: err.message ?? 'No autopilots available!' + }) + } + } + ) + + // get autopilot provider information + this.server.get(`${AUTOPILOT_API_PATH}`, (req: Request, res: Response) => { + res.status(200).json(this.getDevices()) + }) + + // get default autopilot device + this.server.get( + `${AUTOPILOT_API_PATH}/_providers/_default`, + (req: Request, res: Response) => { + debug(`params:`, req.params) + res.status(Responses.ok.statusCode).json({ id: this.defaultDeviceId }) + } + ) + + // set default autopilot device + this.server.post( + `${AUTOPILOT_API_PATH}/_providers/_default/:id`, + (req: Request, res: Response) => { + debug(`params:`, req.params) + if (!this.deviceToProvider.has(req.params.id)) { + debug('** Invalid device id supplied...') + res.status(Responses.invalid.statusCode).json(Responses.invalid) + return + } + this.initDefaults(req.params.id) + res.status(Responses.ok.statusCode).json(Responses.ok) + } + ) + + // get default autopilot status & options + this.server.get( + `${AUTOPILOT_API_PATH}/:id`, + (req: Request, res: Response) => { + this.useProvider(req) + .getData(req.params.id) + .then((data: AutopilotInfo) => { + res.json(data) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // get autopilot options + this.server.get( + `${AUTOPILOT_API_PATH}/:id/options`, + (req: Request, res: Response) => { + this.useProvider(req) + .getData(req.params.id) + .then((r: AutopilotInfo) => { + res.json(r.options) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // engage / enable the autopilot + this.server.post( + `${AUTOPILOT_API_PATH}/:id/engage`, + (req: Request, res: Response) => { + this.useProvider(req) + .engage(req.params.id) + .then(() => { + res.status(Responses.ok.statusCode).json(Responses.ok) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // disengage / disable the autopilot + this.server.post( + `${AUTOPILOT_API_PATH}/:id/disengage`, + (req: Request, res: Response) => { + this.useProvider(req) + .disengage(req.params.id) + .then(() => { + res.status(Responses.ok.statusCode).json(Responses.ok) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // get state + this.server.get( + `${AUTOPILOT_API_PATH}/:id/state`, + (req: Request, res: Response) => { + this.useProvider(req) + .getState(req.params.id) + .then((r: string) => { + res.json({ value: r }) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // set state + this.server.put( + `${AUTOPILOT_API_PATH}/:id/state`, + (req: Request, res: Response) => { + if (typeof req.body.value === 'undefined') { + res.status(Responses.invalid.statusCode).json(Responses.invalid) + return + } + this.useProvider(req) + .setState(req.body.value, req.params.id) + .then(() => { + res.status(Responses.ok.statusCode).json(Responses.ok) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // get mode + this.server.get( + `${AUTOPILOT_API_PATH}/:id/mode`, + (req: Request, res: Response) => { + this.useProvider(req) + .getMode(req.params.id) + .then((r: string) => { + res.json({ value: r }) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // set mode + this.server.put( + `${AUTOPILOT_API_PATH}/:id/mode`, + (req: Request, res: Response) => { + if (typeof req.body.value === 'undefined') { + res.status(400).json(Responses.invalid) + return + } + this.useProvider(req) + .setMode(req.body.value, req.params.id) + .then(() => { + res.status(Responses.ok.statusCode).json(Responses.ok) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // get target + this.server.get( + `${AUTOPILOT_API_PATH}/:id/target`, + (req: Request, res: Response) => { + this.useProvider(req) + .getTarget(req.params.id) + .then((r: number) => { + res.json({ value: r }) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // set target + this.server.put( + `${AUTOPILOT_API_PATH}/:id/target`, + (req: Request, res: Response) => { + if (typeof req.body.value !== 'number') { + res.status(Responses.invalid.statusCode).json(Responses.invalid) + return + } + + const u: string = req.body.units ?? 'rad' + let v = + typeof u === 'string' && u.toLocaleLowerCase() === 'deg' + ? req.body.value * (Math.PI / 180) + : req.body.value + + v = + v < 0 - Math.PI + ? Math.max(...[0 - Math.PI, v]) + : Math.min(...[2 * Math.PI, v]) + + debug('target = ', v) + this.useProvider(req) + .setTarget(v, req.params.id) + .then(() => { + res.status(Responses.ok.statusCode).json(Responses.ok) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // adjust target + this.server.put( + `${AUTOPILOT_API_PATH}/:id/target/adjust`, + (req: Request, res: Response) => { + if (typeof req.body.value !== 'number') { + res.status(Responses.invalid.statusCode).json(Responses.invalid) + return + } + const u: string = req.body.units ?? 'rad' + const v = + typeof u === 'string' && u.toLocaleLowerCase() === 'deg' + ? req.body.value * (Math.PI / 180) + : req.body.value + + debug('target = ', v) + this.useProvider(req) + .adjustTarget(v, req.params.id) + .then(() => { + res.status(Responses.ok.statusCode).json(Responses.ok) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // port tack + this.server.post( + `${AUTOPILOT_API_PATH}/:id/tack/port`, + (req: Request, res: Response) => { + this.useProvider(req) + .tack('port', req.params.id) + .then(() => { + res.status(Responses.ok.statusCode).json(Responses.ok) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // starboard tack + this.server.post( + `${AUTOPILOT_API_PATH}/:id/tack/starboard`, + (req: Request, res: Response) => { + this.useProvider(req) + .tack('starboard', req.params.id) + .then(() => { + res.status(Responses.ok.statusCode).json(Responses.ok) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // port gybe + this.server.post( + `${AUTOPILOT_API_PATH}/:id/gybe/port`, + (req: Request, res: Response) => { + this.useProvider(req) + .gybe('port', req.params.id) + .then(() => { + res.status(Responses.ok.statusCode).json(Responses.ok) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // starboard gybe + this.server.post( + `${AUTOPILOT_API_PATH}/:id/gybe/starboard`, + (req: Request, res: Response) => { + this.useProvider(req) + .gybe('starboard', req.params.id) + .then(() => { + res.status(Responses.ok.statusCode).json(Responses.ok) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // dodge mode ON + this.server.post( + `${AUTOPILOT_API_PATH}/:id/dodge`, + (req: Request, res: Response) => { + this.useProvider(req) + .dodge(0, req.params.id) + .then(() => { + res.status(Responses.ok.statusCode).json(Responses.ok) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // dodge mode OFF + this.server.delete( + `${AUTOPILOT_API_PATH}/:id/dodge`, + (req: Request, res: Response) => { + this.useProvider(req) + .dodge(null, req.params.id) + .then(() => { + res.status(Responses.ok.statusCode).json(Responses.ok) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + /** dodge port (-ive) / starboard (+ive) degrees */ + this.server.put( + `${AUTOPILOT_API_PATH}/:id/dodge`, + (req: Request, res: Response) => { + if (typeof req.body.value !== 'number') { + res.status(Responses.invalid.statusCode).json(Responses.invalid) + return + } + + const u: string = req.body.units ?? 'rad' + let v = + typeof u === 'string' && u.toLocaleLowerCase() === 'deg' + ? req.body.value * (Math.PI / 180) + : req.body.value + + debug('dodge pre-normalisation) = ', v) + v = + v < 0 + ? Math.max(...[0 - this.settings.maxTurn, v]) + : Math.min(...[this.settings.maxTurn, v]) + + debug('dodge = ', v) + this.useProvider(req) + .dodge(v, req.params.id) + .then(() => { + res.status(Responses.ok.statusCode).json(Responses.ok) + }) + .catch((err) => { + res.status(err.statusCode ?? 500).json({ + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + }) + }) + } + ) + + // error response + this.server.use( + `${AUTOPILOT_API_PATH}/*`, + (err: any, req: Request, res: Response, next: NextFunction) => { + const msg = { + state: err.state ?? 'FAILED', + statusCode: err.statusCode ?? 500, + message: err.message ?? 'No autopilots available!' + } + if (res.headersSent) { + console.log('EXCEPTION: headersSent') + return next(msg) + } + res.status(500).json(msg) + } + ) + } + + // returns provider to use. + private useProvider(req: Request): AutopilotProvider { + debug(`useProvider(${req.params.id})`) + + if (req.params.id === DEFAULTIDPATH) { + if (!this.defaultDeviceId) { + this.initDefaults() + } + if ( + this.defaultProviderId && + this.autopilotProviders.has(this.defaultProviderId) + ) { + debug(`Using default device provider...`) + return this.autopilotProviders.get( + this.defaultProviderId + ) as AutopilotProvider + } else { + debug(`No default device provider...`) + throw Responses.invalid + } + } else { + const pid = this.deviceToProvider.get(req.params.id) as string + if (this.autopilotProviders.has(pid)) { + debug(`Found provider...using ${pid}`) + return this.autopilotProviders.get(pid) as AutopilotProvider + } else { + debug('Cannot get Provider!') + throw Responses.invalid + } + } + } + + // Returns an array of provider info + private getDevices(): AutopilotList { + const pilots: AutopilotList = {} + this.deviceToProvider.forEach((providerId: string, deviceId: string) => { + pilots[deviceId] = { + provider: providerId, + isDefault: deviceId === this.defaultDeviceId + } + }) + return pilots + } + + /** Initialises the value of default device / provider. + * If id is not supplied sets first registered device as the default. + **/ + private initDefaults(deviceId?: string) { + debug(`initDefaults()...${deviceId}`) + + // set to supplied deviceId + if (deviceId && this.deviceToProvider.has(deviceId)) { + this.defaultDeviceId = deviceId + this.defaultProviderId = this.deviceToProvider.get( + this.defaultDeviceId + ) as string + } + // else set to first AP device registered + else if (this.deviceToProvider.size !== 0) { + const k = this.deviceToProvider.keys() + this.defaultDeviceId = k.next().value as string + this.defaultProviderId = this.deviceToProvider.get( + this.defaultDeviceId + ) as string + } else { + this.defaultDeviceId = undefined + this.defaultProviderId = undefined + } + this.emitUpdates( + [ + this.buildPathValue( + 'defaultPilot' as Path, + this.defaultDeviceId ?? null + ) + ], + 'autopilotApi' as SourceRef + ) + debug(`Default Device = ${this.defaultDeviceId}`) + debug(`Default Provider = ${this.defaultProviderId}`) + } + + // build autopilot delta PathValue + private buildPathValue(path: Path, value: Value): PathValue { + return { + path: `steering.autopilot${path ? '.' + path : ''}` as Path, + value: value + } + } + + // emit delta updates on operation success + private emitUpdates(values: PathValue[], source: SourceRef) { + const msg: Delta = { + updates: [ + { + values: values + } + ] + } + debug(`delta -> ${source}:`, msg.updates[0]) + this.server.handleMessage(source, msg, SKVersion.v2) + this.server.handleMessage(source, msg, SKVersion.v1) + } +} diff --git a/src/api/autopilot/openApi.json b/src/api/autopilot/openApi.json new file mode 100644 index 000000000..8604120e6 --- /dev/null +++ b/src/api/autopilot/openApi.json @@ -0,0 +1,732 @@ +{ + "openapi": "3.0.0", + "info": { + "version": "2.0.0", + "title": "Signal K Autopilot API", + "termsOfService": "http://signalk.org/terms/", + "license": { + "name": "Apache 2.0", + "url": "http://www.apache.org/licenses/LICENSE-2.0.html" + } + }, + "externalDocs": { + "url": "http://signalk.org/specification/", + "description": "Signal K specification." + }, + "servers": [ + { + "url": "/signalk/v2/api/vessels/self/autopilots" + } + ], + "tags": [ + { + "name": "autopilot", + "description": "Signal K Autopilot API" + } + ], + "components": { + "schemas": { + "autopilotStateOption": { + "type": "object", + "title": "Autopilot state option definition", + "description": "Autopilot `state` option and indication whether pilot is actively steering.", + "properties": { + "name": { + "type": "string", + "description": "State name / label", + "example": "enabled" + }, + "engaged": { + "type": "boolean", + "description": "Set `true` if pilot is actively steering when in this `state`.", + "example": true + } + }, + "example": [ + { "name": "auto", "engaged": true }, + { "name": "standby", "engaged": false } + ] + }, + "autopilotOptions": { + "type": "object", + "title": "Autopilot configuration options", + "description": "A collection of configuration options and their valid values", + "additionalProperties": { + "type": "array", + "items": { + "type": "string" + } + }, + "properties": { + "states": { + "type": "array", + "items": { + "$ref": "#/components/schemas/autopilotStateOption" + }, + "description": "List of valid autopilot states." + }, + "modes": { + "type": "array", + "items": { + "type": "string" + }, + "description": "List of valid Mode values.", + "example": ["compass", "gps"] + } + } + }, + "angleInput": { + "type": "object", + "required": ["value"], + "properties": { + "value": { + "type": "number", + "description": "Value of (degrees / radians).", + "example": 2.12 + }, + "units": { + "type": "string", + "enum": ["deg", "rad"], + "description": "Units of supplied value.", + "example": "deg" + } + } + } + }, + "responses": { + "200ActionResponse": { + "description": "PUT OK response", + "content": { + "application/json": { + "schema": { + "type": "object", + "properties": { + "state": { + "type": "string", + "enum": ["COMPLETED"] + }, + "statusCode": { + "type": "number", + "enum": [200] + } + }, + "required": ["statusCode", "state"] + } + } + } + }, + "ErrorResponse": { + "description": "Failed operation", + "content": { + "application/json": { + "schema": { + "type": "object", + "description": "Request error response", + "properties": { + "state": { + "type": "string", + "enum": ["FAILED"] + }, + "statusCode": { + "type": "number", + "enum": [400, 404] + }, + "message": { + "type": "string" + } + }, + "required": ["state", "statusCode", "message"] + } + } + } + } + }, + "parameters": { + "AutopilotIdParam": { + "name": "id", + "in": "path", + "description": "autopilot id", + "required": true, + "schema": { + "type": "string" + } + } + }, + "securitySchemes": { + "bearerAuth": { + "type": "http", + "scheme": "bearer", + "bearerFormat": "JWT" + }, + "cookieAuth": { + "type": "apiKey", + "in": "cookie", + "name": "JAUTHENTICATION" + } + } + }, + "security": [{ "cookieAuth": [] }, { "bearerAuth": [] }], + "paths": { + "/": { + "get": { + "tags": ["autopilot"], + "summary": "Retrieve list of autopilots.", + "description": "Returns a list of autopilots indexed by their identifier.", + "responses": { + "default": { + "description": "Autopilot device list response.", + "content": { + "application/json": { + "schema": { + "type": "object", + "additionalProperties": { + "type": "object", + "required": ["provider", "isDefault"], + "properties": { + "provider": { + "type": "string", + "description": "Provider plugin managing the autopilot device.", + "example": "my-pilot-provider" + }, + "isDefault": { + "type": "boolean", + "description": "Set to true when the autopilot is currently set as the default.", + "example": "false" + } + } + } + } + } + } + }, + "error": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/_providers/_default": { + "get": { + "tags": ["autopilot"], + "summary": "Get the default autopilot device id.", + "description": "Returns the device id of the autopilot assigned as the default.", + "responses": { + "default": { + "description": "Autopilot configuration response", + "content": { + "application/json": { + "schema": { + "type": "object", + "required": ["id"], + "properties": { + "id": { + "type": "string" + } + } + } + } + } + } + } + } + }, + "/_providers/_default/{id}": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "post": { + "tags": ["autopilot"], + "summary": "Set the default autopilot device.", + "description": "Sets the autopilot with the supplied `id` as the default.", + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/{id}": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "get": { + "tags": ["autopilot"], + "summary": "Retrieve autopilot information.", + "description": "Returns the current state autopilot information including the available options for `state` and `mode`.", + "responses": { + "default": { + "description": "Autopilot configuration response", + "content": { + "application/json": { + "schema": { + "type": "object", + "required": ["state", "mode", "target", "engaged"], + "properties": { + "engaged": { + "type": "boolean", + "description": "Autopilot is engaged and actively steering the vessel", + "example": "true" + }, + "state": { + "type": "string", + "description": "Autopilot state", + "example": "auto" + }, + "mode": { + "type": "string", + "description": "Autopilot operational mode", + "example": "compass" + }, + "target": { + "description": "Current target value (radians)", + "type": "number", + "example": 2.8762 + }, + "options": { + "$ref": "#/components/schemas/autopilotOptions" + } + } + } + } + } + }, + "error": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/{id}/options": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "get": { + "tags": ["autopilot"], + "summary": "Retrieve autopilot options.", + "description": "Returns the selectable options and the values that can be applied (e.g. for`state` and `mode`).", + "responses": { + "default": { + "description": "Autopilot configuration response", + "content": { + "application/json": { + "schema": { + "$ref": "#/components/schemas/autopilotOptions" + } + } + } + }, + "error": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/{id}/engage": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "post": { + "tags": ["autopilot"], + "summary": "Engage autopilot to steer vessel", + "description": "Provider plugin will set the autopilot to a `state` where it is actively steering the vessel. `state` selected is determined by the provider plugin.", + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/{id}/disengage": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "post": { + "tags": ["autopilot"], + "summary": "Disengage autopilot from steering vessel.", + "description": "Provider plugin will set the autopilot to a `state` where it is NOT actively steering the vessel. `state` selected is determined by the provider plugin.", + + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/{id}/state": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "get": { + "tags": ["autopilot"], + "summary": "Retrieve the current state.", + "description": "Returns the current `state` value from the autopilot.", + "responses": { + "default": { + "description": "Autopilot value response", + "content": { + "application/json": { + "schema": { + "type": "object", + "required": ["value"], + "properties": { + "value": { + "type": "string", + "example": "standby" + } + } + } + } + } + }, + "error": { + "$ref": "#/components/responses/ErrorResponse" + } + } + }, + "put": { + "tags": ["autopilot"], + "summary": "Set autopilot state.", + "description": "Set the autopilot to the supplied valid `state` value.", + "requestBody": { + "description": "Supply valid `state` value (as per response from autopilot information request).", + "required": true, + "content": { + "application/json": { + "schema": { + "type": "object", + "properties": { + "value": { + "type": "string", + "description": "Value representing the `state` the autopilot is to enter.", + "example": "enabled" + } + } + } + } + } + }, + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/{id}/mode": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "get": { + "tags": ["autopilot"], + "summary": "Retrieve the current mode.", + "description": "Returns the current `mode` value from the autopilot.", + "responses": { + "default": { + "description": "Autopilot value response", + "content": { + "application/json": { + "schema": { + "type": "object", + "required": ["value"], + "properties": { + "value": { + "type": "string", + "example": "compass" + } + } + } + } + } + }, + "error": { + "$ref": "#/components/responses/ErrorResponse" + } + } + }, + "put": { + "tags": ["autopilot"], + "summary": "Set autopilot mode", + "description": "Set the autopilot to the supplied valid `mode` value.", + "requestBody": { + "description": "Supply valid `mode` value (as per response from autopilot information request).", + "required": true, + "content": { + "application/json": { + "schema": { + "type": "object", + "properties": { + "value": { + "type": "string", + "description": "Value representing the `mode` the autopilot is to enter.", + "example": "compass" + } + } + } + } + } + }, + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/{id}/target": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "get": { + "tags": ["autopilot"], + "summary": "Retrieve the current target value.", + "description": "The current target value in radians.", + "responses": { + "default": { + "description": "Autopilot value response", + "content": { + "application/json": { + "schema": { + "type": "object", + "required": ["value"], + "properties": { + "value": { + "type": "number", + "description": "Value in radians", + "example": 2.456 + } + } + } + } + } + }, + "error": { + "$ref": "#/components/responses/ErrorResponse" + } + } + }, + "put": { + "tags": ["autopilot"], + "summary": "Set autopilot `target` value.", + "description": "Value supplied must fall within the valid range (-180 & 360 degrees / PI & 2 * PI radians).", + "requestBody": { + "description": "Value within the valid range.", + "required": true, + "content": { + "application/json": { + "schema": { + "$ref": "#/components/schemas/angleInput" + } + } + } + }, + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/{id}/target/adjust": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "put": { + "tags": ["autopilot"], + "summary": "Adjust autopilot target value by +/- degrees / radians.", + "description": "Value supplied will be added to the current target. The result must fall within the valid range (-180 & 360 degrees / PI & 2 * PI radians).", + "requestBody": { + "description": "Value to add to the current `target`.", + "required": true, + "content": { + "application/json": { + "schema": { + "$ref": "#/components/schemas/angleInput" + } + } + } + }, + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/{id}/tack/port": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "post": { + "tags": ["autopilot"], + "summary": "Tack to port.", + "description": "Execute a port tack.", + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/{id}/tack/starboard": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "post": { + "tags": ["autopilot"], + "summary": "Tack to starboard.", + "description": "Execute a starboard tack.", + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/{id}/gybe/port": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "post": { + "tags": ["autopilot"], + "summary": "Gybe to port.", + "description": "Execute a gybe to port.", + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/{id}/gybe/starboard": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "post": { + "tags": ["autopilot"], + "summary": "Gybe to starboard.", + "description": "Execute a gybe to starboard.", + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + }, + "/{id}/dodge": { + "parameters": [ + { + "$ref": "#/components/parameters/AutopilotIdParam" + } + ], + "post": { + "tags": ["autopilot"], + "summary": "Turn on dodge mode.", + "description": "Enter dodge mode at the current course setting.", + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + }, + "delete": { + "tags": ["autopilot"], + "summary": "Turn Off dodge mode.", + "description": "Resume steering original course.", + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + }, + "put": { + "tags": ["autopilot"], + "summary": "Steer port / starboard to dodge obstacles.", + "description": "Override the current course to change direction the supplied number of degrees / radians.", + "requestBody": { + "description": "+/- value to change direction (-ive = port).", + "required": true, + "content": { + "application/json": { + "schema": { + "$ref": "#/components/schemas/angleInput" + } + } + } + }, + "responses": { + "200ActionResponse": { + "$ref": "#/components/responses/200ActionResponse" + }, + "default": { + "$ref": "#/components/responses/ErrorResponse" + } + } + } + } + } +} diff --git a/src/api/autopilot/openApi.ts b/src/api/autopilot/openApi.ts new file mode 100644 index 000000000..be4532ad4 --- /dev/null +++ b/src/api/autopilot/openApi.ts @@ -0,0 +1,8 @@ +import { OpenApiDescription } from '../swagger' +import autopilotApiDoc from './openApi.json' + +export const autopilotApiRecord = { + name: 'autopilot', + path: '/signalk/v2/api/vessels/self/autopilot', + apiDoc: autopilotApiDoc as unknown as OpenApiDescription +} diff --git a/src/api/index.ts b/src/api/index.ts index a3ccff4ea..a68515464 100644 --- a/src/api/index.ts +++ b/src/api/index.ts @@ -4,6 +4,7 @@ import { WithSecurityStrategy } from '../security' import { CourseApi } from './course' import { FeaturesApi } from './discovery' import { ResourcesApi } from './resources' +import { AutopilotApi } from './autopilot' import { SignalKApiId } from '@signalk/server-api' export interface ApiResponse { @@ -35,6 +36,11 @@ export const Responses = { state: 'FAILED', statusCode: 404, message: 'Resource not found.' + }, + notImplemented: { + state: 'FAILED', + statusCode: 500, + message: 'Not implemented.' } } @@ -56,8 +62,18 @@ export const startApis = ( ;(app as any).courseApi = courseApi apiList.push('course') + const autopilotApi = new AutopilotApi(app) + // eslint-disable-next-line @typescript-eslint/no-explicit-any + ;(app as any).autopilotApi = autopilotApi + apiList.push('autopilot') + const featuresApi = new FeaturesApi(app) - Promise.all([resourcesApi.start(), courseApi.start(), featuresApi.start()]) + Promise.all([ + resourcesApi.start(), + courseApi.start(), + featuresApi.start(), + autopilotApi.start() + ]) return apiList } diff --git a/src/api/swagger.ts b/src/api/swagger.ts index cc77734a8..cd875c698 100644 --- a/src/api/swagger.ts +++ b/src/api/swagger.ts @@ -5,6 +5,7 @@ import { SERVERROUTESPREFIX } from '../constants' import { courseApiRecord } from './course/openApi' import { notificationsApiRecord } from './notifications/openApi' import { resourcesApiRecord } from './resources/openApi' +import { autopilotApiRecord } from './autopilot/openApi' import { securityApiRecord } from './security/openApi' import { discoveryApiRecord } from './discovery/openApi' import { appsApiRecord } from './apps/openApi' @@ -26,10 +27,11 @@ interface ApiRecords { const apiDocs = [ discoveryApiRecord, appsApiRecord, - securityApiRecord, + autopilotApiRecord, courseApiRecord, notificationsApiRecord, - resourcesApiRecord + resourcesApiRecord, + securityApiRecord ].reduce((acc, apiRecord: OpenApiRecord) => { acc[apiRecord.name] = apiRecord return acc diff --git a/src/interfaces/plugins.ts b/src/interfaces/plugins.ts index c131aebbc..a366365ca 100644 --- a/src/interfaces/plugins.ts +++ b/src/interfaces/plugins.ts @@ -22,9 +22,12 @@ import { PropertyValues, PropertyValuesCallback, ResourceProvider, + AutopilotProvider, ServerAPI, RouteDestination, - SignalKApiId + Value, + SignalKApiId, + SourceRef } from '@signalk/server-api' // eslint-disable-next-line @typescript-eslint/ban-ts-comment // @ts-ignore @@ -33,6 +36,7 @@ import express, { Request, Response } from 'express' import fs from 'fs' import _ from 'lodash' import path from 'path' +import { AutopilotApi } from '../api/autopilot' import { CourseApi } from '../api/course' import { ResourcesApi } from '../api/resources' import { SERVERROUTESPREFIX } from '../constants' @@ -473,9 +477,10 @@ module.exports = (theApp: any) => { console.error(`${plugin.id}:no configuration data`) safeConfiguration = {} } - onStopHandlers[plugin.id].push(() => + onStopHandlers[plugin.id].push(() => { app.resourcesApi.unRegister(plugin.id) - ) + app.autopilotApi.unRegister(plugin.id) + }) plugin.start(safeConfiguration, restart) debug('Started plugin ' + plugin.name) setPluginStartedMessage(plugin) @@ -561,6 +566,21 @@ module.exports = (theApp: any) => { resourcesApi.register(plugin.id, provider) } + const autopilotApi: AutopilotApi = app.autopilotApi + _.omit(appCopy, 'autopilotApi') // don't expose the actual autopilot api manager + appCopy.registerAutopilotProvider = ( + provider: AutopilotProvider, + devices: string[] + ) => { + autopilotApi.register(plugin.id, provider, devices) + } + appCopy.autopilotUpdate = ( + deviceId: SourceRef, + apInfo: { [k: string]: Value } + ) => { + autopilotApi.apUpdate(plugin.id, deviceId, apInfo) + } + _.omit(appCopy, 'apiList') // don't expose the actual apiList const courseApi: CourseApi = app.courseApi From 3a8d2d45698a02e0fa4a5f74e657880dd7870270 Mon Sep 17 00:00:00 2001 From: panaaj <38519157+panaaj@users.noreply.github.com> Date: Sun, 15 Dec 2024 09:49:28 +1030 Subject: [PATCH 2/2] fix `path` value. Correct value to contain `autopilots` not `autopilot` --- src/api/autopilot/openApi.ts | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/api/autopilot/openApi.ts b/src/api/autopilot/openApi.ts index be4532ad4..c7637e322 100644 --- a/src/api/autopilot/openApi.ts +++ b/src/api/autopilot/openApi.ts @@ -3,6 +3,6 @@ import autopilotApiDoc from './openApi.json' export const autopilotApiRecord = { name: 'autopilot', - path: '/signalk/v2/api/vessels/self/autopilot', + path: '/signalk/v2/api/vessels/self/autopilots', apiDoc: autopilotApiDoc as unknown as OpenApiDescription }