Skip to content

Commit

Permalink
att_control: remove resetting the attitude setpoint
Browse files Browse the repository at this point in the history
since the position controller publishes them again already when disarmed.
  • Loading branch information
MaEtUgR authored and dagar committed Nov 24, 2019
1 parent d3bd251 commit 28755d5
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 22 deletions.
7 changes: 0 additions & 7 deletions src/modules/mc_att_control/mc_att_control_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -247,13 +247,6 @@ void
MulticopterAttitudeControl::control_attitude()
{
_v_att_sp_sub.update(&_v_att_sp);

// reinitialize the setpoint while not armed to make sure no value from the last mode or flight is still kept
if (!_v_control_mode.flag_armed) {
Quatf().copyTo(_v_att_sp.q_d);
Vector3f().copyTo(_v_att_sp.thrust_body);
}

_rates_sp = _attitude_control.update(Quatf(_v_att.q), Quatf(_v_att_sp.q_d), _v_att_sp.yaw_sp_move_rate);
}

Expand Down
15 changes: 0 additions & 15 deletions src/modules/vtol_att_control/vtol_att_control_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -389,13 +389,6 @@ VtolAttitudeControl::Run()
_fw_virtual_att_sp_sub.update(&_fw_virtual_att_sp);

if (mc_att_sp_updated || fw_att_sp_updated) {

// reinitialize the setpoint while not armed to make sure no value from the last mode or flight is still kept
if (!_v_control_mode.flag_armed) {
Vector3f().copyTo(_mc_virtual_att_sp.thrust_body);
Vector3f().copyTo(_v_att_sp.thrust_body);
}

_vtol_type->update_transition_state();
_v_att_sp_pub.publish(_v_att_sp);
}
Expand All @@ -408,14 +401,6 @@ VtolAttitudeControl::Run()
_vtol_vehicle_status.vtol_in_trans_mode = false;
_vtol_vehicle_status.in_transition_to_fw = false;

if (mc_att_sp_updated) {
// reinitialize the setpoint while not armed to make sure no value from the last mode or flight is still kept
if (!_v_control_mode.flag_armed) {
Vector3f().copyTo(_mc_virtual_att_sp.thrust_body);
Vector3f().copyTo(_v_att_sp.thrust_body);
}
}

_vtol_type->update_mc_state();
_v_att_sp_pub.publish(_v_att_sp);

Expand Down

0 comments on commit 28755d5

Please sign in to comment.