mirror of https://github.com/ArduPilot/ardupilot
AP_Camera: camera_fov_status includes field-of-view
This commit is contained in:
parent
7d4d2f98bf
commit
73589a276e
|
@ -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
|
||||
|
|
|
@ -85,6 +85,10 @@ public:
|
|||
// 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) {}
|
||||
|
||||
|
|
|
@ -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
|
||||
|
||||
};
|
||||
|
|
|
@ -23,6 +23,8 @@ public:
|
|||
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;
|
||||
|
|
Loading…
Reference in New Issue