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

Copter: accept do-change-speed during takeoff #25654

Merged
merged 4 commits into from
Dec 5, 2023
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
8 changes: 1 addition & 7 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -404,13 +404,7 @@ bool Copter::set_circle_rate(float rate_dps)
// set desired speed (m/s). Used for scripting.
bool Copter::set_desired_speed(float speed)
{
// exit if vehicle is not in auto mode
if (!flightmode->is_autopilot()) {
return false;
}

wp_nav->set_speed_xy(speed * 100.0f);
return true;
return flightmode->set_speed_xy(speed * 100.0f);
}

#if MODE_AUTO_ENABLED == ENABLED
Expand Down
8 changes: 8 additions & 0 deletions ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -679,6 +679,7 @@ class ModeAuto : public Mode {
int32_t condition_value; // used in condition commands (eg delay, change alt, etc.)
uint32_t condition_start;

// Land within Auto state
enum class State {
FlyToLocation = 0,
Descending = 1
Expand Down Expand Up @@ -713,6 +714,13 @@ class ModeAuto : public Mode {
float climb_rate; // climb rate in m/s. provided by mission command
uint32_t start_ms; // system time that nav attitude time command was received (used for timeout)
} nav_attitude_time;

// desired speeds
struct {
float xy; // desired speed horizontally in m/s. 0 if unset
float up; // desired speed upwards in m/s. 0 if unset
float down; // desired speed downwards in m/s. 0 if unset
} desired_speed_override;
};

#if AUTOTUNE_ENABLED == ENABLED
Expand Down
20 changes: 19 additions & 1 deletion ArduCopter/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,9 @@ bool ModeAuto::init(bool ignore_checks)
// initialise waypoint and spline controller
wp_nav->wp_and_spline_init();

// initialise desired speed overrides
desired_speed_override = {0, 0, 0};

// set flag to start mission
waiting_to_start = true;

Expand Down Expand Up @@ -370,7 +373,16 @@ bool ModeAuto::wp_start(const Location& dest_loc)
stopping_point = takeoff_complete_pos.tofloat();
}
}
wp_nav->wp_and_spline_init(0, stopping_point);
float des_speed_xy_cm = is_positive(desired_speed_override.xy) ? (desired_speed_override.xy * 100) : 0;
wp_nav->wp_and_spline_init(des_speed_xy_cm, stopping_point);

// override speeds up and down if necessary
if (is_positive(desired_speed_override.up)) {
wp_nav->set_speed_up(desired_speed_override.up * 100.0);
}
if (is_positive(desired_speed_override.down)) {
wp_nav->set_speed_down(desired_speed_override.down * 100.0);
}
}

if (!wp_nav->set_wp_destination_loc(dest_loc)) {
Expand Down Expand Up @@ -585,18 +597,21 @@ bool ModeAuto::use_pilot_yaw(void) const
bool ModeAuto::set_speed_xy(float speed_xy_cms)
{
copter.wp_nav->set_speed_xy(speed_xy_cms);
desired_speed_override.xy = speed_xy_cms * 0.01;
return true;
}

bool ModeAuto::set_speed_up(float speed_up_cms)
{
copter.wp_nav->set_speed_up(speed_up_cms);
desired_speed_override.up = speed_up_cms * 0.01;
return true;
}

bool ModeAuto::set_speed_down(float speed_down_cms)
{
copter.wp_nav->set_speed_down(speed_down_cms);
desired_speed_override.down = speed_down_cms * 0.01;
return true;
}

Expand Down Expand Up @@ -1855,10 +1870,13 @@ void ModeAuto::do_change_speed(const AP_Mission::Mission_Command& cmd)
if (cmd.content.speed.target_ms > 0) {
if (cmd.content.speed.speed_type == 2) {
copter.wp_nav->set_speed_up(cmd.content.speed.target_ms * 100.0f);
desired_speed_override.up = cmd.content.speed.target_ms;
} else if (cmd.content.speed.speed_type == 3) {
copter.wp_nav->set_speed_down(cmd.content.speed.target_ms * 100.0f);
desired_speed_override.down = cmd.content.speed.target_ms;
} else {
copter.wp_nav->set_speed_xy(cmd.content.speed.target_ms * 100.0f);
desired_speed_override.xy = cmd.content.speed.target_ms;
}
}
}
Expand Down
23 changes: 12 additions & 11 deletions Tools/autotest/ArduCopter_Tests/DO_CHANGE_SPEED/mission.txt
Original file line number Diff line number Diff line change
@@ -1,11 +1,12 @@
QGC WPL 110
0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.090027 1
1 0 3 22 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 20.000000 1
2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.362656 149.165072 20.000000 1
3 0 0 178 1.000000 15.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.360174 149.167908 14.000000 1
5 0 0 178 1.000000 10.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363296 149.169244 18.000000 1
7 0 0 178 1.000000 16.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364115 149.165747 20.000000 1
9 0 0 20 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1
QGC WPL 110
0 1 0 16 0 0 0 0 -35.3632620 149.1652370 584.090000 1
1 0 3 22 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 20.000000 1
2 0 3 178 0.00000000 4.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.000000 1
3 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36265600 149.16507200 20.000000 1
4 0 0 178 1.00000000 15.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.000000 1
5 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36017400 149.16790800 14.000000 1
6 0 0 178 1.00000000 10.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.000000 1
7 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36329600 149.16924400 18.000000 1
8 0 0 178 1.00000000 16.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.000000 1
9 0 3 16 0.00000000 0.00000000 0.00000000 0.00000000 -35.36411500 149.16574700 20.000000 1
10 0 0 20 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.00000000 0.000000 1
13 changes: 10 additions & 3 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -9505,22 +9505,29 @@ def DO_CHANGE_SPEED(self):
self.wait_ready_to_arm()
self.arm_vehicle()

self.wait_current_waypoint(2)
self.wait_current_waypoint(1)
self.wait_groundspeed(
3.5, 4.5,
minimum_duration=5,
timeout=60,
)

self.wait_current_waypoint(3)
self.wait_groundspeed(
14.5, 15.5,
minimum_duration=10,
timeout=60,
)

self.wait_current_waypoint(4)
self.wait_current_waypoint(5)
self.wait_groundspeed(
9.5, 11.5,
minimum_duration=10,
timeout=60,
)

self.set_parameter("ANGLE_MAX", 6000)
self.wait_current_waypoint(6)
self.wait_current_waypoint(7)
self.wait_groundspeed(
15.5, 16.5,
minimum_duration=10,
Expand Down
Loading