Skip to content

Commit

Permalink
AP_Mount: Topotek pitch rate direction fix
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 authored and peterbarker committed Jan 4, 2025
1 parent 01964d8 commit c722841
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_Mount/AP_Mount_Topotek.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -845,7 +845,7 @@ void AP_Mount_Topotek::send_rate_target(const MountTarget& rate_rads)

// convert and constrain rates
const uint8_t roll_angle_speed = constrain_int16(degrees(rate_rads.roll) * ANGULAR_VELOCITY_CONVERSION, -99, 99);
const uint8_t pitch_angle_speed = constrain_int16(degrees(rate_rads.pitch) * ANGULAR_VELOCITY_CONVERSION, -99, 99);
const uint8_t pitch_angle_speed = constrain_int16(-degrees(rate_rads.pitch) * ANGULAR_VELOCITY_CONVERSION, -99, 99);
const uint8_t yaw_angle_speed = constrain_int16(degrees(rate_rads.yaw) * ANGULAR_VELOCITY_CONVERSION, -99, 99);

// send stop rotation command three times if target roll, pitch and yaw are zero
Expand Down

0 comments on commit c722841

Please sign in to comment.