Skip to content

Commit

Permalink
AP_Camera: add parameter CAMx_MNT_INST for associating camera with co…
Browse files Browse the repository at this point in the history
…rresponding mount
  • Loading branch information
khanasif786 committed Jul 27, 2023
1 parent 617fb98 commit a68376c
Show file tree
Hide file tree
Showing 4 changed files with 26 additions and 6 deletions.
22 changes: 16 additions & 6 deletions libraries/AP_Camera/AP_Camera_Mount.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ bool AP_Camera_Mount::trigger_pic()
{
AP_Mount* mount = AP::mount();
if (mount != nullptr) {
mount->take_picture(0);
mount->take_picture(get_mount_instance());
return true;
}
return false;
Expand All @@ -22,7 +22,7 @@ bool AP_Camera_Mount::record_video(bool start_recording)
{
AP_Mount* mount = AP::mount();
if (mount != nullptr) {
return mount->record_video(0, start_recording);
return mount->record_video(get_mount_instance(), start_recording);
}
return false;
}
Expand All @@ -32,7 +32,7 @@ bool AP_Camera_Mount::set_zoom(ZoomType zoom_type, float zoom_value)
{
AP_Mount* mount = AP::mount();
if (mount != nullptr) {
return mount->set_zoom(0, zoom_type, zoom_value);
return mount->set_zoom(get_mount_instance(), zoom_type, zoom_value);
}
return false;
}
Expand All @@ -43,7 +43,7 @@ SetFocusResult AP_Camera_Mount::set_focus(FocusType focus_type, float focus_valu
{
AP_Mount* mount = AP::mount();
if (mount != nullptr) {
return mount->set_focus(0, focus_type, focus_value);
return mount->set_focus(get_mount_instance(), focus_type, focus_value);
}
return SetFocusResult::FAILED;
}
Expand All @@ -55,7 +55,7 @@ bool AP_Camera_Mount::set_tracking(TrackingType tracking_type, const Vector2f& p
{
AP_Mount* mount = AP::mount();
if (mount != nullptr) {
return mount->set_tracking(0, tracking_type, p1, p2);
return mount->set_tracking(get_mount_instance(), tracking_type, p1, p2);
}
return false;
}
Expand All @@ -66,7 +66,7 @@ bool AP_Camera_Mount::set_lens(uint8_t lens)
{
AP_Mount* mount = AP::mount();
if (mount != nullptr) {
return mount->set_lens(0, lens);
return mount->set_lens(get_mount_instance(), lens);
}
return false;
}
Expand All @@ -89,4 +89,14 @@ void AP_Camera_Mount::send_camera_settings(mavlink_channel_t chan) const
}
}

// get correspoding mount instance for the camera
uint8_t AP_Camera_Mount::get_mount_instance() const
{
// instance 0 means default
if (_params.mount_instance.get() == 0) {
return _instance;
}
return _params.mount_instance.get() - 1;
}

#endif // AP_CAMERA_MOUNT_ENABLED
3 changes: 3 additions & 0 deletions libraries/AP_Camera/AP_Camera_Mount.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,9 @@ class AP_Camera_Mount : public AP_Camera_Backend

// send camera settings message to GCS
void send_camera_settings(mavlink_channel_t chan) const override;

// get correspoding mount instance for the camera
uint8_t get_mount_instance() const;
};

#endif // AP_CAMERA_MOUNT_ENABLED
6 changes: 6 additions & 0 deletions libraries/AP_Camera/AP_Camera_Params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,12 @@ const AP_Param::GroupInfo AP_Camera_Params::var_info[] = {
// @User: Standard
AP_GROUPINFO("_OPTIONS", 10, AP_Camera_Params, options, 0),

// @Param: _MNT_INST
// @DisplayName: Camera Mount instance
// @Description: Mount instace to which camera is associated with. By default its 0 means camera and mount have identical instance numbers e.g. camera1 and mount1
// @User: Standard
AP_GROUPINFO("_MNT_INST", 11, AP_Camera_Params, mount_instance, 0),

AP_GROUPEND

};
Expand Down
1 change: 1 addition & 0 deletions libraries/AP_Camera/AP_Camera_Params.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@ class AP_Camera_Params {
AP_Int8 relay_on; // relay value to trigger camera
AP_Float interval_min; // minimum time (in seconds) between shots required by camera
AP_Int8 options; // whether to start recording when armed and stop when disarmed
AP_Int8 mount_instance; // mount instace to which camera is associated with

// pin number for accurate camera feedback messages
AP_Int8 feedback_pin;
Expand Down

0 comments on commit a68376c

Please sign in to comment.