Public Member Functions | Protected Attributes | List of all members
V4RWideAngleNode Class Reference
Inheritance diagram for V4RWideAngleNode:
Inheritance graph
[legend]

Public Member Functions

void callbackParameters (tuw_uvc::CameraWideAngleConfig &config, uint32_t level)
 
 V4RWideAngleNode (ros::NodeHandle &n)
 
- Public Member Functions inherited from V4RCamNode
void publishCamera ()
 
void showCameraImage ()
 
 V4RCamNode (ros::NodeHandle &n)
 
 ~V4RCamNode ()
 
- Public Member Functions inherited from V4RCam
const std::vector< ControlEntryPtr > & detectControlEnties ()
 
ControlEntryPtr getControlEntry (std::string varName)
 
bool grab ()
 destructor More...
 
bool hasErrorMsg () const
 
bool hasInfoMsg () const
 
FD initCamera (const std::string &videoDevice="")
 vector of the current supported control entries More...
 
bool isBlackListed (int control)
 
int load_controls (const std::string &filename)
 
std::string pullErrorMsg ()
 
std::string pullInfoMsg ()
 
int save_controls (const std::string &filename)
 
int v4lget (ControlEntryPtr entry)
 
int v4lgetInfo (ControlEntryPtr entry)
 v4lcontrols More...
 
int v4lset (ControlEntryPtr entry)
 
int v4lupdate (ControlEntryPtr entry)
 
 V4RCam ()
 shared pointer for ControlEntry More...
 
 ~V4RCam ()
 construtor More...
 

Protected Attributes

dynamic_reconfigure::Server< tuw_uvc::CameraWideAngleConfig >::CallbackType reconfigureFnc_
 
dynamic_reconfigure::Server< tuw_uvc::CameraWideAngleConfig > reconfigureServer_
 
- Protected Attributes inherited from V4RCamNode
bool camera_freeze_
 
sensor_msgs::Image cameraImage_
 
sensor_msgs::CameraInfo cameraInfo_
 
image_transport::CameraPublisher cameraPublisher_
 
sensor_msgs::Image cameraThumbnail_
 
image_transport::Publisher cameraThumbnailPublisher_
 
int convert_image_
 
bool generate_dynamic_reconfigure_
 
image_transport::ImageTransport imageTransport_
 
ros::NodeHandle n_
 
ros::NodeHandle n_param_
 
bool queueRosParamToV4LCommit_
 
int ratioThumbnail_
 
ros::ServiceServer set_camera_info_srv_
 
bool show_camera_image_
 
boost::thread showCameraImageThread_
 
bool showCameraImageThreadActive_
 
ros::Subscriber subSphere_
 
- Protected Attributes inherited from V4RCam
std::string aviFilename_
 device name /dev/videoX More...
 
std::vector< ControlEntryPtrcontrolEntries_
 mutex to secure critical sections More...
 
double durationLastFrame_
 time stamp of the last frame More...
 
std::stringstream error_msg_
 
int format_
 not supported yet More...
 
float fps_
 image height More...
 
int grabmethod_
 image formate More...
 
int height_
 image width More...
 
std::stringstream info_msg_
 
boost::interprocess::interprocess_mutex mutexImage_
 duration between last and the frame before the last one More...
 
vdInpVideoIn_
 
timeval timeLastFrame_
 frames per second More...
 
std::string videoDevice_
 pointer to the v4l2 device More...
 
int width_
 

Additional Inherited Members

- Public Types inherited from V4RCam
typedef boost::shared_ptr< ControlEntryControlEntryPtr
 
typedef int FD
 
typedef boost::shared_ptr< v4l2_control > v4l2_controlPtr
 
- Static Public Member Functions inherited from V4RCam
static char removeNonAlNum (char in)
 
- Static Public Attributes inherited from V4RCamNode
static const int CONVERT_RAW = 0
 
static const int CONVERT_YUV422toBGR = 2
 
static const int CONVERT_YUV422toGray = 3
 
static const int CONVERT_YUV422toRGB = 1
 
- Static Public Attributes inherited from V4RCam
static const int ERROR = 1
 
static const int LOAD = 1
 
static const int NA = 0
 
static const int OK = 0
 
static const int SAVE = 2
 
- Protected Member Functions inherited from V4RCamNode
void callbackSphere (const tuw_uvc::SphereConstPtr &msg)
 
void commitRosParamsToV4L (bool force=false)
 
void commitV4LToRosParams ()
 
void loopCamera ()
 
void readCameraControls ()
 
void readControlEntryInfo (ControlEntry *entry)
 
void readInitParams ()
 
bool setCameraInfo (sensor_msgs::SetCameraInfoRequest &req, sensor_msgs::SetCameraInfoResponse &rsp)
 
void updateControlEntry (ControlEntry *entry)
 
void updateDynamicReconfigureFile (const char *filename) const
 
void writeCameraControls ()
 

Detailed Description

Definition at line 26 of file wide_angle_node.cpp.

Constructor & Destructor Documentation

V4RWideAngleNode::V4RWideAngleNode ( ros::NodeHandle n)
inline

Definition at line 28 of file wide_angle_node.cpp.

Member Function Documentation

void V4RWideAngleNode::callbackParameters ( tuw_uvc::CameraWideAngleConfig &  config,
uint32_t  level 
)
inline

Definition at line 32 of file wide_angle_node.cpp.

Member Data Documentation

dynamic_reconfigure::Server<tuw_uvc::CameraWideAngleConfig>::CallbackType V4RWideAngleNode::reconfigureFnc_
protected

Definition at line 39 of file wide_angle_node.cpp.

dynamic_reconfigure::Server<tuw_uvc::CameraWideAngleConfig> V4RWideAngleNode::reconfigureServer_
protected

Definition at line 38 of file wide_angle_node.cpp.


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


tuw_uvc
Author(s): Markus Bader
autogenerated on Mon Jun 10 2019 15:39:24