PX4 Firmware
PX4 Autopilot Software http://px4.io
CameraTrigger Class Reference
Inheritance diagram for CameraTrigger:
Collaboration diagram for CameraTrigger:

Public Member Functions

 CameraTrigger ()
 Constructor. More...
 
 ~CameraTrigger () override
 Destructor, also kills task. More...
 
void update_intervalometer ()
 Run intervalometer update. More...
 
void update_distance ()
 Run distance-based trigger update. More...
 
void shoot_once ()
 Trigger the camera just once. More...
 
void enable_keep_alive (bool on)
 Toggle keep camera alive functionality. More...
 
void toggle_power ()
 Toggle camera power (on/off) More...
 
bool start ()
 Start the task. More...
 
void stop ()
 Stop the task. More...
 
void status ()
 Display status. More...
 
void test ()
 Trigger one image. More...
 

Private Member Functions

void Run () override
 Vehicle command handler. More...
 

Static Private Member Functions

static void engage (void *arg)
 Fires trigger. More...
 
static void disengage (void *arg)
 Resets trigger. More...
 
static void engange_turn_on_off (void *arg)
 Fires on/off. More...
 
static void disengage_turn_on_off (void *arg)
 Resets on/off. More...
 
static void keep_alive_up (void *arg)
 Enables keep alive signal. More...
 
static void keep_alive_down (void *arg)
 Disables keep alive signal. More...
 

Private Attributes

struct hrt_call _engagecall
 
struct hrt_call _disengagecall
 
struct hrt_call _engage_turn_on_off_call
 
struct hrt_call _disengage_turn_on_off_call
 
struct hrt_call _keepalivecall_up
 
struct hrt_call _keepalivecall_down
 
float _activation_time
 
float _interval
 
float _distance
 
uint32_t _trigger_seq
 
bool _trigger_enabled
 
bool _trigger_paused
 
bool _one_shot
 
bool _test_shot
 
bool _turning_on
 
matrix::Vector2f _last_shoot_position
 
bool _valid_position
 
uORB::Subscription _command_sub {ORB_ID(vehicle_command)}
 
uORB::Subscription _lpos_sub {ORB_ID(vehicle_local_position)}
 
orb_advert_t _trigger_pub
 
uORB::PublicationQueued< vehicle_command_ack_s_cmd_ack_pub {ORB_ID(vehicle_command_ack)}
 
param_t _p_mode
 
param_t _p_activation_time
 
param_t _p_interval
 
param_t _p_distance
 
param_t _p_interface
 
param_t _p_cam_cap_fback
 
trigger_mode_t _trigger_mode
 
int32_t _cam_cap_fback
 
camera_interface_mode_t _camera_interface_mode
 
CameraInterface_camera_interface
 instance of camera interface More...
 

Detailed Description

Definition at line 95 of file camera_trigger.cpp.

Constructor & Destructor Documentation

◆ CameraTrigger()

CameraTrigger::CameraTrigger ( )

◆ ~CameraTrigger()

CameraTrigger::~CameraTrigger ( )
override

Destructor, also kills task.

Definition at line 330 of file camera_trigger.cpp.

References _camera_interface, and camera_trigger::g_camera_trigger.

Member Function Documentation

◆ disengage()

void CameraTrigger::disengage ( void *  arg)
staticprivate

Resets trigger.

Definition at line 756 of file camera_trigger.cpp.

References _camera_interface, and CameraInterface::trigger().

Referenced by Run(), shoot_once(), and update_intervalometer().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ disengage_turn_on_off()

void CameraTrigger::disengage_turn_on_off ( void *  arg)
staticprivate

Resets on/off.

Definition at line 772 of file camera_trigger.cpp.

References _camera_interface, and CameraInterface::send_toggle_power().

Referenced by toggle_power().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ enable_keep_alive()

void CameraTrigger::enable_keep_alive ( bool  on)

Toggle keep camera alive functionality.

Definition at line 391 of file camera_trigger.cpp.

References _keepalivecall_down, _keepalivecall_up, hrt_call_every(), hrt_cancel(), keep_alive_down(), and keep_alive_up().

Referenced by Run(), and start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ engage()

void CameraTrigger::engage ( void *  arg)
staticprivate

Fires trigger.

Definition at line 717 of file camera_trigger.cpp.

References _cam_cap_fback, _camera_interface, _test_shot, _trigger_pub, _trigger_seq, camera_trigger_s::feedback, hrt_absolute_time(), ORB_ID, orb_publish(), camera_trigger_s::seq, camera_trigger_s::timestamp, camera_trigger_s::timestamp_utc, and CameraInterface::trigger().

Referenced by shoot_once(), and update_intervalometer().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ engange_turn_on_off()

void CameraTrigger::engange_turn_on_off ( void *  arg)
staticprivate

Fires on/off.

Definition at line 764 of file camera_trigger.cpp.

References _camera_interface, and CameraInterface::send_toggle_power().

Referenced by toggle_power().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ keep_alive_down()

void CameraTrigger::keep_alive_down ( void *  arg)
staticprivate

Disables keep alive signal.

Definition at line 788 of file camera_trigger.cpp.

References _camera_interface, and CameraInterface::send_keep_alive().

Referenced by enable_keep_alive().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ keep_alive_up()

void CameraTrigger::keep_alive_up ( void *  arg)
staticprivate

Enables keep alive signal.

Definition at line 780 of file camera_trigger.cpp.

References _camera_interface, and CameraInterface::send_keep_alive().

Referenced by enable_keep_alive().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ Run()

◆ shoot_once()

void CameraTrigger::shoot_once ( )

Trigger the camera just once.

Definition at line 420 of file camera_trigger.cpp.

References _activation_time, _disengagecall, _engagecall, _trigger_paused, disengage(), engage(), and hrt_call_after().

Referenced by Run(), and update_distance().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ start()

bool CameraTrigger::start ( )

Start the task.

Definition at line 433 of file camera_trigger.cpp.

References _camera_interface, _trigger_enabled, _trigger_mode, enable_keep_alive(), camera_trigger::g_camera_trigger, CameraInterface::has_power_control(), CameraInterface::is_powered_on(), toggle_power(), TRIGGER_MODE_DISTANCE_ALWAYS_ON, TRIGGER_MODE_INTERVAL_ALWAYS_ON, and update_intervalometer().

Referenced by camera_trigger_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ status()

void CameraTrigger::status ( )

Display status.

Definition at line 796 of file camera_trigger.cpp.

References _activation_time, _camera_interface, _distance, _interval, _trigger_enabled, _trigger_mode, _trigger_paused, CameraInterface::has_power_control(), CameraInterface::info(), CameraInterface::is_powered_on(), TRIGGER_MODE_DISTANCE_ALWAYS_ON, TRIGGER_MODE_DISTANCE_ON_CMD, TRIGGER_MODE_INTERVAL_ALWAYS_ON, and TRIGGER_MODE_INTERVAL_ON_CMD.

Referenced by camera_trigger_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ stop()

void CameraTrigger::stop ( )

Stop the task.

Definition at line 476 of file camera_trigger.cpp.

References _disengage_turn_on_off_call, _disengagecall, _engage_turn_on_off_call, _engagecall, _keepalivecall_down, _keepalivecall_up, camera_trigger::g_camera_trigger, and hrt_cancel().

Referenced by camera_trigger_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ test()

void CameraTrigger::test ( )

Trigger one image.

Definition at line 494 of file camera_trigger.cpp.

References hrt_absolute_time(), ORB_ID, and vehicle_command_s::timestamp.

Referenced by camera_trigger_main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ toggle_power()

void CameraTrigger::toggle_power ( )

Toggle camera power (on/off)

Definition at line 409 of file camera_trigger.cpp.

References _disengage_turn_on_off_call, _engage_turn_on_off_call, disengage_turn_on_off(), engange_turn_on_off(), and hrt_call_after().

Referenced by camera_trigger_main(), Run(), and start().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_distance()

void CameraTrigger::update_distance ( )

Run distance-based trigger update.

Definition at line 358 of file camera_trigger.cpp.

References _distance, _last_shoot_position, _lpos_sub, _trigger_enabled, _turning_on, _valid_position, uORB::Subscription::copy(), and shoot_once().

Referenced by Run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_intervalometer()

void CameraTrigger::update_intervalometer ( )

Run intervalometer update.

Definition at line 340 of file camera_trigger.cpp.

References _activation_time, _disengagecall, _engagecall, _interval, _trigger_enabled, _trigger_paused, disengage(), engage(), and hrt_call_every().

Referenced by Run(), and start().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ _activation_time

float CameraTrigger::_activation_time
private

Definition at line 162 of file camera_trigger.cpp.

Referenced by CameraTrigger(), Run(), shoot_once(), status(), and update_intervalometer().

◆ _cam_cap_fback

int32_t CameraTrigger::_cam_cap_fback
private

Definition at line 189 of file camera_trigger.cpp.

Referenced by CameraTrigger(), and engage().

◆ _camera_interface

CameraInterface* CameraTrigger::_camera_interface
private

◆ _camera_interface_mode

camera_interface_mode_t CameraTrigger::_camera_interface_mode
private

Definition at line 191 of file camera_trigger.cpp.

Referenced by CameraTrigger(), and Run().

◆ _cmd_ack_pub

uORB::PublicationQueued<vehicle_command_ack_s> CameraTrigger::_cmd_ack_pub {ORB_ID(vehicle_command_ack)}
private

Definition at line 179 of file camera_trigger.cpp.

Referenced by Run().

◆ _command_sub

uORB::Subscription CameraTrigger::_command_sub {ORB_ID(vehicle_command)}
private

Definition at line 174 of file camera_trigger.cpp.

Referenced by Run().

◆ _disengage_turn_on_off_call

struct hrt_call CameraTrigger::_disengage_turn_on_off_call
private

Definition at line 158 of file camera_trigger.cpp.

Referenced by CameraTrigger(), stop(), and toggle_power().

◆ _disengagecall

struct hrt_call CameraTrigger::_disengagecall
private

Definition at line 156 of file camera_trigger.cpp.

Referenced by CameraTrigger(), Run(), shoot_once(), stop(), and update_intervalometer().

◆ _distance

float CameraTrigger::_distance
private

Definition at line 164 of file camera_trigger.cpp.

Referenced by CameraTrigger(), Run(), status(), and update_distance().

◆ _engage_turn_on_off_call

struct hrt_call CameraTrigger::_engage_turn_on_off_call
private

Definition at line 157 of file camera_trigger.cpp.

Referenced by CameraTrigger(), stop(), and toggle_power().

◆ _engagecall

struct hrt_call CameraTrigger::_engagecall
private

Definition at line 155 of file camera_trigger.cpp.

Referenced by Run(), shoot_once(), stop(), and update_intervalometer().

◆ _interval

float CameraTrigger::_interval
private

Definition at line 163 of file camera_trigger.cpp.

Referenced by CameraTrigger(), Run(), status(), and update_intervalometer().

◆ _keepalivecall_down

struct hrt_call CameraTrigger::_keepalivecall_down
private

Definition at line 160 of file camera_trigger.cpp.

Referenced by CameraTrigger(), enable_keep_alive(), and stop().

◆ _keepalivecall_up

struct hrt_call CameraTrigger::_keepalivecall_up
private

Definition at line 159 of file camera_trigger.cpp.

Referenced by CameraTrigger(), enable_keep_alive(), and stop().

◆ _last_shoot_position

matrix::Vector2f CameraTrigger::_last_shoot_position
private

Definition at line 171 of file camera_trigger.cpp.

Referenced by CameraTrigger(), and update_distance().

◆ _lpos_sub

uORB::Subscription CameraTrigger::_lpos_sub {ORB_ID(vehicle_local_position)}
private

Definition at line 175 of file camera_trigger.cpp.

Referenced by update_distance().

◆ _one_shot

bool CameraTrigger::_one_shot
private

Definition at line 168 of file camera_trigger.cpp.

Referenced by CameraTrigger(), and Run().

◆ _p_activation_time

param_t CameraTrigger::_p_activation_time
private

Definition at line 182 of file camera_trigger.cpp.

Referenced by CameraTrigger(), and Run().

◆ _p_cam_cap_fback

param_t CameraTrigger::_p_cam_cap_fback
private

Definition at line 186 of file camera_trigger.cpp.

Referenced by CameraTrigger().

◆ _p_distance

param_t CameraTrigger::_p_distance
private

Definition at line 184 of file camera_trigger.cpp.

Referenced by CameraTrigger(), and Run().

◆ _p_interface

param_t CameraTrigger::_p_interface
private

Definition at line 185 of file camera_trigger.cpp.

Referenced by CameraTrigger().

◆ _p_interval

param_t CameraTrigger::_p_interval
private

Definition at line 183 of file camera_trigger.cpp.

Referenced by CameraTrigger(), and Run().

◆ _p_mode

param_t CameraTrigger::_p_mode
private

Definition at line 181 of file camera_trigger.cpp.

Referenced by CameraTrigger().

◆ _test_shot

bool CameraTrigger::_test_shot
private

Definition at line 169 of file camera_trigger.cpp.

Referenced by CameraTrigger(), engage(), and Run().

◆ _trigger_enabled

bool CameraTrigger::_trigger_enabled
private

◆ _trigger_mode

trigger_mode_t CameraTrigger::_trigger_mode
private

Definition at line 188 of file camera_trigger.cpp.

Referenced by CameraTrigger(), Run(), start(), and status().

◆ _trigger_paused

bool CameraTrigger::_trigger_paused
private

Definition at line 167 of file camera_trigger.cpp.

Referenced by CameraTrigger(), Run(), shoot_once(), status(), and update_intervalometer().

◆ _trigger_pub

orb_advert_t CameraTrigger::_trigger_pub
private

Definition at line 177 of file camera_trigger.cpp.

Referenced by CameraTrigger(), and engage().

◆ _trigger_seq

uint32_t CameraTrigger::_trigger_seq
private

Definition at line 165 of file camera_trigger.cpp.

Referenced by CameraTrigger(), engage(), and Run().

◆ _turning_on

bool CameraTrigger::_turning_on
private

Definition at line 170 of file camera_trigger.cpp.

Referenced by CameraTrigger(), Run(), and update_distance().

◆ _valid_position

bool CameraTrigger::_valid_position
private

Definition at line 172 of file camera_trigger.cpp.

Referenced by CameraTrigger(), Run(), and update_distance().


The documentation for this class was generated from the following file: