Skip to content
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

Add pure mode #1815

Draft
wants to merge 20 commits into
base: main
Choose a base branch
from
Draft
Changes from 1 commit
Commits
Show all changes
20 commits
Select commit Hold shift + click to select a range
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
Prev Previous commit
Next Next commit
action: only attempt ORBIT against PX4
This excludes ORBIT from ArduPilot and Pure mode for now as it is
still marked WIP. We need to decide if that's the right way to go
forward, or if it should still be possible to use it in these
compatibilitylmodes.
julianoes committed Nov 22, 2022
commit b8190a250221521656330df756ee47a70a565f2e
6 changes: 5 additions & 1 deletion src/mavsdk/plugins/action/action_impl.cpp
Original file line number Diff line number Diff line change
@@ -493,8 +493,12 @@ void ActionImpl::do_orbit_async(
const double absolute_altitude_m,
const Action::ResultCallback& callback)
{
MavlinkCommandSender::CommandInt command{};
// The DO_ORBIT command is marked as WIP, hence only supported for PX4 for now.
if (_parent->compatibility_mode() != System::CompatibilityMode::Px4) {
_parent->call_user_callback([callback]() { callback(Action::Result::Unsupported); });
}

MavlinkCommandSender::CommandInt command{};
command.command = MAV_CMD_DO_ORBIT;
command.target_component_id = _parent->get_autopilot_id();
command.params.maybe_param1 = radius_m;