Public Member Functions | Private Member Functions | Private Attributes | List of all members
rc::GenICamDeviceNodelet Class Reference

#include <genicam_device_nodelet.h>

Inheritance diagram for rc::GenICamDeviceNodelet:
Inheritance graph
[legend]

Public Member Functions

bool depthAcquisitionTrigger (rc_common_msgs::Trigger::Request &req, rc_common_msgs::Trigger::Response &resp)
 
 GenICamDeviceNodelet ()
 
virtual void onInit ()
 
virtual ~GenICamDeviceNodelet ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Private Member Functions

void grab (std::string id, rcg::Device::ACCESS access)
 
void initConfiguration ()
 
void publishConnectionDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void publishDeviceDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat)
 
void reconfigure (rc_genicam_driver::rc_genicam_driverConfig &c, uint32_t level)
 
void subChanged ()
 
void updateSubscriptions (bool force=false)
 

Private Attributes

int complete_buffers_total
 
rc_genicam_driver::rc_genicam_driverConfig config
 
int connection_loss_total
 
int current_reconnect_trial
 
std::shared_ptr< rcg::Devicedev
 
std::string device_interface
 
std::string device_ip
 
std::string device_mac
 
std::string device_model
 
std::recursive_mutex device_mtx
 
std::string device_name
 
std::string device_serial
 
std::string device_version
 
std::string frame_id
 
int gev_packet_size
 
std::thread grab_thread
 
int image_receive_timeouts_total
 
int incomplete_buffers_total
 
std::shared_ptr< GenApi::CNodeMapRef > nodemap
 
std::vector< std::shared_ptr< GenICam2RosPublisher > > pub
 
dynamic_reconfigure::Server< rc_genicam_driver::rc_genicam_driverConfig > * reconfig
 
boost::recursive_mutex reconfig_mtx
 
std::atomic_bool running
 
bool scolor
 
int scomponents
 
bool streaming
 
ros::ServiceServer trigger_service
 
diagnostic_updater::Updater updater
 

Additional Inherited Members

- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Detailed Description

Definition at line 55 of file genicam_device_nodelet.h.

Constructor & Destructor Documentation

rc::GenICamDeviceNodelet::GenICamDeviceNodelet ( )

Definition at line 64 of file genicam_device_nodelet.cpp.

rc::GenICamDeviceNodelet::~GenICamDeviceNodelet ( )
virtual

Definition at line 80 of file genicam_device_nodelet.cpp.

Member Function Documentation

bool rc::GenICamDeviceNodelet::depthAcquisitionTrigger ( rc_common_msgs::Trigger::Request &  req,
rc_common_msgs::Trigger::Response &  resp 
)

Definition at line 159 of file genicam_device_nodelet.cpp.

void rc::GenICamDeviceNodelet::grab ( std::string  id,
rcg::Device::ACCESS  access 
)
private

Definition at line 892 of file genicam_device_nodelet.cpp.

void rc::GenICamDeviceNodelet::initConfiguration ( )
private

Definition at line 201 of file genicam_device_nodelet.cpp.

void rc::GenICamDeviceNodelet::onInit ( )
virtual

Implements nodelet::Nodelet.

Definition at line 95 of file genicam_device_nodelet.cpp.

void rc::GenICamDeviceNodelet::publishConnectionDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper stat)
private

Definition at line 765 of file genicam_device_nodelet.cpp.

void rc::GenICamDeviceNodelet::publishDeviceDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper stat)
private

Definition at line 807 of file genicam_device_nodelet.cpp.

void rc::GenICamDeviceNodelet::reconfigure ( rc_genicam_driver::rc_genicam_driverConfig &  c,
uint32_t  level 
)
private

Definition at line 353 of file genicam_device_nodelet.cpp.

void rc::GenICamDeviceNodelet::subChanged ( )
private

Definition at line 760 of file genicam_device_nodelet.cpp.

void rc::GenICamDeviceNodelet::updateSubscriptions ( bool  force = false)
private

Definition at line 686 of file genicam_device_nodelet.cpp.

Member Data Documentation

int rc::GenICamDeviceNodelet::complete_buffers_total
private

Definition at line 107 of file genicam_device_nodelet.h.

rc_genicam_driver::rc_genicam_driverConfig rc::GenICamDeviceNodelet::config
private

Definition at line 84 of file genicam_device_nodelet.h.

int rc::GenICamDeviceNodelet::connection_loss_total
private

Definition at line 106 of file genicam_device_nodelet.h.

int rc::GenICamDeviceNodelet::current_reconnect_trial
private

Definition at line 110 of file genicam_device_nodelet.h.

std::shared_ptr<rcg::Device> rc::GenICamDeviceNodelet::dev
private

Definition at line 87 of file genicam_device_nodelet.h.

std::string rc::GenICamDeviceNodelet::device_interface
private

Definition at line 103 of file genicam_device_nodelet.h.

std::string rc::GenICamDeviceNodelet::device_ip
private

Definition at line 104 of file genicam_device_nodelet.h.

std::string rc::GenICamDeviceNodelet::device_mac
private

Definition at line 101 of file genicam_device_nodelet.h.

std::string rc::GenICamDeviceNodelet::device_model
private

Definition at line 98 of file genicam_device_nodelet.h.

std::recursive_mutex rc::GenICamDeviceNodelet::device_mtx
private

Definition at line 86 of file genicam_device_nodelet.h.

std::string rc::GenICamDeviceNodelet::device_name
private

Definition at line 102 of file genicam_device_nodelet.h.

std::string rc::GenICamDeviceNodelet::device_serial
private

Definition at line 100 of file genicam_device_nodelet.h.

std::string rc::GenICamDeviceNodelet::device_version
private

Definition at line 99 of file genicam_device_nodelet.h.

std::string rc::GenICamDeviceNodelet::frame_id
private

Definition at line 79 of file genicam_device_nodelet.h.

int rc::GenICamDeviceNodelet::gev_packet_size
private

Definition at line 105 of file genicam_device_nodelet.h.

std::thread rc::GenICamDeviceNodelet::grab_thread
private

Definition at line 93 of file genicam_device_nodelet.h.

int rc::GenICamDeviceNodelet::image_receive_timeouts_total
private

Definition at line 109 of file genicam_device_nodelet.h.

int rc::GenICamDeviceNodelet::incomplete_buffers_total
private

Definition at line 108 of file genicam_device_nodelet.h.

std::shared_ptr<GenApi::CNodeMapRef> rc::GenICamDeviceNodelet::nodemap
private

Definition at line 88 of file genicam_device_nodelet.h.

std::vector<std::shared_ptr<GenICam2RosPublisher> > rc::GenICamDeviceNodelet::pub
private

Definition at line 96 of file genicam_device_nodelet.h.

dynamic_reconfigure::Server<rc_genicam_driver::rc_genicam_driverConfig>* rc::GenICamDeviceNodelet::reconfig
private

Definition at line 83 of file genicam_device_nodelet.h.

boost::recursive_mutex rc::GenICamDeviceNodelet::reconfig_mtx
private

Definition at line 82 of file genicam_device_nodelet.h.

std::atomic_bool rc::GenICamDeviceNodelet::running
private

Definition at line 94 of file genicam_device_nodelet.h.

bool rc::GenICamDeviceNodelet::scolor
private

Definition at line 91 of file genicam_device_nodelet.h.

int rc::GenICamDeviceNodelet::scomponents
private

Definition at line 90 of file genicam_device_nodelet.h.

bool rc::GenICamDeviceNodelet::streaming
private

Definition at line 111 of file genicam_device_nodelet.h.

ros::ServiceServer rc::GenICamDeviceNodelet::trigger_service
private

Definition at line 80 of file genicam_device_nodelet.h.

diagnostic_updater::Updater rc::GenICamDeviceNodelet::updater
private

Definition at line 113 of file genicam_device_nodelet.h.


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


rc_genicam_driver
Author(s): Heiko Hirschmueller , Felix Ruess
autogenerated on Sat Feb 13 2021 03:55:07