Copter: RTL accepts do-change-speed commands

This commit is contained in:
Randy Mackay 2023-04-19 21:28:51 +09:00
parent 110901e95d
commit ca7473d960
2 changed files with 22 additions and 0 deletions

View File

@ -1319,6 +1319,10 @@ public:
bool use_pilot_yaw() const override; bool use_pilot_yaw() const override;
bool set_speed_xy(float speed_xy_cms) override;
bool set_speed_up(float speed_up_cms) override;
bool set_speed_down(float speed_down_cms) override;
// RTL states // RTL states
enum class SubMode : uint8_t { enum class SubMode : uint8_t {
STARTING, STARTING,

View File

@ -554,4 +554,22 @@ bool ModeRTL::use_pilot_yaw(void) const
return allow_yaw_option || land_repositioning || final_landing; return allow_yaw_option || land_repositioning || final_landing;
} }
bool ModeRTL::set_speed_xy(float speed_xy_cms)
{
copter.wp_nav->set_speed_xy(speed_xy_cms);
return true;
}
bool ModeRTL::set_speed_up(float speed_up_cms)
{
copter.wp_nav->set_speed_up(speed_up_cms);
return true;
}
bool ModeRTL::set_speed_down(float speed_down_cms)
{
copter.wp_nav->set_speed_down(speed_down_cms);
return true;
}
#endif #endif