PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <camera_capture.hpp>
Classes | |
struct | _trig_s |
Public Member Functions | |
CameraCapture () | |
Constructor. More... | |
~CameraCapture () | |
Destructor, also kills task. More... | |
int | start () |
Start the task. More... | |
void | stop () |
Stop the task. More... | |
void | status () |
void | Run () override |
void | set_capture_control (bool enabled) |
void | reset_statistics (bool reset_seq) |
void | publish_trigger () |
Static Public Member Functions | |
static void | capture_trampoline (void *context, uint32_t chan_index, hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow) |
Static Public Attributes | |
static struct work_s | _work_publisher |
Private Member Functions | |
void | capture_callback (uint32_t chan_index, hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow) |
Static Private Member Functions | |
static int | gpio_interrupt_routine (int irq, void *context, void *arg) |
static void | publish_trigger_trampoline (void *arg) |
Private Attributes | |
uORB::PublicationQueued< vehicle_command_ack_s > | _command_ack_pub {ORB_ID(vehicle_command_ack)} |
uORB::Publication< camera_trigger_s > | _trigger_pub {ORB_ID(camera_trigger)} |
uORB::Subscription | _command_sub {ORB_ID(vehicle_command)} |
struct CameraCapture::_trig_s | _trigger |
ringbuffer::RingBuffer * | _trig_buffer {nullptr} |
bool | _capture_enabled {false} |
bool | _gpio_capture {false} |
param_t | _p_strobe_delay {PARAM_INVALID} |
float | _strobe_delay {0.0f} |
param_t | _p_camera_capture_mode {PARAM_INVALID} |
int32_t | _camera_capture_mode {0} |
param_t | _p_camera_capture_edge {PARAM_INVALID} |
int32_t | _camera_capture_edge {0} |
uint32_t | _capture_seq {0} |
hrt_abstime | _last_trig_begin_time {0} |
hrt_abstime | _last_exposure_time {0} |
hrt_abstime | _last_trig_time {0} |
uint32_t | _capture_overflows {0} |
Definition at line 65 of file camera_capture.hpp.
CameraCapture::CameraCapture | ( | ) |
Constructor.
Definition at line 51 of file camera_capture.cpp.
References _camera_capture_edge, _camera_capture_mode, _p_camera_capture_edge, _p_camera_capture_mode, _p_strobe_delay, _strobe_delay, _work_publisher, param_find(), and param_get().
Referenced by camera_capture_main().
CameraCapture::~CameraCapture | ( | ) |
Destructor, also kills task.
Definition at line 67 of file camera_capture.cpp.
References _trig_buffer, and camera_capture::g_camera_capture.
|
private |
Definition at line 78 of file camera_capture.cpp.
References _trigger, _work_publisher, CameraCapture::_trig_s::chan_index, CameraCapture::_trig_s::edge_state, CameraCapture::_trig_s::edge_time, CameraCapture::_trig_s::overflow, and publish_trigger_trampoline().
Referenced by capture_trampoline().
|
static |
Definition at line 163 of file camera_capture.cpp.
References capture_callback(), and camera_capture::g_camera_capture.
Referenced by set_capture_control().
|
staticprivate |
Definition at line 89 of file camera_capture.cpp.
References _trigger, _work_publisher, CameraCapture::_trig_s::chan_index, CameraCapture::_trig_s::edge_state, CameraCapture::_trig_s::edge_time, hrt_absolute_time(), CameraCapture::_trig_s::overflow, and publish_trigger_trampoline().
Referenced by set_capture_control().
void CameraCapture::publish_trigger | ( | ) |
Definition at line 112 of file camera_capture.cpp.
References _camera_capture_mode, _capture_overflows, _capture_seq, _gpio_capture, _last_exposure_time, _last_trig_begin_time, _last_trig_time, _strobe_delay, _trigger, _trigger_pub, CameraCapture::_trig_s::edge_state, CameraCapture::_trig_s::edge_time, CameraCapture::_trig_s::overflow, uORB::Publication< T >::publish(), and camera_trigger_s::timestamp.
Referenced by publish_trigger_trampoline().
|
staticprivate |
Definition at line 104 of file camera_capture.cpp.
References publish_trigger().
Referenced by capture_callback(), and gpio_interrupt_routine().
void CameraCapture::reset_statistics | ( | bool | reset_seq | ) |
Definition at line 286 of file camera_capture.cpp.
References _capture_overflows, _capture_seq, _last_exposure_time, _last_trig_begin_time, and _last_trig_time.
Referenced by camera_capture_main(), Run(), and set_capture_control().
|
override |
Definition at line 170 of file camera_capture.cpp.
References _command_ack_pub, _command_sub, commandParamToInt, hrt_absolute_time(), uORB::PublicationQueued< T >::publish(), reset_statistics(), set_capture_control(), vehicle_command_ack_s::timestamp, and uORB::Subscription::update().
void CameraCapture::set_capture_control | ( | bool | enabled | ) |
Definition at line 210 of file camera_capture.cpp.
References _camera_capture_edge, _camera_capture_mode, _capture_enabled, _gpio_capture, Both, input_capture_config_t::callback, capture_trampoline(), input_capture_config_t::channel, input_capture_config_t::context, input_capture_config_t::edge, Falling, fd, input_capture_config_t::filter, gpio_interrupt_routine(), GPIO_TRIG_AVX, INPUT_CAP_GET_COUNT, INPUT_CAP_SET_CALLBACK, PWM_SERVO_MODE_4PWM2CAP, PWM_SERVO_SET_MODE, PX4FMU_DEVICE_PATH, reset_statistics(), and Rising.
Referenced by camera_capture_main(), and Run().
int CameraCapture::start | ( | ) |
Start the task.
Definition at line 299 of file camera_capture.cpp.
References _trig_buffer.
Referenced by camera_capture_main().
void CameraCapture::status | ( | ) |
Definition at line 327 of file camera_capture.cpp.
References _camera_capture_mode, _capture_enabled, _capture_overflows, _capture_seq, _last_exposure_time, and _last_trig_time.
Referenced by camera_capture_main().
void CameraCapture::stop | ( | ) |
Stop the task.
Definition at line 315 of file camera_capture.cpp.
References _work_publisher, and camera_capture::g_camera_capture.
Referenced by camera_capture_main().
|
private |
Definition at line 133 of file camera_capture.hpp.
Referenced by CameraCapture(), and set_capture_control().
|
private |
Definition at line 131 of file camera_capture.hpp.
Referenced by CameraCapture(), publish_trigger(), set_capture_control(), and status().
|
private |
Definition at line 124 of file camera_capture.hpp.
Referenced by set_capture_control(), and status().
|
private |
Definition at line 140 of file camera_capture.hpp.
Referenced by publish_trigger(), reset_statistics(), and status().
|
private |
Definition at line 136 of file camera_capture.hpp.
Referenced by publish_trigger(), reset_statistics(), and status().
|
private |
Definition at line 108 of file camera_capture.hpp.
Referenced by Run().
|
private |
Definition at line 112 of file camera_capture.hpp.
Referenced by Run().
|
private |
Definition at line 125 of file camera_capture.hpp.
Referenced by publish_trigger(), and set_capture_control().
|
private |
Definition at line 138 of file camera_capture.hpp.
Referenced by publish_trigger(), reset_statistics(), and status().
|
private |
Definition at line 137 of file camera_capture.hpp.
Referenced by publish_trigger(), and reset_statistics().
|
private |
Definition at line 139 of file camera_capture.hpp.
Referenced by publish_trigger(), reset_statistics(), and status().
|
private |
Definition at line 132 of file camera_capture.hpp.
Referenced by CameraCapture().
|
private |
Definition at line 130 of file camera_capture.hpp.
Referenced by CameraCapture().
|
private |
Definition at line 128 of file camera_capture.hpp.
Referenced by CameraCapture().
|
private |
Definition at line 129 of file camera_capture.hpp.
Referenced by CameraCapture(), and publish_trigger().
|
private |
Definition at line 122 of file camera_capture.hpp.
Referenced by start(), and ~CameraCapture().
|
private |
Referenced by capture_callback(), gpio_interrupt_routine(), and publish_trigger().
|
private |
Definition at line 109 of file camera_capture.hpp.
Referenced by publish_trigger().
|
static |
Definition at line 103 of file camera_capture.hpp.
Referenced by CameraCapture(), capture_callback(), gpio_interrupt_routine(), and stop().