AP_Camera: fixed build on cygwin with conflicting POINT

This commit is contained in:
Andrew Tridgell 2023-05-10 15:09:33 +10:00
parent 99e6958e36
commit 7175318fbb
2 changed files with 6 additions and 6 deletions

View File

@ -247,17 +247,17 @@ MAV_RESULT AP_Camera::handle_command_long(const mavlink_command_long_t &packet)
take_picture();
return MAV_RESULT_ACCEPTED;
case MAV_CMD_CAMERA_TRACK_POINT:
if (set_tracking(TrackingType::POINT, Vector2f{packet.param1, packet.param2}, Vector2f{})) {
if (set_tracking(TrackingType::TRK_POINT, Vector2f{packet.param1, packet.param2}, Vector2f{})) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_UNSUPPORTED;
case MAV_CMD_CAMERA_TRACK_RECTANGLE:
if (set_tracking(TrackingType::RECTANGLE, Vector2f{packet.param1, packet.param2}, Vector2f{packet.param3, packet.param4})) {
if (set_tracking(TrackingType::TRK_RECTANGLE, Vector2f{packet.param1, packet.param2}, Vector2f{packet.param3, packet.param4})) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_UNSUPPORTED;
case MAV_CMD_CAMERA_STOP_TRACKING:
if (set_tracking(TrackingType::NONE, Vector2f{}, Vector2f{})) {
if (set_tracking(TrackingType::TRK_NONE, Vector2f{}, Vector2f{})) {
return MAV_RESULT_ACCEPTED;
}
return MAV_RESULT_UNSUPPORTED;

View File

@ -22,7 +22,7 @@ enum class FocusType : uint8_t {
// tracking types when tracking an object in the video stream
enum class TrackingType : uint8_t {
NONE = 0, // tracking is inactive
POINT = 1, // tracking a point
RECTANGLE = 2 // tracking a rectangle
TRK_NONE = 0, // tracking is inactive
TRK_POINT = 1, // tracking a point
TRK_RECTANGLE = 2 // tracking a rectangle
};