#include <CameraNode.h>
Public Member Functions | |
CameraNode (ros::NodeHandle node, ros::NodeHandle private_nh) | |
~CameraNode () | |
Private Member Functions | |
void | closeCamera () |
void | handlePath (std::string &path) |
void | loadIntrinsics () |
sensor_msgs::ImagePtr | processFrame (const char *frame, size_t size, sensor_msgs::CameraInfoPtr &info) |
void | publishImage (const char *frame, size_t size) |
void | reconfig (monoConfig &config, uint32_t level) |
bool | setCameraInfo (sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp) |
void | startCamera () |
void | stopCamera () |
void | timerCallback (const ros::TimerEvent &event) |
Private Attributes | |
bool | auto_exposure_ |
bool | auto_gain_ |
ueye::Camera | cam_ |
std::string | config_path_ |
bool | configured_ |
bool | force_streaming_ |
image_transport::ImageTransport | it_ |
sensor_msgs::CameraInfo | msg_camera_info_ |
image_transport::CameraPublisher | pub_stream_ |
bool | running_ |
dynamic_reconfigure::Server < monoConfig > | srv_ |
ros::ServiceServer | srv_cam_info_ |
ros::Timer | timer_ |
int | trigger_mode_ |
int | zoom_ |
Definition at line 67 of file CameraNode.h.
ueye::CameraNode::CameraNode | ( | ros::NodeHandle | node, |
ros::NodeHandle | private_nh | ||
) |
Definition at line 40 of file CameraNode.cpp.
Definition at line 111 of file CameraNode.cpp.
void ueye::CameraNode::closeCamera | ( | ) | [private] |
Definition at line 396 of file CameraNode.cpp.
void ueye::CameraNode::handlePath | ( | std::string & | path | ) | [private] |
Definition at line 116 of file CameraNode.cpp.
void ueye::CameraNode::loadIntrinsics | ( | ) | [private] |
Definition at line 323 of file CameraNode.cpp.
sensor_msgs::ImagePtr ueye::CameraNode::processFrame | ( | const char * | frame, |
size_t | size, | ||
sensor_msgs::CameraInfoPtr & | info | ||
) | [private] |
Definition at line 346 of file CameraNode.cpp.
void ueye::CameraNode::publishImage | ( | const char * | frame, |
size_t | size | ||
) | [private] |
Definition at line 371 of file CameraNode.cpp.
void ueye::CameraNode::reconfig | ( | monoConfig & | config, |
uint32_t | level | ||
) | [private] |
Definition at line 132 of file CameraNode.cpp.
bool ueye::CameraNode::setCameraInfo | ( | sensor_msgs::SetCameraInfo::Request & | req, |
sensor_msgs::SetCameraInfo::Response & | rsp | ||
) | [private] |
Definition at line 275 of file CameraNode.cpp.
void ueye::CameraNode::startCamera | ( | ) | [private] |
Definition at line 378 of file CameraNode.cpp.
void ueye::CameraNode::stopCamera | ( | ) | [private] |
Definition at line 387 of file CameraNode.cpp.
void ueye::CameraNode::timerCallback | ( | const ros::TimerEvent & | event | ) | [private] |
Definition at line 264 of file CameraNode.cpp.
bool ueye::CameraNode::auto_exposure_ [private] |
Definition at line 97 of file CameraNode.h.
bool ueye::CameraNode::auto_gain_ [private] |
Definition at line 98 of file CameraNode.h.
ueye::Camera ueye::CameraNode::cam_ [private] |
Definition at line 91 of file CameraNode.h.
std::string ueye::CameraNode::config_path_ [private] |
Definition at line 95 of file CameraNode.h.
bool ueye::CameraNode::configured_ [private] |
Definition at line 93 of file CameraNode.h.
bool ueye::CameraNode::force_streaming_ [private] |
Definition at line 94 of file CameraNode.h.
Definition at line 102 of file CameraNode.h.
sensor_msgs::CameraInfo ueye::CameraNode::msg_camera_info_ [private] |
Definition at line 89 of file CameraNode.h.
Definition at line 103 of file CameraNode.h.
bool ueye::CameraNode::running_ [private] |
Definition at line 92 of file CameraNode.h.
dynamic_reconfigure::Server<monoConfig> ueye::CameraNode::srv_ [private] |
Definition at line 87 of file CameraNode.h.
Definition at line 104 of file CameraNode.h.
ros::Timer ueye::CameraNode::timer_ [private] |
Definition at line 88 of file CameraNode.h.
int ueye::CameraNode::trigger_mode_ [private] |
Definition at line 96 of file CameraNode.h.
int ueye::CameraNode::zoom_ [private] |
Definition at line 99 of file CameraNode.h.