#include <camera.h>
Public Member Functions | |
Camera (ros::NodeHandle comm_nh, ros::NodeHandle param_nh) | |
void | feedImages () |
void | onInit () |
void | sendInfo (sensor_msgs::ImagePtr &image, ros::Time time) |
void | sendInfoJpeg (ros::Time time) |
~Camera () | |
Private Attributes | |
uvc_cam::Cam * | cam |
std::string | device |
std::string | format |
int | fps |
std::string | frame |
int | frames_to_skip |
int | height |
boost::thread | image_thread |
camera_info_manager::CameraInfoManager | info_mgr |
ros::Publisher | info_pub |
image_transport::ImageTransport | it |
ros::NodeHandle | node |
bool | ok |
ros::NodeHandle | pnode |
image_transport::Publisher | pub |
ros::Publisher | pubjpeg |
bool | rotate |
int | skip_frames |
int | width |
uvc_camera::Camera::Camera | ( | ros::NodeHandle | comm_nh, |
ros::NodeHandle | param_nh | ||
) |
Definition at line 20 of file camera.cpp.
Definition at line 234 of file camera.cpp.
void uvc_camera::Camera::feedImages | ( | ) |
Definition at line 169 of file camera.cpp.
void uvc_camera::Camera::onInit | ( | ) |
void uvc_camera::Camera::sendInfo | ( | sensor_msgs::ImagePtr & | image, |
ros::Time | time | ||
) |
Definition at line 139 of file camera.cpp.
void uvc_camera::Camera::sendInfoJpeg | ( | ros::Time | time | ) |
Definition at line 161 of file camera.cpp.
uvc_cam::Cam* uvc_camera::Camera::cam [private] |
std::string uvc_camera::Camera::device [private] |
std::string uvc_camera::Camera::format [private] |
int uvc_camera::Camera::fps [private] |
std::string uvc_camera::Camera::frame [private] |
int uvc_camera::Camera::frames_to_skip [private] |
int uvc_camera::Camera::height [private] |
boost::thread uvc_camera::Camera::image_thread [private] |
ros::Publisher uvc_camera::Camera::info_pub [private] |
ros::NodeHandle uvc_camera::Camera::node [private] |
bool uvc_camera::Camera::ok [private] |
ros::NodeHandle uvc_camera::Camera::pnode [private] |
ros::Publisher uvc_camera::Camera::pubjpeg [private] |
bool uvc_camera::Camera::rotate [private] |
int uvc_camera::Camera::skip_frames [private] |
int uvc_camera::Camera::width [private] |