Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Camera: CAMERA_FOV_STATUS includes horizontal and vertical field-of-view #25441

Merged
merged 1 commit into from
Nov 2, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions libraries/AP_Camera/AP_Camera_Backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -280,8 +280,8 @@ void AP_Camera_Backend::send_camera_fov_status(mavlink_channel_t chan) const
poi_loc.lng,
poi_loc.alt,
quat_array,
NaN, // currently setting hfov as NaN
NaN // currently setting vfov as NaN
horizontal_fov() > 0 ? horizontal_fov() : NaN,
vertical_fov() > 0 ? vertical_fov() : NaN
);
}
#endif
Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_Camera/AP_Camera_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,10 @@ class AP_Camera_Backend
// set camera lens as a value from 0 to 5
virtual bool set_lens(uint8_t lens) { return false; }

// get camera image horizontal or vertical field of view in degrees. returns 0 if unknown
float horizontal_fov() const { return MAX(0, _params.hfov); }
float vertical_fov() const { return MAX(0, _params.vfov); }

// handle MAVLink messages from the camera
virtual void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) {}

Expand Down
16 changes: 16 additions & 0 deletions libraries/AP_Camera/AP_Camera_Params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,22 @@ const AP_Param::GroupInfo AP_Camera_Params::var_info[] = {
// @User: Standard
AP_GROUPINFO("_MNT_INST", 11, AP_Camera_Params, mount_instance, 0),

// @Param: _HFOV
// @DisplayName: Camera horizontal field of view
// @Description: Camera horizontal field of view. 0 if unknown
// @Units: deg
// @Range: 0 360
// @User: Standard
AP_GROUPINFO("_HFOV", 12, AP_Camera_Params, hfov, 0),

// @Param: _VFOV
// @DisplayName: Camera vertical field of view
// @Description: Camera vertical field of view. 0 if unknown
// @Units: deg
// @Range: 0 180
// @User: Standard
AP_GROUPINFO("_VFOV", 13, AP_Camera_Params, vfov, 0),

AP_GROUPEND

};
Expand Down
2 changes: 2 additions & 0 deletions libraries/AP_Camera/AP_Camera_Params.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@ class AP_Camera_Params {
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 instance to which camera is associated with
AP_Float hfov; // horizontal field of view in degrees
AP_Float vfov; // vertical field of view in degrees

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