mirror of https://github.com/ArduPilot/ardupilot
AP_Camera: Support for camera feedback signal
Added _feedback_pin; Added _camera_triggered; Included FEEDBACK_PIN parameter and his default definition
This commit is contained in:
parent
b5cb48ba6d
commit
2f3510023d
|
@ -71,6 +71,13 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = {
|
|||
// @Units: Degrees
|
||||
// @Range: 0 180
|
||||
AP_GROUPINFO("MAX_ROLL", 7, AP_Camera, _max_roll, 0),
|
||||
|
||||
// @Param: FEEDBACK_PIN
|
||||
// @DisplayName: Camera feedback pin
|
||||
// @Description: pin number to use for save accurate camera feedback messages. If set to -1 then don't use a pin flag for this, otherwise this is a pin number which if held high after a picture trigger order, will save camera messages when camera really takes a picture. An universal camera hot shoe is needed
|
||||
// @Values: -1:Disabled, 0-8:APM FeedbackPin, 50-55:PixHawk FeedbackPin
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("FEEDBACK_PIN", 8, AP_Camera, _feedback_pin, AP_CAMERA_FEEDBACK_DEFAULT_FEEDBACK_PIN),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
@ -276,4 +283,4 @@ bool AP_Camera::update_location(const struct Location &loc, const AP_AHRS &ahrs)
|
|||
_last_photo_time = tnow;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
}
|
|
@ -25,6 +25,8 @@
|
|||
#define AP_CAMERA_SERVO_ON_PWM 1300 // default PWM value to move servo to when shutter is activated
|
||||
#define AP_CAMERA_SERVO_OFF_PWM 1100 // default PWM value to move servo to when shutter is deactivated
|
||||
|
||||
#define AP_CAMERA_FEEDBACK_DEFAULT_FEEDBACK_PIN -1 // default is to not use camera feedback pin
|
||||
|
||||
/// @class Camera
|
||||
/// @brief Object managing a Photo or video camera
|
||||
class AP_Camera {
|
||||
|
@ -40,6 +42,12 @@ public:
|
|||
_apm_relay = obj_relay;
|
||||
}
|
||||
|
||||
// pin number for accurate camera feedback messages
|
||||
AP_Int8 _feedback_pin;
|
||||
|
||||
// this is set to 1 when camera really has been triggered
|
||||
AP_Int8 _camera_triggered;
|
||||
|
||||
// single entry point to take pictures
|
||||
// set send_mavlink_msg to true to send DO_DIGICAM_CONTROL message to all components
|
||||
void trigger_pic(bool send_mavlink_msg);
|
||||
|
@ -85,4 +93,4 @@ private:
|
|||
|
||||
};
|
||||
|
||||
#endif /* AP_CAMERA_H */
|
||||
#endif /* AP_CAMERA_H */
|
Loading…
Reference in New Issue