#include <vrmstnode.h>
Public Member Functions | |
| void | retireCam () | 
| void | spin () | 
| VRMagicStereoNode (VRmDWORD camDesired) | |
| ~VRMagicStereoNode () | |
Private Member Functions | |
| void | AbandonTopics () | 
| void | AnnounceTopics () | 
| void | broadcastFrame () | 
| void | grabFrame (VRmDWORD port, sensor_msgs::Image &img, const ros::Time &triggerTime) | 
| void | initCam (VRmDWORD camDesired) | 
| void | initProperties () | 
| void | loadCalibration () | 
| void | propertyUpdate (vrmagic_multi_driver::CamParamsConfig &config, uint32_t level) | 
| bool | runUpdateLeft (sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &res) | 
| bool | runUpdateRight (sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &res) | 
| void | storeCalibration () | 
Private Attributes | |
| boost::mutex | calibAccess | 
| bool | calibrated | 
| boost::mutex | camAccess | 
| image_transport::CameraPublisher | camPubLeft | 
| image_transport::CameraPublisher | camPubRight | 
| dynamic_reconfigure::Server < vrmagic_multi_driver::CamParamsConfig >  | dConfServer | 
| VRmUsbCamDevice | device | 
| ros::Rate | fpsLimit | 
| const std::string | frame_id | 
| unsigned int | framesDelivered | 
| unsigned int | height | 
| sensor_msgs::Image | imgLeft | 
| sensor_msgs::Image | imgRight | 
| sensor_msgs::CameraInfo | leftCalib | 
| ros::ServiceServer | leftCalibUpdate | 
| ros::NodeHandle | leftNs | 
| PropertyCache * | props | 
| sensor_msgs::CameraInfo | rightCalib | 
| ros::ServiceServer | rightCalibUpdate | 
| ros::NodeHandle | rightNs | 
| ros::NodeHandle | thisNode | 
| boost::mutex | timerAccess | 
| unsigned int | width | 
Definition at line 51 of file vrmstnode.h.
| VRMagicStereoNode::VRMagicStereoNode | ( | VRmDWORD | camDesired | ) | 
Definition at line 381 of file vrmstnode.cpp.
Definition at line 392 of file vrmstnode.cpp.
| void VRMagicStereoNode::AbandonTopics | ( | ) |  [private] | 
        
Definition at line 216 of file vrmstnode.cpp.
| void VRMagicStereoNode::AnnounceTopics | ( | ) |  [private] | 
        
Definition at line 208 of file vrmstnode.cpp.
| void VRMagicStereoNode::broadcastFrame | ( | ) |  [private] | 
        
Definition at line 224 of file vrmstnode.cpp.
| void VRMagicStereoNode::grabFrame | ( | VRmDWORD | port, | 
| sensor_msgs::Image & | img, | ||
| const ros::Time & | triggerTime | ||
| ) |  [private] | 
        
Definition at line 262 of file vrmstnode.cpp.
| void VRMagicStereoNode::initCam | ( | VRmDWORD | camDesired | ) |  [private] | 
        
Definition at line 320 of file vrmstnode.cpp.
| void VRMagicStereoNode::initProperties | ( | ) |  [private] | 
        
Definition at line 297 of file vrmstnode.cpp.
| void VRMagicStereoNode::loadCalibration | ( | ) |  [private] | 
        
Definition at line 156 of file vrmstnode.cpp.
| void VRMagicStereoNode::propertyUpdate | ( | vrmagic_multi_driver::CamParamsConfig & | config, | 
| uint32_t | level | ||
| ) |  [private] | 
        
Definition at line 67 of file vrmstnode.cpp.
| void VRMagicStereoNode::retireCam | ( | ) | 
Definition at line 370 of file vrmstnode.cpp.
| bool VRMagicStereoNode::runUpdateLeft | ( | sensor_msgs::SetCameraInfo::Request & | req, | 
| sensor_msgs::SetCameraInfo::Response & | res | ||
| ) |  [private] | 
        
Definition at line 134 of file vrmstnode.cpp.
| bool VRMagicStereoNode::runUpdateRight | ( | sensor_msgs::SetCameraInfo::Request & | req, | 
| sensor_msgs::SetCameraInfo::Response & | res | ||
| ) |  [private] | 
        
Definition at line 145 of file vrmstnode.cpp.
| void VRMagicStereoNode::spin | ( | ) | 
Definition at line 399 of file vrmstnode.cpp.
| void VRMagicStereoNode::storeCalibration | ( | ) |  [private] | 
        
Definition at line 180 of file vrmstnode.cpp.
boost::mutex VRMagicStereoNode::calibAccess [private] | 
        
Definition at line 66 of file vrmstnode.h.
bool VRMagicStereoNode::calibrated [private] | 
        
Definition at line 54 of file vrmstnode.h.
boost::mutex VRMagicStereoNode::camAccess [private] | 
        
Definition at line 66 of file vrmstnode.h.
Definition at line 58 of file vrmstnode.h.
Definition at line 58 of file vrmstnode.h.
dynamic_reconfigure::Server<vrmagic_multi_driver::CamParamsConfig> VRMagicStereoNode::dConfServer [private] | 
        
Definition at line 62 of file vrmstnode.h.
VRmUsbCamDevice VRMagicStereoNode::device [private] | 
        
Definition at line 64 of file vrmstnode.h.
ros::Rate VRMagicStereoNode::fpsLimit [private] | 
        
Definition at line 63 of file vrmstnode.h.
const std::string VRMagicStereoNode::frame_id [private] | 
        
Definition at line 69 of file vrmstnode.h.
unsigned int VRMagicStereoNode::framesDelivered [private] | 
        
Definition at line 55 of file vrmstnode.h.
unsigned int VRMagicStereoNode::height [private] | 
        
Definition at line 56 of file vrmstnode.h.
sensor_msgs::Image VRMagicStereoNode::imgLeft [private] | 
        
Definition at line 67 of file vrmstnode.h.
sensor_msgs::Image VRMagicStereoNode::imgRight [private] | 
        
Definition at line 68 of file vrmstnode.h.
sensor_msgs::CameraInfo VRMagicStereoNode::leftCalib [private] | 
        
Definition at line 59 of file vrmstnode.h.
Definition at line 60 of file vrmstnode.h.
ros::NodeHandle VRMagicStereoNode::leftNs [private] | 
        
Definition at line 57 of file vrmstnode.h.
PropertyCache* VRMagicStereoNode::props [private] | 
        
Definition at line 65 of file vrmstnode.h.
sensor_msgs::CameraInfo VRMagicStereoNode::rightCalib [private] | 
        
Definition at line 59 of file vrmstnode.h.
Definition at line 60 of file vrmstnode.h.
ros::NodeHandle VRMagicStereoNode::rightNs [private] | 
        
Definition at line 57 of file vrmstnode.h.
ros::NodeHandle VRMagicStereoNode::thisNode [private] | 
        
Definition at line 57 of file vrmstnode.h.
boost::mutex VRMagicStereoNode::timerAccess [private] | 
        
Definition at line 66 of file vrmstnode.h.
unsigned int VRMagicStereoNode::width [private] | 
        
Definition at line 56 of file vrmstnode.h.