mirror of https://github.com/ArduPilot/ardupilot
Copter: Add set_yaw_angle_offset() function to AutoYaw mode
This commit is contained in:
parent
2c80c702bc
commit
3bac3618e1
|
@ -149,6 +149,18 @@ void Mode::AutoYaw::set_yaw_angle_rate(float yaw_angle_d, float yaw_rate_ds)
|
|||
set_mode(Mode::ANGLE_RATE);
|
||||
}
|
||||
|
||||
// set_yaw_angle_offset - sets the yaw look at heading for auto mode, as an offset from the current yaw angle
|
||||
void Mode::AutoYaw::set_yaw_angle_offset(const float yaw_angle_offset_d)
|
||||
{
|
||||
_last_update_ms = millis();
|
||||
|
||||
_yaw_angle_cd = wrap_360_cd(_yaw_angle_cd + (yaw_angle_offset_d * 100.0));
|
||||
_yaw_rate_cds = 0.0f;
|
||||
|
||||
// set yaw mode
|
||||
set_mode(Mode::ANGLE_RATE);
|
||||
}
|
||||
|
||||
// set_roi - sets the yaw to look at roi for auto mode
|
||||
void Mode::AutoYaw::set_roi(const Location &roi_location)
|
||||
{
|
||||
|
|
|
@ -335,6 +335,8 @@ public:
|
|||
|
||||
void set_yaw_angle_rate(float yaw_angle_d, float yaw_rate_ds);
|
||||
|
||||
void set_yaw_angle_offset(const float yaw_angle_offset_d);
|
||||
|
||||
bool reached_fixed_yaw_target();
|
||||
|
||||
#if WEATHERVANE_ENABLED
|
||||
|
|
Loading…
Reference in New Issue