VehicleAttitudeSetpoint: rename fw_control_yaw to fw_control_yaw_wheel to make usage clearer

Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
Silvan Fuhrer 2022-10-31 16:54:32 +01:00 committed by Daniel Agar
parent 4b036e6723
commit 6c611a7e8b
4 changed files with 9 additions and 10 deletions

View File

@ -15,7 +15,7 @@ float32[3] thrust_body # Normalized thrust command in body NED frame [-1,1]
bool reset_integral # Reset roll/pitch/yaw integrals (navigation logic change)
bool fw_control_yaw # control heading with rudder (used for auto takeoff on runway)
bool fw_control_yaw_wheel # control heading with steering wheel (used for auto takeoff on runway)
uint8 apply_flaps # flap config specifier
uint8 FLAPS_OFF = 0 # no flaps

View File

@ -364,12 +364,11 @@ void FixedwingAttitudeControl::Run()
// the position controller will not emit attitude setpoints in some modes
// we need to make sure that this flag is reset
_att_sp.fw_control_yaw = _att_sp.fw_control_yaw && _vcontrol_mode.flag_control_auto_enabled;
_att_sp.fw_control_yaw_wheel = _att_sp.fw_control_yaw_wheel && _vcontrol_mode.flag_control_auto_enabled;
bool wheel_control = false;
// TODO: manual wheel_control on ground?
if (_param_fw_w_en.get() && _att_sp.fw_control_yaw) {
if (_param_fw_w_en.get() && _att_sp.fw_control_yaw_wheel) {
wheel_control = true;
}

View File

@ -1439,7 +1439,7 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo
ground_speed);
// yaw control is disabled once in "taking off" state
_att_sp.fw_control_yaw = _runway_takeoff.controlYaw();
_att_sp.fw_control_yaw_wheel = _runway_takeoff.controlYaw();
// XXX: hacky way to pass through manual nose-wheel incrementing. need to clean this interface.
if (_param_rwto_nudge.get()) {
@ -1447,7 +1447,7 @@ FixedwingPositionControl::control_auto_takeoff(const hrt_abstime &now, const flo
}
// tune up the lateral position control guidance when on the ground
if (_att_sp.fw_control_yaw) {
if (_att_sp.fw_control_yaw_wheel) {
_npfg.setPeriod(_param_rwto_l1_period.get());
_l1_control.set_l1_period(_param_rwto_l1_period.get());
@ -1827,7 +1827,7 @@ FixedwingPositionControl::control_auto_landing(const hrt_abstime &now, const flo
_att_sp.pitch_body = get_tecs_pitch();
// enable direct yaw control using rudder/wheel
_att_sp.fw_control_yaw = true;
_att_sp.fw_control_yaw_wheel = true;
// XXX: hacky way to pass through manual nose-wheel incrementing. need to clean this interface.
if (_param_fw_lnd_nudge.get() > LandingNudgingOption::kNudgingDisabled) {
@ -1900,7 +1900,7 @@ FixedwingPositionControl::control_auto_landing(const hrt_abstime &now, const flo
_att_sp.yaw_body = _yaw;
// enable direct yaw control using rudder/wheel
_att_sp.fw_control_yaw = false;
_att_sp.fw_control_yaw_wheel = false;
_att_sp.thrust_body[0] = (_landed) ? _param_fw_thr_idle.get() : get_tecs_thrust();
}
@ -2315,7 +2315,7 @@ FixedwingPositionControl::Run()
_att_sp.reset_integral = false;
// by default we don't want yaw to be contoller directly with rudder
_att_sp.fw_control_yaw = false;
_att_sp.fw_control_yaw_wheel = false;
// default to zero - is used (IN A HACKY WAY) to pass direct nose wheel steering via yaw stick to the actuators during auto takeoff
_att_sp.yaw_sp_move_rate = 0.0f;

View File

@ -63,7 +63,7 @@ TEST(PositionControlTest, EmptySetpoint)
EXPECT_EQ(Quatf(attitude.q_d), Quatf(1.f, 0.f, 0.f, 0.f));
EXPECT_EQ(Vector3f(attitude.thrust_body), Vector3f(0.f, 0.f, 0.f));
EXPECT_EQ(attitude.reset_integral, false);
EXPECT_EQ(attitude.fw_control_yaw, false);
EXPECT_EQ(attitude.fw_control_yaw_wheel, false);
EXPECT_FLOAT_EQ(attitude.apply_flaps, 0.f);//vehicle_attitude_setpoint_s::FLAPS_OFF); // TODO why no reference?
}