Skip to content

Commit

Permalink
action: remove max speed settings
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 committed Oct 28, 2024
1 parent d46bb7a commit 7b951bc
Show file tree
Hide file tree
Showing 12 changed files with 319 additions and 2,725 deletions.
2 changes: 1 addition & 1 deletion proto
20 changes: 0 additions & 20 deletions src/mavsdk/plugins/action/action.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -225,26 +225,6 @@ Action::Result Action::set_takeoff_altitude(float altitude) const
return _impl->set_takeoff_altitude(altitude);
}

void Action::get_maximum_speed_async(const GetMaximumSpeedCallback callback)
{
_impl->get_maximum_speed_async(callback);
}

std::pair<Action::Result, float> Action::get_maximum_speed() const
{
return _impl->get_maximum_speed();
}

void Action::set_maximum_speed_async(float speed, const ResultCallback callback)
{
_impl->set_maximum_speed_async(speed, callback);
}

Action::Result Action::set_maximum_speed(float speed) const
{
return _impl->set_maximum_speed(speed);
}

void Action::get_return_to_launch_altitude_async(const GetReturnToLaunchAltitudeCallback callback)
{
_impl->get_return_to_launch_altitude_async(callback);
Expand Down
29 changes: 0 additions & 29 deletions src/mavsdk/plugins/action/action_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -716,35 +716,6 @@ std::pair<Action::Result, float> ActionImpl::get_takeoff_altitude() const
}
}

void ActionImpl::set_maximum_speed_async(
const float speed_m_s, const Action::ResultCallback& callback) const
{
callback(set_maximum_speed(speed_m_s));
}

Action::Result ActionImpl::set_maximum_speed(float speed_m_s) const
{
const MavlinkParameterClient::Result result =
_system_impl->set_param_float(MAX_SPEED_PARAM, speed_m_s);
return (result == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
Action::Result::ParameterError;
}

void ActionImpl::get_maximum_speed_async(const Action::GetMaximumSpeedCallback& callback) const
{
auto speed_result = get_maximum_speed();
callback(speed_result.first, speed_result.second);
}

std::pair<Action::Result, float> ActionImpl::get_maximum_speed() const
{
auto result = _system_impl->get_param_float(MAX_SPEED_PARAM);
return std::make_pair<>(
(result.first == MavlinkParameterClient::Result::Success) ? Action::Result::Success :
Action::Result::ParameterError,
result.second);
}

void ActionImpl::set_return_to_launch_altitude_async(
const float relative_altitude_m, const Action::ResultCallback& callback) const
{
Expand Down
7 changes: 0 additions & 7 deletions src/mavsdk/plugins/action/action_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -84,13 +84,6 @@ class ActionImpl : public PluginImplBase {
Action::Result set_takeoff_altitude(float relative_altitude_m);
std::pair<Action::Result, float> get_takeoff_altitude() const;

void
set_maximum_speed_async(const float speed_m_s, const Action::ResultCallback& callback) const;
void get_maximum_speed_async(const Action::GetMaximumSpeedCallback& callback) const;

Action::Result set_maximum_speed(float speed_m_s) const;
std::pair<Action::Result, float> get_maximum_speed() const;

void set_return_to_launch_altitude_async(
const float relative_altitude_m, const Action::ResultCallback& callback) const;
void get_return_to_launch_altitude_async(
Expand Down
37 changes: 0 additions & 37 deletions src/mavsdk/plugins/action/include/plugins/action/action.h
Original file line number Diff line number Diff line change
Expand Up @@ -542,43 +542,6 @@ class Action : public PluginBase {
*/
Result set_takeoff_altitude(float altitude) const;

/**
* @brief Callback type for get_maximum_speed_async.
*/
using GetMaximumSpeedCallback = std::function<void(Result, float)>;

/**
* @brief Get the vehicle maximum speed (in metres/second).
*
* This function is non-blocking. See 'get_maximum_speed' for the blocking counterpart.
*/
void get_maximum_speed_async(const GetMaximumSpeedCallback callback);

/**
* @brief Get the vehicle maximum speed (in metres/second).
*
* This function is blocking. See 'get_maximum_speed_async' for the non-blocking counterpart.
*
* @return Result of request.
*/
std::pair<Result, float> get_maximum_speed() const;

/**
* @brief Set vehicle maximum speed (in metres/second).
*
* This function is non-blocking. See 'set_maximum_speed' for the blocking counterpart.
*/
void set_maximum_speed_async(float speed, const ResultCallback callback);

/**
* @brief Set vehicle maximum speed (in metres/second).
*
* This function is blocking. See 'set_maximum_speed_async' for the non-blocking counterpart.
*
* @return Result of request.
*/
Result set_maximum_speed(float speed) const;

/**
* @brief Callback type for get_return_to_launch_altitude_async.
*/
Expand Down
2 changes: 0 additions & 2 deletions src/mavsdk/plugins/action/mocks/action_mock.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,6 @@ class MockAction {
MOCK_CONST_METHOD0(transition_to_multicopter, Action::Result()){};
MOCK_CONST_METHOD0(get_takeoff_altitude, std::pair<Action::Result, float>()){};
MOCK_CONST_METHOD1(set_takeoff_altitude, Action::Result(float)){};
MOCK_CONST_METHOD0(get_maximum_speed, std::pair<Action::Result, float>()){};
MOCK_CONST_METHOD1(set_maximum_speed, Action::Result(float)){};
MOCK_CONST_METHOD0(get_return_to_launch_altitude, std::pair<Action::Result, float>()){};
MOCK_CONST_METHOD1(set_return_to_launch_altitude, Action::Result(float)){};
MOCK_CONST_METHOD1(set_current_speed, Action::Result(float)){};
Expand Down
94 changes: 5 additions & 89 deletions src/mavsdk_server/src/generated/action/action.grpc.pb.cc

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

Loading

0 comments on commit 7b951bc

Please sign in to comment.