Public Member Functions | Private Types | Private Member Functions | Private Attributes
astra_wrapper::AstraDriver Class Reference

#include <astra_driver.h>

List of all members.

Public Member Functions

 AstraDriver (ros::NodeHandle &n, ros::NodeHandle &pnh)

Private Types

typedef astra_camera::AstraConfig Config
typedef
dynamic_reconfigure::Server
< Config
ReconfigureServer

Private Member Functions

void advertiseROSTopics ()
void applyConfigToOpenNIDevice ()
void configCb (Config &config, uint32_t level)
sensor_msgs::CameraInfo convertAstraCameraInfo (OBCameraParams p, ros::Time time) const
void depthConnectCb ()
void genVideoModeTableMap ()
bool getCameraInfoCb (astra_camera::GetCameraInfoRequest &req, astra_camera::GetCameraInfoResponse &res)
sensor_msgs::CameraInfoPtr getColorCameraInfo (int width, int height, ros::Time time) const
sensor_msgs::CameraInfoPtr getDefaultCameraInfo (int width, int height, double f) const
sensor_msgs::CameraInfoPtr getDepthCameraInfo (int width, int height, ros::Time time) const
bool getDeviceTypeCb (astra_camera::GetDeviceTypeRequest &req, astra_camera::GetDeviceTypeResponse &res)
sensor_msgs::CameraInfoPtr getIRCameraInfo (int width, int height, ros::Time time) const
bool getIRExposureCb (astra_camera::GetIRExposureRequest &req, astra_camera::GetIRExposureResponse &res)
bool getIRGainCb (astra_camera::GetIRGainRequest &req, astra_camera::GetIRGainResponse &res)
sensor_msgs::CameraInfoPtr getProjectorCameraInfo (int width, int height, ros::Time time) const
bool getSerialCb (astra_camera::GetSerialRequest &req, astra_camera::GetSerialResponse &res)
void imageConnectCb ()
void initDevice ()
int lookupVideoModeFromDynConfig (int mode_nr, AstraVideoMode &video_mode)
void newColorFrameCallback (sensor_msgs::ImagePtr image)
void newDepthFrameCallback (sensor_msgs::ImagePtr image)
void newIRFrameCallback (sensor_msgs::ImagePtr image)
sensor_msgs::ImageConstPtr rawToFloatingPointConversion (sensor_msgs::ImageConstPtr raw_image)
void readConfigFromParameterServer ()
bool resetIRExposureCb (astra_camera::ResetIRExposureRequest &req, astra_camera::ResetIRExposureResponse &res)
bool resetIRGainCb (astra_camera::ResetIRGainRequest &req, astra_camera::ResetIRGainResponse &res)
std::string resolveDeviceURI (const std::string &device_id)
void setColorVideoMode (const AstraVideoMode &color_video_mode)
void setDepthVideoMode (const AstraVideoMode &depth_video_mode)
bool setIRExposureCb (astra_camera::SetIRExposureRequest &req, astra_camera::SetIRExposureResponse &res)
bool setIRFloodCb (astra_camera::SetIRFloodRequest &req, astra_camera::SetIRFloodResponse &res)
bool setIRGainCb (astra_camera::SetIRGainRequest &req, astra_camera::SetIRGainResponse &res)
void setIRVideoMode (const AstraVideoMode &ir_video_mode)
bool setLaserCb (astra_camera::SetLaserRequest &req, astra_camera::SetLaserResponse &res)

Private Attributes

std::set< std::string > alreadyOpen
bool auto_exposure_
bool auto_white_balance_
bool color_depth_synchronization_
std::string color_frame_id_
boost::shared_ptr
< camera_info_manager::CameraInfoManager
color_info_manager_
 Camera info manager objects.
std::string color_info_url_
bool color_subscribers_
ros::Duration color_time_offset_
AstraVideoMode color_video_mode_
bool config_init_
boost::mutex connect_mutex_
int data_skip_
int data_skip_color_counter_
int data_skip_depth_counter_
int data_skip_ir_counter_
std::string depth_frame_id_
double depth_ir_offset_x_
double depth_ir_offset_y_
bool depth_raw_subscribers_
bool depth_registration_
bool depth_subscribers_
ros::Duration depth_time_offset_
AstraVideoMode depth_video_mode_
boost::shared_ptr< AstraDevicedevice_
std::string device_id_
boost::shared_ptr
< AstraDeviceManager
device_manager_
ros::ServiceServer get_camera_info
 get_serial server
ros::ServiceServer get_device_type_server
ros::ServiceServer get_ir_exposure_server
ros::ServiceServer get_ir_gain_server
ros::ServiceServer get_serial_server
std::string ir_frame_id_
boost::shared_ptr
< camera_info_manager::CameraInfoManager
ir_info_manager_
std::string ir_info_url_
bool ir_subscribers_
ros::Duration ir_time_offset_
AstraVideoMode ir_video_mode_
ros::NodeHandlenh_
Config old_config_
ros::NodeHandlepnh_
bool projector_info_subscribers_
image_transport::CameraPublisher pub_color_
image_transport::CameraPublisher pub_depth_
image_transport::CameraPublisher pub_depth_raw_
image_transport::CameraPublisher pub_ir_
ros::Publisher pub_projector_info_
boost::shared_ptr
< ReconfigureServer
reconfigure_server_
 reconfigure server
ros::ServiceServer reset_ir_exposure_server
ros::ServiceServer reset_ir_gain_server
bool rgb_preferred_
ros::ServiceServer set_ir_exposure_server
ros::ServiceServer set_ir_flood_server
ros::ServiceServer set_ir_gain_server
ros::ServiceServer set_laser_server
bool use_device_time_
int uvc_flip_
std::map< int, AstraVideoModevideo_modes_lookup_
int z_offset_mm_
double z_scaling_

Detailed Description

Definition at line 72 of file astra_driver.h.


Member Typedef Documentation

typedef astra_camera::AstraConfig astra_wrapper::AstraDriver::Config [private]

Definition at line 78 of file astra_driver.h.

typedef dynamic_reconfigure::Server<Config> astra_wrapper::AstraDriver::ReconfigureServer [private]

Definition at line 79 of file astra_driver.h.


Constructor & Destructor Documentation

Definition at line 51 of file astra_driver.cpp.


Member Function Documentation

Definition at line 157 of file astra_driver.cpp.

Definition at line 416 of file astra_driver.cpp.

void astra_wrapper::AstraDriver::configCb ( Config config,
uint32_t  level 
) [private]

Definition at line 302 of file astra_driver.cpp.

sensor_msgs::CameraInfo astra_wrapper::AstraDriver::convertAstraCameraInfo ( OBCameraParams  p,
ros::Time  time 
) const [private]

Definition at line 656 of file astra_driver.cpp.

Definition at line 541 of file astra_driver.cpp.

Definition at line 1074 of file astra_driver.cpp.

bool astra_wrapper::AstraDriver::getCameraInfoCb ( astra_camera::GetCameraInfoRequest &  req,
astra_camera::GetCameraInfoResponse &  res 
) [private]

Definition at line 290 of file astra_driver.cpp.

sensor_msgs::CameraInfoPtr astra_wrapper::AstraDriver::getColorCameraInfo ( int  width,
int  height,
ros::Time  time 
) const [private]
Todo:
Use binning/ROI properly in publishing camera infos

Definition at line 733 of file astra_driver.cpp.

sensor_msgs::CameraInfoPtr astra_wrapper::AstraDriver::getDefaultCameraInfo ( int  width,
int  height,
double  f 
) const [private]

Definition at line 698 of file astra_driver.cpp.

sensor_msgs::CameraInfoPtr astra_wrapper::AstraDriver::getDepthCameraInfo ( int  width,
int  height,
ros::Time  time 
) const [private]
Todo:
Could put this in projector frame so as to encode the baseline in P[3]

Definition at line 844 of file astra_driver.cpp.

bool astra_wrapper::AstraDriver::getDeviceTypeCb ( astra_camera::GetDeviceTypeRequest &  req,
astra_camera::GetDeviceTypeResponse &  res 
) [private]

Definition at line 242 of file astra_driver.cpp.

sensor_msgs::CameraInfoPtr astra_wrapper::AstraDriver::getIRCameraInfo ( int  width,
int  height,
ros::Time  time 
) const [private]

Definition at line 792 of file astra_driver.cpp.

bool astra_wrapper::AstraDriver::getIRExposureCb ( astra_camera::GetIRExposureRequest &  req,
astra_camera::GetIRExposureResponse &  res 
) [private]

Definition at line 260 of file astra_driver.cpp.

bool astra_wrapper::AstraDriver::getIRGainCb ( astra_camera::GetIRGainRequest &  req,
astra_camera::GetIRGainResponse &  res 
) [private]

Definition at line 248 of file astra_driver.cpp.

sensor_msgs::CameraInfoPtr astra_wrapper::AstraDriver::getProjectorCameraInfo ( int  width,
int  height,
ros::Time  time 
) const [private]

Definition at line 862 of file astra_driver.cpp.

bool astra_wrapper::AstraDriver::getSerialCb ( astra_camera::GetSerialRequest &  req,
astra_camera::GetSerialResponse &  res 
) [private]

Definition at line 236 of file astra_driver.cpp.

Definition at line 477 of file astra_driver.cpp.

Definition at line 1034 of file astra_driver.cpp.

int astra_wrapper::AstraDriver::lookupVideoModeFromDynConfig ( int  mode_nr,
AstraVideoMode video_mode 
) [private]

Definition at line 1198 of file astra_driver.cpp.

void astra_wrapper::AstraDriver::newColorFrameCallback ( sensor_msgs::ImagePtr  image) [private]

Definition at line 581 of file astra_driver.cpp.

void astra_wrapper::AstraDriver::newDepthFrameCallback ( sensor_msgs::ImagePtr  image) [private]

Definition at line 597 of file astra_driver.cpp.

void astra_wrapper::AstraDriver::newIRFrameCallback ( sensor_msgs::ImagePtr  image) [private]

Definition at line 565 of file astra_driver.cpp.

sensor_msgs::ImageConstPtr astra_wrapper::AstraDriver::rawToFloatingPointConversion ( sensor_msgs::ImageConstPtr  raw_image) [private]

Definition at line 1215 of file astra_driver.cpp.

Definition at line 873 of file astra_driver.cpp.

bool astra_wrapper::AstraDriver::resetIRExposureCb ( astra_camera::ResetIRExposureRequest &  req,
astra_camera::ResetIRExposureResponse &  res 
) [private]

Definition at line 284 of file astra_driver.cpp.

bool astra_wrapper::AstraDriver::resetIRGainCb ( astra_camera::ResetIRGainRequest &  req,
astra_camera::ResetIRGainResponse &  res 
) [private]

Definition at line 278 of file astra_driver.cpp.

std::string astra_wrapper::AstraDriver::resolveDeviceURI ( const std::string &  device_id) [private]

Definition at line 895 of file astra_driver.cpp.

void astra_wrapper::AstraDriver::setColorVideoMode ( const AstraVideoMode color_video_mode) [private]

Definition at line 387 of file astra_driver.cpp.

void astra_wrapper::AstraDriver::setDepthVideoMode ( const AstraVideoMode depth_video_mode) [private]

Definition at line 401 of file astra_driver.cpp.

bool astra_wrapper::AstraDriver::setIRExposureCb ( astra_camera::SetIRExposureRequest &  req,
astra_camera::SetIRExposureResponse &  res 
) [private]

Definition at line 266 of file astra_driver.cpp.

bool astra_wrapper::AstraDriver::setIRFloodCb ( astra_camera::SetIRFloodRequest &  req,
astra_camera::SetIRFloodResponse &  res 
) [private]

Definition at line 296 of file astra_driver.cpp.

bool astra_wrapper::AstraDriver::setIRGainCb ( astra_camera::SetIRGainRequest &  req,
astra_camera::SetIRGainResponse &  res 
) [private]

Definition at line 254 of file astra_driver.cpp.

void astra_wrapper::AstraDriver::setIRVideoMode ( const AstraVideoMode ir_video_mode) [private]

Definition at line 372 of file astra_driver.cpp.

bool astra_wrapper::AstraDriver::setLaserCb ( astra_camera::SetLaserRequest &  req,
astra_camera::SetLaserResponse &  res 
) [private]

Definition at line 272 of file astra_driver.cpp.


Member Data Documentation

Definition at line 154 of file astra_driver.h.

Definition at line 199 of file astra_driver.h.

Definition at line 200 of file astra_driver.h.

Definition at line 176 of file astra_driver.h.

Definition at line 171 of file astra_driver.h.

Camera info manager objects.

Definition at line 164 of file astra_driver.h.

Definition at line 174 of file astra_driver.h.

Definition at line 203 of file astra_driver.h.

Definition at line 188 of file astra_driver.h.

Definition at line 167 of file astra_driver.h.

Definition at line 152 of file astra_driver.h.

Definition at line 155 of file astra_driver.h.

Definition at line 191 of file astra_driver.h.

Definition at line 194 of file astra_driver.h.

Definition at line 195 of file astra_driver.h.

Definition at line 193 of file astra_driver.h.

Definition at line 172 of file astra_driver.h.

Definition at line 182 of file astra_driver.h.

Definition at line 183 of file astra_driver.h.

Definition at line 205 of file astra_driver.h.

Definition at line 177 of file astra_driver.h.

Definition at line 204 of file astra_driver.h.

Definition at line 189 of file astra_driver.h.

Definition at line 168 of file astra_driver.h.

boost::shared_ptr<AstraDevice> astra_wrapper::AstraDriver::device_ [private]

Definition at line 133 of file astra_driver.h.

Definition at line 135 of file astra_driver.h.

Definition at line 132 of file astra_driver.h.

get_serial server

Definition at line 138 of file astra_driver.h.

Definition at line 140 of file astra_driver.h.

Definition at line 143 of file astra_driver.h.

Definition at line 141 of file astra_driver.h.

Definition at line 139 of file astra_driver.h.

Definition at line 170 of file astra_driver.h.

Definition at line 164 of file astra_driver.h.

Definition at line 174 of file astra_driver.h.

Definition at line 202 of file astra_driver.h.

Definition at line 187 of file astra_driver.h.

Definition at line 166 of file astra_driver.h.

Definition at line 129 of file astra_driver.h.

Definition at line 210 of file astra_driver.h.

Definition at line 130 of file astra_driver.h.

Definition at line 206 of file astra_driver.h.

Definition at line 157 of file astra_driver.h.

Definition at line 158 of file astra_driver.h.

Definition at line 159 of file astra_driver.h.

Definition at line 160 of file astra_driver.h.

Definition at line 161 of file astra_driver.h.

reconfigure server

Definition at line 151 of file astra_driver.h.

Definition at line 148 of file astra_driver.h.

Definition at line 147 of file astra_driver.h.

Definition at line 197 of file astra_driver.h.

Definition at line 144 of file astra_driver.h.

Definition at line 145 of file astra_driver.h.

Definition at line 142 of file astra_driver.h.

Definition at line 146 of file astra_driver.h.

Definition at line 208 of file astra_driver.h.

Definition at line 211 of file astra_driver.h.

Definition at line 179 of file astra_driver.h.

Definition at line 184 of file astra_driver.h.

Definition at line 185 of file astra_driver.h.


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


astra_camera
Author(s): Tim Liu
autogenerated on Wed Jul 10 2019 03:18:55