Skip to content

Dds quadplane takeoff #30098

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

Merged
merged 2 commits into from
May 28, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
6 changes: 6 additions & 0 deletions ArduPlane/Plane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1012,6 +1012,12 @@ bool Plane::is_taking_off() const
return control_mode->is_taking_off();
}

#if HAL_QUADPLANE_ENABLED
bool Plane::start_takeoff(const float alt) {
return plane.quadplane.available() && quadplane.do_user_takeoff(alt);
}
#endif

// correct AHRS pitch for PTCH_TRIM_DEG in non-VTOL modes, and return VTOL view in VTOL
void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const
{
Expand Down
2 changes: 2 additions & 0 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -1002,6 +1002,8 @@ class Plane : public AP_Vehicle {
void do_vtol_land(const AP_Mission::Mission_Command& cmd);
bool verify_nav_wp(const AP_Mission::Mission_Command& cmd);
#if HAL_QUADPLANE_ENABLED
// vtol takeoff from AP_Vehicle for quadplane.
bool start_takeoff(const float alt) override;
bool verify_landing_vtol_approach(const AP_Mission::Mission_Command& cmd);
#endif
void do_wait_delay(const AP_Mission::Mission_Command& cmd);
Expand Down
2 changes: 1 addition & 1 deletion Tools/ros2/ardupilot_msgs/srv/Takeoff.srv
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@

# This service requests the vehicle to takeoff
# This service requests the vehicle to takeoff (VTOL style for QuadPlane).

# alt : Set the takeoff altitude above home or above terrain(in case of rangefinder)

Expand Down
Loading