#include <ueye_cam_nodelet.hpp>
Public Member Functions | |
void | configCallback (ueye_cam::UEyeCamConfig &config, uint32_t level) |
virtual void | onInit () |
UEyeCamNodelet () | |
virtual | ~UEyeCamNodelet () |
Static Public Attributes | |
static const std::string | DEFAULT_CAMERA_NAME = "camera" |
static const std::string | DEFAULT_CAMERA_TOPIC = "image_raw" |
static const std::string | DEFAULT_COLOR_MODE = "" |
static constexpr double | DEFAULT_EXPOSURE = 33.0 |
static constexpr int | DEFAULT_FLASH_DURATION = 1000 |
static const std::string | DEFAULT_FRAME_NAME = "camera" |
static constexpr double | DEFAULT_FRAME_RATE = 10.0 |
static constexpr int | DEFAULT_IMAGE_HEIGHT = 480 |
static constexpr int | DEFAULT_IMAGE_WIDTH = 640 |
static constexpr int | DEFAULT_PIXEL_CLOCK = 25 |
static const std::string | DEFAULT_TIMEOUT_TOPIC = "timeout_count" |
static constexpr unsigned int | RECONFIGURE_CLOSE = 3 |
static constexpr unsigned int | RECONFIGURE_RUNNING = 0 |
static constexpr unsigned int | RECONFIGURE_STOP = 1 |
Protected Member Functions | |
virtual INT | connectCam () |
virtual INT | disconnectCam () |
bool | fillMsgData (sensor_msgs::Image &img) const |
void | frameGrabLoop () |
ros::Time | getImageTickTimestamp () |
ros::Time | getImageTimestamp () |
virtual void | handleTimeout () |
void | loadIntrinsicsFile () |
INT | parseROSParams (ros::NodeHandle &local_nh) |
INT | queryCamParams () |
bool | saveIntrinsicsFile () |
bool | setCamInfo (sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp) |
void | startFrameGrabber () |
void | stopFrameGrabber () |
virtual INT | syncCamConfig (std::string dft_mode_str="mono8") |
Protected Attributes | |
std::string | cam_intr_filename_ |
ueye_cam::UEyeCamConfig | cam_params_ |
std::string | cam_params_filename_ |
std::string | cam_topic_ |
bool | cfg_sync_requested_ |
bool | frame_grab_alive_ |
std::thread | frame_grab_thread_ |
std::string | frame_name_ |
uint64_t | init_clock_tick_ |
ros::Time | init_publish_time_ |
ros::Time | init_ros_time_ |
boost::mutex | output_rate_mutex_ |
uint64_t | prev_output_frame_idx_ |
sensor_msgs::CameraInfo | ros_cam_info_ |
image_transport::CameraPublisher | ros_cam_pub_ |
ReconfigureServer * | ros_cfg_ |
boost::recursive_mutex | ros_cfg_mutex_ |
unsigned int | ros_frame_count_ |
sensor_msgs::Image | ros_image_ |
ros::ServiceServer | set_cam_info_srv_ |
unsigned long long int | timeout_count_ |
ros::Publisher | timeout_pub_ |
std::string | timeout_topic_ |
Static Protected Attributes | |
static const std::map< INT, std::string > | ENCODING_DICTIONARY |
ROS interface nodelet for UEye camera API from IDS Imaging Development Systems GMBH.
Definition at line 72 of file ueye_cam_nodelet.hpp.
Definition at line 76 of file ueye_cam_nodelet.cpp.
ueye_cam::UEyeCamNodelet::~UEyeCamNodelet | ( | ) | [virtual] |
Definition at line 123 of file ueye_cam_nodelet.cpp.
void ueye_cam::UEyeCamNodelet::configCallback | ( | ueye_cam::UEyeCamConfig & | config, |
uint32_t | level | ||
) |
Handles callbacks from dynamic_reconfigure.
Definition at line 530 of file ueye_cam_nodelet.cpp.
INT ueye_cam::UEyeCamNodelet::connectCam | ( | ) | [protected, virtual] |
Initializes the camera handle, loads UEye INI configuration, refreshes parameters from camera, loads and sets static ROS parameters, and starts the frame grabber thread.
Definition at line 844 of file ueye_cam_nodelet.cpp.
INT ueye_cam::UEyeCamNodelet::disconnectCam | ( | ) | [protected, virtual] |
Stops the frame grabber thread, closes the camera handle, and releases all local variables.
Reimplemented from ueye_cam::UEyeCamDriver.
Definition at line 865 of file ueye_cam_nodelet.cpp.
bool ueye_cam::UEyeCamNodelet::fillMsgData | ( | sensor_msgs::Image & | img | ) | const [protected] |
Transfers the current frame content into given sensor_msgs::Image, therefore writes the fields width, height, encoding, step and data of img.
Definition at line 1100 of file ueye_cam_nodelet.cpp.
void ueye_cam::UEyeCamNodelet::frameGrabLoop | ( | ) | [protected] |
Main ROS interface "spin" loop.
Definition at line 889 of file ueye_cam_nodelet.cpp.
ros::Time ueye_cam::UEyeCamNodelet::getImageTickTimestamp | ( | ) | [protected] |
Returns image's timestamp based on device's internal clock or current wall time if driver call fails.
Definition at line 1181 of file ueye_cam_nodelet.cpp.
ros::Time ueye_cam::UEyeCamNodelet::getImageTimestamp | ( | ) | [protected] |
Returns image's timestamp or current wall time if driver call fails.
Definition at line 1166 of file ueye_cam_nodelet.cpp.
void ueye_cam::UEyeCamNodelet::handleTimeout | ( | ) | [protected, virtual] |
Reimplemented from ueye_cam::UEyeCamDriver.
Definition at line 1191 of file ueye_cam_nodelet.cpp.
void ueye_cam::UEyeCamNodelet::loadIntrinsicsFile | ( | ) | [protected] |
Loads the camera's intrinsic parameters from camIntrFilename.
Definition at line 1145 of file ueye_cam_nodelet.cpp.
void ueye_cam::UEyeCamNodelet::onInit | ( | ) | [virtual] |
Initializes ROS environment, loads static ROS parameters, initializes UEye camera, and starts live capturing / frame grabbing thread.
Implements nodelet::Nodelet.
Definition at line 136 of file ueye_cam_nodelet.cpp.
INT ueye_cam::UEyeCamNodelet::parseROSParams | ( | ros::NodeHandle & | local_nh | ) | [protected] |
Loads, validates, and updates static ROS parameters.
Definition at line 211 of file ueye_cam_nodelet.cpp.
INT ueye_cam::UEyeCamNodelet::queryCamParams | ( | ) | [protected] |
Reads parameter values from currently selected camera.
Definition at line 716 of file ueye_cam_nodelet.cpp.
bool ueye_cam::UEyeCamNodelet::saveIntrinsicsFile | ( | ) | [protected] |
Saves the camera's intrinsic parameters to camIntrFilename.
Definition at line 1157 of file ueye_cam_nodelet.cpp.
bool ueye_cam::UEyeCamNodelet::setCamInfo | ( | sensor_msgs::SetCameraInfo::Request & | req, |
sensor_msgs::SetCameraInfo::Response & | rsp | ||
) | [protected] |
(ROS Service) Updates the camera's intrinsic parameters over the ROS topic, and saves the parameters to a flatfile.
Definition at line 877 of file ueye_cam_nodelet.cpp.
void ueye_cam::UEyeCamNodelet::startFrameGrabber | ( | ) | [protected] |
Definition at line 1067 of file ueye_cam_nodelet.cpp.
void ueye_cam::UEyeCamNodelet::stopFrameGrabber | ( | ) | [protected] |
Definition at line 1073 of file ueye_cam_nodelet.cpp.
INT ueye_cam::UEyeCamNodelet::syncCamConfig | ( | std::string | dft_mode_str = "mono8" | ) | [protected, virtual] |
Calls UEyeCamDriver::syncCamConfig(), then updates ROS camera info and ROS image settings.
Reimplemented from ueye_cam::UEyeCamDriver.
Definition at line 683 of file ueye_cam_nodelet.cpp.
std::string ueye_cam::UEyeCamNodelet::cam_intr_filename_ [protected] |
Definition at line 201 of file ueye_cam_nodelet.hpp.
ueye_cam::UEyeCamConfig ueye_cam::UEyeCamNodelet::cam_params_ [protected] |
Definition at line 203 of file ueye_cam_nodelet.hpp.
std::string ueye_cam::UEyeCamNodelet::cam_params_filename_ [protected] |
Definition at line 202 of file ueye_cam_nodelet.hpp.
std::string ueye_cam::UEyeCamNodelet::cam_topic_ [protected] |
Definition at line 199 of file ueye_cam_nodelet.hpp.
bool ueye_cam::UEyeCamNodelet::cfg_sync_requested_ [protected] |
Definition at line 187 of file ueye_cam_nodelet.hpp.
const std::string ueye_cam::UEyeCamNodelet::DEFAULT_CAMERA_NAME = "camera" [static] |
Definition at line 85 of file ueye_cam_nodelet.hpp.
const std::string ueye_cam::UEyeCamNodelet::DEFAULT_CAMERA_TOPIC = "image_raw" [static] |
Definition at line 86 of file ueye_cam_nodelet.hpp.
const std::string ueye_cam::UEyeCamNodelet::DEFAULT_COLOR_MODE = "" [static] |
Definition at line 88 of file ueye_cam_nodelet.hpp.
constexpr double ueye_cam::UEyeCamNodelet::DEFAULT_EXPOSURE = 33.0 [static] |
Definition at line 79 of file ueye_cam_nodelet.hpp.
constexpr int ueye_cam::UEyeCamNodelet::DEFAULT_FLASH_DURATION = 1000 [static] |
Definition at line 82 of file ueye_cam_nodelet.hpp.
const std::string ueye_cam::UEyeCamNodelet::DEFAULT_FRAME_NAME = "camera" [static] |
Definition at line 84 of file ueye_cam_nodelet.hpp.
constexpr double ueye_cam::UEyeCamNodelet::DEFAULT_FRAME_RATE = 10.0 [static] |
Definition at line 80 of file ueye_cam_nodelet.hpp.
constexpr int ueye_cam::UEyeCamNodelet::DEFAULT_IMAGE_HEIGHT = 480 [static] |
Definition at line 78 of file ueye_cam_nodelet.hpp.
constexpr int ueye_cam::UEyeCamNodelet::DEFAULT_IMAGE_WIDTH = 640 [static] |
Definition at line 77 of file ueye_cam_nodelet.hpp.
constexpr int ueye_cam::UEyeCamNodelet::DEFAULT_PIXEL_CLOCK = 25 [static] |
Definition at line 81 of file ueye_cam_nodelet.hpp.
const std::string ueye_cam::UEyeCamNodelet::DEFAULT_TIMEOUT_TOPIC = "timeout_count" [static] |
Definition at line 87 of file ueye_cam_nodelet.hpp.
const std::map< INT, std::string > ueye_cam::UEyeCamNodelet::ENCODING_DICTIONARY [static, protected] |
{ { IS_CM_SENSOR_RAW8, sensor_msgs::image_encodings::BAYER_RGGB8 }, { IS_CM_SENSOR_RAW10, sensor_msgs::image_encodings::BAYER_RGGB16 }, { IS_CM_SENSOR_RAW12, sensor_msgs::image_encodings::BAYER_RGGB16 }, { IS_CM_SENSOR_RAW16, sensor_msgs::image_encodings::BAYER_RGGB16 }, { IS_CM_MONO8, sensor_msgs::image_encodings::MONO8 }, { IS_CM_MONO10, sensor_msgs::image_encodings::MONO16 }, { IS_CM_MONO12, sensor_msgs::image_encodings::MONO16 }, { IS_CM_MONO16, sensor_msgs::image_encodings::MONO16 }, { IS_CM_RGB8_PACKED, sensor_msgs::image_encodings::RGB8 }, { IS_CM_BGR8_PACKED, sensor_msgs::image_encodings::BGR8 }, { IS_CM_RGB10_PACKED, sensor_msgs::image_encodings::RGB16 }, { IS_CM_BGR10_PACKED, sensor_msgs::image_encodings::BGR16 }, { IS_CM_RGB10_UNPACKED, sensor_msgs::image_encodings::RGB16 }, { IS_CM_BGR10_UNPACKED, sensor_msgs::image_encodings::BGR16 }, { IS_CM_RGB12_UNPACKED, sensor_msgs::image_encodings::RGB16 }, { IS_CM_BGR12_UNPACKED, sensor_msgs::image_encodings::BGR16 } }
Definition at line 162 of file ueye_cam_nodelet.hpp.
bool ueye_cam::UEyeCamNodelet::frame_grab_alive_ [protected] |
Definition at line 183 of file ueye_cam_nodelet.hpp.
std::thread ueye_cam::UEyeCamNodelet::frame_grab_thread_ [protected] |
Definition at line 182 of file ueye_cam_nodelet.hpp.
std::string ueye_cam::UEyeCamNodelet::frame_name_ [protected] |
Definition at line 198 of file ueye_cam_nodelet.hpp.
uint64_t ueye_cam::UEyeCamNodelet::init_clock_tick_ [protected] |
Definition at line 206 of file ueye_cam_nodelet.hpp.
Definition at line 208 of file ueye_cam_nodelet.hpp.
ros::Time ueye_cam::UEyeCamNodelet::init_ros_time_ [protected] |
Definition at line 205 of file ueye_cam_nodelet.hpp.
boost::mutex ueye_cam::UEyeCamNodelet::output_rate_mutex_ [protected] |
Definition at line 210 of file ueye_cam_nodelet.hpp.
uint64_t ueye_cam::UEyeCamNodelet::prev_output_frame_idx_ [protected] |
Definition at line 209 of file ueye_cam_nodelet.hpp.
constexpr unsigned int ueye_cam::UEyeCamNodelet::RECONFIGURE_CLOSE = 3 [static] |
Definition at line 76 of file ueye_cam_nodelet.hpp.
constexpr unsigned int ueye_cam::UEyeCamNodelet::RECONFIGURE_RUNNING = 0 [static] |
Definition at line 74 of file ueye_cam_nodelet.hpp.
constexpr unsigned int ueye_cam::UEyeCamNodelet::RECONFIGURE_STOP = 1 [static] |
Definition at line 75 of file ueye_cam_nodelet.hpp.
sensor_msgs::CameraInfo ueye_cam::UEyeCamNodelet::ros_cam_info_ [protected] |
Definition at line 191 of file ueye_cam_nodelet.hpp.
Definition at line 189 of file ueye_cam_nodelet.hpp.
ReconfigureServer* ueye_cam::UEyeCamNodelet::ros_cfg_ [protected] |
Definition at line 185 of file ueye_cam_nodelet.hpp.
boost::recursive_mutex ueye_cam::UEyeCamNodelet::ros_cfg_mutex_ [protected] |
Definition at line 186 of file ueye_cam_nodelet.hpp.
unsigned int ueye_cam::UEyeCamNodelet::ros_frame_count_ [protected] |
Definition at line 192 of file ueye_cam_nodelet.hpp.
sensor_msgs::Image ueye_cam::UEyeCamNodelet::ros_image_ [protected] |
Definition at line 190 of file ueye_cam_nodelet.hpp.
Definition at line 196 of file ueye_cam_nodelet.hpp.
unsigned long long int ueye_cam::UEyeCamNodelet::timeout_count_ [protected] |
Definition at line 194 of file ueye_cam_nodelet.hpp.
ros::Publisher ueye_cam::UEyeCamNodelet::timeout_pub_ [protected] |
Definition at line 193 of file ueye_cam_nodelet.hpp.
std::string ueye_cam::UEyeCamNodelet::timeout_topic_ [protected] |
Definition at line 200 of file ueye_cam_nodelet.hpp.