mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: fixed build on cygwin with conflicting POINT
This commit is contained in:
parent
7175318fbb
commit
84b52374f6
|
@ -993,7 +993,7 @@ bool RC_Channel::do_aux_function_camera_image_tracking(const AuxSwitchPos ch_fla
|
||||||
}
|
}
|
||||||
// High position enables tracking a POINT in middle of image
|
// High position enables tracking a POINT in middle of image
|
||||||
// Low or Mediums disables tracking. (0.5,0.5) is still passed in but ignored
|
// Low or Mediums disables tracking. (0.5,0.5) is still passed in but ignored
|
||||||
return camera->set_tracking(ch_flag == AuxSwitchPos::HIGH ? TrackingType::POINT : TrackingType::NONE, Vector2f{0.5, 0.5}, Vector2f{});
|
return camera->set_tracking(ch_flag == AuxSwitchPos::HIGH ? TrackingType::TRK_POINT : TrackingType::TRK_NONE, Vector2f{0.5, 0.5}, Vector2f{});
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue