void ActionImpl::takeoff_async(const Action::ResultCallback& callback) const { if (_system_impl->autopilot() == Autopilot::Px4) { takeoff_async_px4(callback); } else { takeoff_async_apm(callback); } } void ActionImpl::takeoff_async_px4(const Action::ResultCallback& callback) const { MavlinkCommandSender::CommandLong command{}; command.command = MAV_CMD_NAV_TAKEOFF; command.target_component_id = _system_impl->get_autopilot_id(); _system_impl->send_command_async( command, [this, callback](MavlinkCommandSender::Result result, float) { command_result_callback(result, callback); }); } void ActionImpl::takeoff_async_apm(const Action::ResultCallback& callback) const { auto send_takeoff_command = [this, callback]() { MavlinkCommandSender::CommandLong command{}; command.command = MAV_CMD_NAV_TAKEOFF; command.target_component_id = _system_impl->get_autopilot_id(); command.params.maybe_param7 = get_takeoff_altitude().second; _system_impl->send_command_async( command, [this, callback](MavlinkCommandSender::Result result, float) { command_result_callback(result, callback); }); }; if (_system_impl->get_flight_mode() != FlightMode::Offboard) { _system_impl->set_flight_mode_async( FlightMode::Offboard, [callback, send_takeoff_command](MavlinkCommandSender::Result result, float) { Action::Result action_result = action_result_from_command_result(result); if (action_result != Action::Result::Success) { if (callback) { callback(action_result); } } send_takeoff_command(); }); } else { send_takeoff_command(); } }