From 01a546d4f83e06ecde6a005bfbbbd067aaa49ac5 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 29 Oct 2024 19:56:18 +1300 Subject: [PATCH] action: remove max speed settings (#355) This API is confusing as it only works for PX4 quads but not PX4 fixedwing or anything ArduPilot based. The reason is that this just sets a PX4 parameter that is not standardized via MAVLink. Therefore, I suggest to remove the API and instead recommend to use the param plugin to set the specific params specifically. --- protos/action/action.proto | 21 --------------------- 1 file changed, 21 deletions(-) diff --git a/protos/action/action.proto b/protos/action/action.proto index 3ac5b9ab..142da006 100644 --- a/protos/action/action.proto +++ b/protos/action/action.proto @@ -137,14 +137,6 @@ service ActionService { * Set takeoff altitude (in meters above ground). */ rpc SetTakeoffAltitude(SetTakeoffAltitudeRequest) returns(SetTakeoffAltitudeResponse) {} - /* - * Get the vehicle maximum speed (in metres/second). - */ - rpc GetMaximumSpeed(GetMaximumSpeedRequest) returns(GetMaximumSpeedResponse) {} - /* - * Set vehicle maximum speed (in metres/second). - */ - rpc SetMaximumSpeed(SetMaximumSpeedRequest) returns(SetMaximumSpeedResponse) {} /* * Get the return to launch minimum return altitude (in meters). */ @@ -279,19 +271,6 @@ message SetTakeoffAltitudeResponse { ActionResult action_result = 1; } -message GetMaximumSpeedRequest {} -message GetMaximumSpeedResponse { - ActionResult action_result = 1; - float speed = 2; // Maximum speed (in metres/second) -} - -message SetMaximumSpeedRequest { - float speed = 1; // Maximum speed (in metres/second) -} -message SetMaximumSpeedResponse { - ActionResult action_result = 1; -} - message GetReturnToLaunchAltitudeRequest {} message GetReturnToLaunchAltitudeResponse { ActionResult action_result = 1;