Skip to content

Commit

Permalink
gimbal - input_mavlink: return NoUpdate by default
Browse files Browse the repository at this point in the history
  • Loading branch information
fury1895 authored and julianoes committed Jun 19, 2024
1 parent 741c7ab commit e4fc302
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion src/modules/gimbal/input_mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -518,7 +518,7 @@ InputMavlinkGimbalV2::update(unsigned int timeout_ms, ControlData &control_data,
// We can't return early instead because we need to copy all topics that triggered poll.

bool exit_loop = false;
UpdateResult update_result = already_active ? UpdateResult::UpdatedActive : UpdateResult::NoUpdate;
UpdateResult update_result = UpdateResult::NoUpdate;

while (!exit_loop && poll_timeout >= 0) {

Expand Down

0 comments on commit e4fc302

Please sign in to comment.