Skip to content

Commit

Permalink
Revert "rover_pos_control: thrust normalization for joystick input (#…
Browse files Browse the repository at this point in the history
…20885)"

This reverts commit 22f7d91.
  • Loading branch information
AlexKlimaj authored and mrpollo committed Jul 11, 2023
1 parent ecd1e9f commit 89b238f
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions src/modules/rover_pos_control/RoverPositionControl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,7 +138,7 @@ RoverPositionControl::manual_control_setpoint_poll()
}

_att_sp.yaw_body = _manual_yaw_sp;
_att_sp.thrust_body[0] = (_manual_control_setpoint.throttle + 1.f) * .5f;
_att_sp.thrust_body[0] = _manual_control_setpoint.throttle;

Quatf q(Eulerf(_att_sp.roll_body, _att_sp.pitch_body, _att_sp.yaw_body));
q.copyTo(_att_sp.q_d);
Expand All @@ -152,7 +152,7 @@ RoverPositionControl::manual_control_setpoint_poll()
// Set heading from the manual roll input channel
_yaw_control = _manual_control_setpoint.roll; // Nominally yaw: _manual_control_setpoint.yaw;
// Set throttle from the manual throttle channel
_throttle_control = (_manual_control_setpoint.throttle + 1.f) * .5f;
_throttle_control = _manual_control_setpoint.throttle;
_reset_yaw_sp = true;
}

Expand Down

0 comments on commit 89b238f

Please sign in to comment.