Skip to content

Commit

Permalink
action: remove max speed settings (#355)
Browse files Browse the repository at this point in the history
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.
  • Loading branch information
julianoes authored Oct 29, 2024
1 parent 4b3ff32 commit 01a546d
Showing 1 changed file with 0 additions and 21 deletions.
21 changes: 0 additions & 21 deletions protos/action/action.proto
Original file line number Diff line number Diff line change
Expand Up @@ -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).
*/
Expand Down Expand Up @@ -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;
Expand Down

0 comments on commit 01a546d

Please sign in to comment.