Public Member Functions | Private Member Functions | Private Attributes | List of all members
flir_boson_usb::BosonCamera Class Reference

#include <BosonCamera.h>

Inheritance diagram for flir_boson_usb::BosonCamera:
Inheritance graph
[legend]

Public Member Functions

 BosonCamera ()
 
 ~BosonCamera ()
 
- 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 agcBasicLinear (const cv::Mat &input_16, cv::Mat *output_8, const int &height, const int &width)
 
void captureAndPublish (const ros::TimerEvent &evt)
 
bool closeCamera ()
 
virtual void onInit ()
 
bool openCamera ()
 

Private Attributes

void * buffer_start
 
struct v4l2_buffer bufferinfo
 
std::shared_ptr< camera_info_manager::CameraInfoManagercamera_info
 
std::string camera_info_url
 
struct v4l2_capability cap
 
ros::Timer capture_timer
 
cv_bridge::CvImage cv_img
 
std::string dev_path
 
int32_t fd
 
int32_t frame = 0
 
std::string frame_id
 
float frame_rate
 
int32_t height
 
int32_t i
 
image_transport::CameraPublisher image_pub
 
std::shared_ptr< image_transport::ImageTransportit
 
ros::NodeHandle nh
 
ros::NodeHandle pnh
 
sensor_msgs::ImagePtr pub_image
 
SensorTypes sensor_type
 
std::string sensor_type_str
 
cv::Mat thermal16
 
cv::Mat thermal16_linear
 
cv::Mat thermal16_linear_zoom
 
cv::Mat thermal_luma
 
cv::Mat thermal_rgb
 
cv::Mat thermal_rgb_zoom
 
int8_t thermal_sensor_name [20]
 
Encoding video_mode
 
std::string video_mode_str
 
int32_t width
 
bool zoom_enable
 

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 65 of file BosonCamera.h.

Constructor & Destructor Documentation

BosonCamera::BosonCamera ( )

Definition at line 29 of file BosonCamera.cpp.

BosonCamera::~BosonCamera ( )

Definition at line 34 of file BosonCamera.cpp.

Member Function Documentation

void BosonCamera::agcBasicLinear ( const cv::Mat &  input_16,
cv::Mat *  output_8,
const int &  height,
const int &  width 
)
private

Definition at line 125 of file BosonCamera.cpp.

void BosonCamera::captureAndPublish ( const ros::TimerEvent evt)
private

Definition at line 329 of file BosonCamera.cpp.

bool BosonCamera::closeCamera ( )
private

Definition at line 313 of file BosonCamera.cpp.

void BosonCamera::onInit ( )
privatevirtual

Implements nodelet::Nodelet.

Definition at line 39 of file BosonCamera.cpp.

bool BosonCamera::openCamera ( )
private

Definition at line 168 of file BosonCamera.cpp.

Member Data Documentation

void* flir_boson_usb::BosonCamera::buffer_start
private

Definition at line 95 of file BosonCamera.h.

struct v4l2_buffer flir_boson_usb::BosonCamera::bufferinfo
private

Definition at line 94 of file BosonCamera.h.

std::shared_ptr<camera_info_manager::CameraInfoManager> flir_boson_usb::BosonCamera::camera_info
private

Definition at line 82 of file BosonCamera.h.

std::string flir_boson_usb::BosonCamera::camera_info_url
private

Definition at line 101 of file BosonCamera.h.

struct v4l2_capability flir_boson_usb::BosonCamera::cap
private

Definition at line 91 of file BosonCamera.h.

ros::Timer flir_boson_usb::BosonCamera::capture_timer
private

Definition at line 87 of file BosonCamera.h.

cv_bridge::CvImage flir_boson_usb::BosonCamera::cv_img
private

Definition at line 85 of file BosonCamera.h.

std::string flir_boson_usb::BosonCamera::dev_path
private

Definition at line 101 of file BosonCamera.h.

int32_t flir_boson_usb::BosonCamera::fd
private

Definition at line 89 of file BosonCamera.h.

int32_t flir_boson_usb::BosonCamera::frame = 0
private

Definition at line 92 of file BosonCamera.h.

std::string flir_boson_usb::BosonCamera::frame_id
private

Definition at line 101 of file BosonCamera.h.

float flir_boson_usb::BosonCamera::frame_rate
private

Definition at line 103 of file BosonCamera.h.

int32_t flir_boson_usb::BosonCamera::height
private

Definition at line 88 of file BosonCamera.h.

int32_t flir_boson_usb::BosonCamera::i
private

Definition at line 90 of file BosonCamera.h.

image_transport::CameraPublisher flir_boson_usb::BosonCamera::image_pub
private

Definition at line 84 of file BosonCamera.h.

std::shared_ptr<image_transport::ImageTransport> flir_boson_usb::BosonCamera::it
private

Definition at line 83 of file BosonCamera.h.

ros::NodeHandle flir_boson_usb::BosonCamera::nh
private

Definition at line 81 of file BosonCamera.h.

ros::NodeHandle flir_boson_usb::BosonCamera::pnh
private

Definition at line 81 of file BosonCamera.h.

sensor_msgs::ImagePtr flir_boson_usb::BosonCamera::pub_image
private

Definition at line 86 of file BosonCamera.h.

SensorTypes flir_boson_usb::BosonCamera::sensor_type
private

Definition at line 106 of file BosonCamera.h.

std::string flir_boson_usb::BosonCamera::sensor_type_str
private

Definition at line 101 of file BosonCamera.h.

cv::Mat flir_boson_usb::BosonCamera::thermal16
private

Definition at line 97 of file BosonCamera.h.

cv::Mat flir_boson_usb::BosonCamera::thermal16_linear
private

Definition at line 97 of file BosonCamera.h.

cv::Mat flir_boson_usb::BosonCamera::thermal16_linear_zoom
private

Definition at line 97 of file BosonCamera.h.

cv::Mat flir_boson_usb::BosonCamera::thermal_luma
private

Definition at line 97 of file BosonCamera.h.

cv::Mat flir_boson_usb::BosonCamera::thermal_rgb
private

Definition at line 97 of file BosonCamera.h.

cv::Mat flir_boson_usb::BosonCamera::thermal_rgb_zoom
private

Definition at line 97 of file BosonCamera.h.

int8_t flir_boson_usb::BosonCamera::thermal_sensor_name[20]
private

Definition at line 93 of file BosonCamera.h.

Encoding flir_boson_usb::BosonCamera::video_mode
private

Definition at line 104 of file BosonCamera.h.

std::string flir_boson_usb::BosonCamera::video_mode_str
private

Definition at line 101 of file BosonCamera.h.

int32_t flir_boson_usb::BosonCamera::width
private

Definition at line 88 of file BosonCamera.h.

bool flir_boson_usb::BosonCamera::zoom_enable
private

Definition at line 105 of file BosonCamera.h.


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


flir_boson_usb
Author(s): Joe Driscoll , Joshua Whitley
autogenerated on Thu Mar 18 2021 02:32:10