mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: add and use SetFocusResult
This commit is contained in:
parent
958622523f
commit
485fee36ab
|
@ -742,11 +742,11 @@ bool AP_Mount::set_zoom(uint8_t instance, ZoomType zoom_type, float zoom_value)
|
|||
|
||||
// set focus specified as rate, percentage or auto
|
||||
// focus in = -1, focus hold = 0, focus out = 1
|
||||
bool AP_Mount::set_focus(uint8_t instance, FocusType focus_type, float focus_value)
|
||||
SetFocusResult AP_Mount::set_focus(uint8_t instance, FocusType focus_type, float focus_value)
|
||||
{
|
||||
auto *backend = get_instance(instance);
|
||||
if (backend == nullptr) {
|
||||
return false;
|
||||
return SetFocusResult::FAILED;
|
||||
}
|
||||
return backend->set_focus(focus_type, focus_value);
|
||||
}
|
||||
|
|
|
@ -216,7 +216,7 @@ public:
|
|||
|
||||
// set focus specified as rate, percentage or auto
|
||||
// focus in = -1, focus hold = 0, focus out = 1
|
||||
bool set_focus(uint8_t instance, FocusType focus_type, float focus_value);
|
||||
SetFocusResult set_focus(uint8_t instance, FocusType focus_type, float focus_value);
|
||||
|
||||
// send camera information message to GCS
|
||||
void send_camera_information(mavlink_channel_t chan) const;
|
||||
|
|
|
@ -155,7 +155,7 @@ public:
|
|||
|
||||
// set focus specified as rate, percentage or auto
|
||||
// focus in = -1, focus hold = 0, focus out = 1
|
||||
virtual bool set_focus(FocusType focus_type, float focus_value) { return false; }
|
||||
virtual SetFocusResult set_focus(FocusType focus_type, float focus_value) { return SetFocusResult::UNSUPPORTED; }
|
||||
|
||||
// send camera information message to GCS
|
||||
virtual void send_camera_information(mavlink_channel_t chan) const {}
|
||||
|
|
|
@ -756,7 +756,7 @@ void AP_Mount_Siyi::update_zoom_control()
|
|||
|
||||
// set focus specified as rate, percentage or auto
|
||||
// focus in = -1, focus hold = 0, focus out = 1
|
||||
bool AP_Mount_Siyi::set_focus(FocusType focus_type, float focus_value)
|
||||
SetFocusResult AP_Mount_Siyi::set_focus(FocusType focus_type, float focus_value)
|
||||
{
|
||||
switch (focus_type) {
|
||||
case FocusType::RATE: {
|
||||
|
@ -767,17 +767,23 @@ bool AP_Mount_Siyi::set_focus(FocusType focus_type, float focus_value)
|
|||
// Siyi API specifies -1 should be sent as 255
|
||||
focus_step = UINT8_MAX;
|
||||
}
|
||||
return send_1byte_packet(SiyiCommandId::MANUAL_FOCUS, (uint8_t)focus_step);
|
||||
if (!send_1byte_packet(SiyiCommandId::MANUAL_FOCUS, (uint8_t)focus_step)) {
|
||||
return SetFocusResult::FAILED;
|
||||
}
|
||||
return SetFocusResult::ACCEPTED;
|
||||
}
|
||||
case FocusType::PCT:
|
||||
// not supported
|
||||
return false;
|
||||
return SetFocusResult::INVALID_PARAMETERS;
|
||||
case FocusType::AUTO:
|
||||
return send_1byte_packet(SiyiCommandId::AUTO_FOCUS, 1);
|
||||
if (!send_1byte_packet(SiyiCommandId::AUTO_FOCUS, 1)) {
|
||||
return SetFocusResult::FAILED;
|
||||
}
|
||||
return SetFocusResult::ACCEPTED;
|
||||
}
|
||||
|
||||
// unsupported focus type
|
||||
return false;
|
||||
return SetFocusResult::INVALID_PARAMETERS;
|
||||
}
|
||||
|
||||
// send camera information message to GCS
|
||||
|
|
|
@ -70,7 +70,7 @@ public:
|
|||
|
||||
// set focus specified as rate, percentage or auto
|
||||
// focus in = -1, focus hold = 0, focus out = 1
|
||||
bool set_focus(FocusType focus_type, float focus_value) override;
|
||||
SetFocusResult set_focus(FocusType focus_type, float focus_value) override;
|
||||
|
||||
// send camera information message to GCS
|
||||
void send_camera_information(mavlink_channel_t chan) const override;
|
||||
|
|
|
@ -164,10 +164,10 @@ bool AP_Mount_Xacti::record_video(bool start_recording)
|
|||
|
||||
// set focus specified as rate, percentage or auto
|
||||
// focus in = -1, focus hold = 0, focus out = 1
|
||||
bool AP_Mount_Xacti::set_focus(FocusType focus_type, float focus_value)
|
||||
SetFocusResult AP_Mount_Xacti::set_focus(FocusType focus_type, float focus_value)
|
||||
{
|
||||
if (_detected_modules[_instance].ap_dronecan == nullptr) {
|
||||
return false;
|
||||
return SetFocusResult::FAILED;
|
||||
}
|
||||
|
||||
// convert focus type and value to parameter value
|
||||
|
@ -185,11 +185,14 @@ bool AP_Mount_Xacti::set_focus(FocusType focus_type, float focus_value)
|
|||
break;
|
||||
default:
|
||||
// unsupported forucs mode
|
||||
return false;
|
||||
return SetFocusResult::INVALID_PARAMETERS;
|
||||
}
|
||||
|
||||
// set FocusMode parameter
|
||||
return _detected_modules[_instance].ap_dronecan->set_parameter_on_node(_detected_modules[_instance].node_id, XACTI_PARAM_FOCUSMODE, focus_param_value, ¶m_int_cb);
|
||||
if (!_detected_modules[_instance].ap_dronecan->set_parameter_on_node(_detected_modules[_instance].node_id, XACTI_PARAM_FOCUSMODE, focus_param_value, ¶m_int_cb)) {
|
||||
return SetFocusResult::FAILED;
|
||||
}
|
||||
return SetFocusResult::ACCEPTED;
|
||||
}
|
||||
|
||||
// send camera information message to GCS
|
||||
|
|
|
@ -53,7 +53,7 @@ public:
|
|||
|
||||
// set focus specified as rate, percentage or auto
|
||||
// focus in = -1, focus hold = 0, focus out = 1
|
||||
bool set_focus(FocusType focus_type, float focus_value) override;
|
||||
SetFocusResult set_focus(FocusType focus_type, float focus_value) override;
|
||||
|
||||
// send camera information message to GCS
|
||||
void send_camera_information(mavlink_channel_t chan) const override;
|
||||
|
|
Loading…
Reference in New Issue