AP_Camera: mount backend implements set_tracking

This commit is contained in:
Randy Mackay 2023-07-06 13:57:20 +09:00
parent ddb91afdde
commit 75de6c0398
2 changed files with 17 additions and 0 deletions

View File

@ -48,6 +48,18 @@ SetFocusResult AP_Camera_Mount::set_focus(FocusType focus_type, float focus_valu
return SetFocusResult::FAILED;
}
// set tracking to none, point or rectangle (see TrackingType enum)
// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
bool AP_Camera_Mount::set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2)
{
AP_Mount* mount = AP::mount();
if (mount != nullptr) {
return mount->set_tracking(0, tracking_type, p1, p2);
}
return false;
}
// send camera information message to GCS
void AP_Camera_Mount::send_camera_information(mavlink_channel_t chan) const
{

View File

@ -46,6 +46,11 @@ public:
// focus in = -1, focus hold = 0, focus out = 1
SetFocusResult set_focus(FocusType focus_type, float focus_value) override;
// set tracking to none, point or rectangle (see TrackingType enum)
// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
bool set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2) override;
// send camera information message to GCS
void send_camera_information(mavlink_channel_t chan) const override;