forked from Archive/PX4-Autopilot
rename camera capture feedback param and move it from camera_feedback module to camera capture driver
This commit is contained in:
parent
42afc88285
commit
d49752141d
|
@ -377,7 +377,8 @@ else
|
|||
fi
|
||||
|
||||
# Camera capture driver
|
||||
if param compare CAM_HSHOE_FBACK 1
|
||||
if param greater CAM_CAP_FBACK 0
|
||||
then
|
||||
if camera_capture start
|
||||
then
|
||||
set FMU_MODE pwm4
|
||||
|
|
|
@ -53,7 +53,7 @@ CameraCapture::CameraCapture() :
|
|||
_trigger_pub(nullptr),
|
||||
_command_ack_pub(nullptr),
|
||||
_command_sub(-1),
|
||||
_hotshoe_trigger_feedback(false),
|
||||
_camera_capture_feedback(false),
|
||||
_capture_seq(0),
|
||||
_last_fall_time(0),
|
||||
_last_exposure_time(0),
|
||||
|
@ -66,10 +66,10 @@ CameraCapture::CameraCapture() :
|
|||
_p_strobe_delay = param_find("CAM_CAP_DELAY");
|
||||
param_get(_p_strobe_delay, &_strobe_delay);
|
||||
|
||||
_p_hotshoe_trigger_feedback = param_find("CAM_HSHOE_FBACK");
|
||||
param_get(_p_hotshoe_trigger_feedback, &_hotshoe_trigger_feedback);
|
||||
_p_camera_capture_feedback = param_find("CAM_CAP_FBACK");
|
||||
param_get(_p_camera_capture_feedback, &_camera_capture_feedback);
|
||||
|
||||
if (_hotshoe_trigger_feedback != 0) {
|
||||
if (_camera_capture_feedback != 0) {
|
||||
struct camera_trigger_s trigger = {};
|
||||
_trigger_pub = orb_advertise(ORB_ID(camera_trigger), &trigger);
|
||||
}
|
||||
|
@ -91,7 +91,7 @@ CameraCapture::capture_callback(uint32_t chan_index,
|
|||
trigger.timestamp = edge_time - ((edge_time - _last_fall_time) / 2); // Get timestamp of mid-exposure
|
||||
trigger.seq = _capture_seq++;
|
||||
|
||||
if (_hotshoe_trigger_feedback != 0) {
|
||||
if (_camera_capture_feedback != 0) {
|
||||
orb_publish(ORB_ID(camera_trigger), _trigger_pub, &trigger);
|
||||
}
|
||||
|
||||
|
|
|
@ -112,8 +112,8 @@ private:
|
|||
// Parameters
|
||||
param_t _p_strobe_delay;
|
||||
float _strobe_delay;
|
||||
param_t _p_hotshoe_trigger_feedback;
|
||||
int32_t _hotshoe_trigger_feedback;
|
||||
param_t _p_camera_capture_feedback;
|
||||
int32_t _camera_capture_feedback;
|
||||
|
||||
// Signal capture statistics
|
||||
uint32_t _capture_seq;
|
||||
|
|
|
@ -49,3 +49,14 @@
|
|||
* @group Camera Capture
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(CAM_CAP_DELAY, 1.0f);
|
||||
|
||||
/**
|
||||
* Camera capture feedback
|
||||
*
|
||||
* Enables camera feedback from hotshoe on camera..
|
||||
*
|
||||
* @boolean
|
||||
* @group Camera Control
|
||||
* @reboot_required true
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAM_CAP_FBACK, 0);
|
||||
|
|
|
@ -171,7 +171,7 @@ private:
|
|||
bool _turning_on;
|
||||
matrix::Vector2f _last_shoot_position;
|
||||
bool _valid_position;
|
||||
int32_t _hotshoe_trigger_feedback;
|
||||
int32_t _camera_capture_feedback;
|
||||
|
||||
int _command_sub;
|
||||
int _lpos_sub;
|
||||
|
@ -184,7 +184,7 @@ private:
|
|||
param_t _p_interval;
|
||||
param_t _p_distance;
|
||||
param_t _p_interface;
|
||||
param_t _p_hotshoe_trigger_feedback;
|
||||
param_t _p_camera_capture_feedback;
|
||||
|
||||
trigger_mode_t _trigger_mode;
|
||||
|
||||
|
@ -248,7 +248,7 @@ CameraTrigger::CameraTrigger() :
|
|||
_turning_on(false),
|
||||
_last_shoot_position(0.0f, 0.0f),
|
||||
_valid_position(false),
|
||||
_hotshoe_trigger_feedback(0),
|
||||
_camera_capture_feedback(0),
|
||||
_command_sub(-1),
|
||||
_lpos_sub(-1),
|
||||
_trigger_pub(nullptr),
|
||||
|
@ -272,14 +272,14 @@ CameraTrigger::CameraTrigger() :
|
|||
_p_activation_time = param_find("TRIG_ACT_TIME");
|
||||
_p_mode = param_find("TRIG_MODE");
|
||||
_p_interface = param_find("TRIG_INTERFACE");
|
||||
_p_hotshoe_trigger_feedback = param_find("CAM_HSHOE_FBACK");
|
||||
_p_camera_capture_feedback = param_find("CAM_CAP_FBACK");
|
||||
|
||||
param_get(_p_activation_time, &_activation_time);
|
||||
param_get(_p_interval, &_interval);
|
||||
param_get(_p_distance, &_distance);
|
||||
param_get(_p_mode, (int32_t *)&_trigger_mode);
|
||||
param_get(_p_interface, (int32_t *)&_camera_interface_mode);
|
||||
param_get(_p_hotshoe_trigger_feedback, &_hotshoe_trigger_feedback);
|
||||
param_get(_p_camera_capture_feedback, &_camera_capture_feedback);
|
||||
|
||||
switch (_camera_interface_mode) {
|
||||
#ifdef __PX4_NUTTX
|
||||
|
@ -318,7 +318,7 @@ CameraTrigger::CameraTrigger() :
|
|||
param_set_no_notification(_p_activation_time, &(_activation_time));
|
||||
}
|
||||
|
||||
if (_hotshoe_trigger_feedback == 0) {
|
||||
if (_camera_capture_feedback == 0) {
|
||||
// Advertise critical publishers here, because we cannot advertise in interrupt context
|
||||
struct camera_trigger_s trigger = {};
|
||||
_trigger_pub = orb_advertise(ORB_ID(camera_trigger), &trigger);
|
||||
|
@ -750,7 +750,7 @@ CameraTrigger::engage(void *arg)
|
|||
// Trigger the camera
|
||||
trig->_camera_interface->trigger(true);
|
||||
|
||||
if (trig->_test_shot || (trig->_hotshoe_trigger_feedback != 0)) {
|
||||
if (trig->_test_shot || (trig->_camera_capture_feedback != 0)) {
|
||||
// do not send messages or increment frame count for test shots
|
||||
return;
|
||||
}
|
||||
|
|
|
@ -49,16 +49,4 @@
|
|||
* @max 1
|
||||
* @group Camera Control
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAM_FBACK_MODE, 0);
|
||||
|
||||
|
||||
/**
|
||||
* Camera feedback from hotshoe
|
||||
*
|
||||
* Enables trigger feedback from hotshoe on camera..
|
||||
*
|
||||
* @boolean
|
||||
* @group Camera Control
|
||||
* @reboot_required true
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAM_HSHOE_FBACK, 0);
|
||||
PARAM_DEFINE_INT32(CAM_FBACK_MODE, 0);
|
Loading…
Reference in New Issue