Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
astra_wrapper::AstraDriver Class Reference

#include <astra_driver.h>

Public Member Functions

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

Private Types

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

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)
 
bool setLDPCb (astra_camera::SetLDPRequest &req, astra_camera::SetLDPResponse &res)
 
bool switchIRCameraCb (astra_camera::SwitchIRCameraRequest &req, astra_camera::SwitchIRCameraResponse &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::CameraInfoManagercolor_info_manager_
 Camera info manager objects. More...
 
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< AstraDeviceManagerdevice_manager_
 
ros::ServiceServer get_camera_info
 get_serial server More...
 
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::CameraInfoManagerir_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< ReconfigureServerreconfigure_server_
 reconfigure server More...
 
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
 
ros::ServiceServer set_ldp_server
 
ros::ServiceServer switch_ir_camera
 
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 75 of file astra_driver.h.

Member Typedef Documentation

◆ Config

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

Definition at line 82 of file astra_driver.h.

◆ ReconfigureServer

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

Definition at line 83 of file astra_driver.h.

Constructor & Destructor Documentation

◆ AstraDriver()

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

Definition at line 51 of file astra_driver.cpp.

◆ ~AstraDriver()

astra_wrapper::AstraDriver::~AstraDriver ( )

Definition at line 157 of file astra_driver.cpp.

Member Function Documentation

◆ advertiseROSTopics()

void astra_wrapper::AstraDriver::advertiseROSTopics ( )
private

Definition at line 161 of file astra_driver.cpp.

◆ applyConfigToOpenNIDevice()

void astra_wrapper::AstraDriver::applyConfigToOpenNIDevice ( )
private

Definition at line 467 of file astra_driver.cpp.

◆ configCb()

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

Definition at line 328 of file astra_driver.cpp.

◆ convertAstraCameraInfo()

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

Definition at line 706 of file astra_driver.cpp.

◆ depthConnectCb()

void astra_wrapper::AstraDriver::depthConnectCb ( )
private

Definition at line 592 of file astra_driver.cpp.

◆ genVideoModeTableMap()

void astra_wrapper::AstraDriver::genVideoModeTableMap ( )
private

Definition at line 1146 of file astra_driver.cpp.

◆ getCameraInfoCb()

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

Definition at line 305 of file astra_driver.cpp.

◆ getColorCameraInfo()

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 783 of file astra_driver.cpp.

◆ getDefaultCameraInfo()

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

Definition at line 748 of file astra_driver.cpp.

◆ getDepthCameraInfo()

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 918 of file astra_driver.cpp.

◆ getDeviceTypeCb()

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

Definition at line 251 of file astra_driver.cpp.

◆ getIRCameraInfo()

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

Definition at line 849 of file astra_driver.cpp.

◆ getIRExposureCb()

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

Definition at line 269 of file astra_driver.cpp.

◆ getIRGainCb()

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

Definition at line 257 of file astra_driver.cpp.

◆ getProjectorCameraInfo()

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

Definition at line 934 of file astra_driver.cpp.

◆ getSerialCb()

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

Definition at line 245 of file astra_driver.cpp.

◆ imageConnectCb()

void astra_wrapper::AstraDriver::imageConnectCb ( )
private

Definition at line 528 of file astra_driver.cpp.

◆ initDevice()

void astra_wrapper::AstraDriver::initDevice ( )
private

Definition at line 1106 of file astra_driver.cpp.

◆ lookupVideoModeFromDynConfig()

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

Definition at line 1294 of file astra_driver.cpp.

◆ newColorFrameCallback()

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

Definition at line 632 of file astra_driver.cpp.

◆ newDepthFrameCallback()

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

Definition at line 648 of file astra_driver.cpp.

◆ newIRFrameCallback()

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

Definition at line 616 of file astra_driver.cpp.

◆ rawToFloatingPointConversion()

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

Definition at line 1311 of file astra_driver.cpp.

◆ readConfigFromParameterServer()

void astra_wrapper::AstraDriver::readConfigFromParameterServer ( )
private

Definition at line 945 of file astra_driver.cpp.

◆ resetIRExposureCb()

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

Definition at line 299 of file astra_driver.cpp.

◆ resetIRGainCb()

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

Definition at line 293 of file astra_driver.cpp.

◆ resolveDeviceURI()

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

Definition at line 967 of file astra_driver.cpp.

◆ setColorVideoMode()

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

Definition at line 438 of file astra_driver.cpp.

◆ setDepthVideoMode()

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

Definition at line 452 of file astra_driver.cpp.

◆ setIRExposureCb()

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

Definition at line 275 of file astra_driver.cpp.

◆ setIRFloodCb()

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

Definition at line 311 of file astra_driver.cpp.

◆ setIRGainCb()

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

Definition at line 263 of file astra_driver.cpp.

◆ setIRVideoMode()

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

Definition at line 423 of file astra_driver.cpp.

◆ setLaserCb()

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

Definition at line 281 of file astra_driver.cpp.

◆ setLDPCb()

bool astra_wrapper::AstraDriver::setLDPCb ( astra_camera::SetLDPRequest &  req,
astra_camera::SetLDPResponse &  res 
)
private

Definition at line 287 of file astra_driver.cpp.

◆ switchIRCameraCb()

bool astra_wrapper::AstraDriver::switchIRCameraCb ( astra_camera::SwitchIRCameraRequest &  req,
astra_camera::SwitchIRCameraResponse &  res 
)
private

Definition at line 317 of file astra_driver.cpp.

Member Data Documentation

◆ alreadyOpen

std::set<std::string> astra_wrapper::AstraDriver::alreadyOpen
private

Definition at line 162 of file astra_driver.h.

◆ auto_exposure_

bool astra_wrapper::AstraDriver::auto_exposure_
private

Definition at line 207 of file astra_driver.h.

◆ auto_white_balance_

bool astra_wrapper::AstraDriver::auto_white_balance_
private

Definition at line 208 of file astra_driver.h.

◆ color_depth_synchronization_

bool astra_wrapper::AstraDriver::color_depth_synchronization_
private

Definition at line 184 of file astra_driver.h.

◆ color_frame_id_

std::string astra_wrapper::AstraDriver::color_frame_id_
private

Definition at line 179 of file astra_driver.h.

◆ color_info_manager_

boost::shared_ptr<camera_info_manager::CameraInfoManager> astra_wrapper::AstraDriver::color_info_manager_
private

Camera info manager objects.

Definition at line 172 of file astra_driver.h.

◆ color_info_url_

std::string astra_wrapper::AstraDriver::color_info_url_
private

Definition at line 182 of file astra_driver.h.

◆ color_subscribers_

bool astra_wrapper::AstraDriver::color_subscribers_
private

Definition at line 211 of file astra_driver.h.

◆ color_time_offset_

ros::Duration astra_wrapper::AstraDriver::color_time_offset_
private

Definition at line 196 of file astra_driver.h.

◆ color_video_mode_

AstraVideoMode astra_wrapper::AstraDriver::color_video_mode_
private

Definition at line 175 of file astra_driver.h.

◆ config_init_

bool astra_wrapper::AstraDriver::config_init_
private

Definition at line 160 of file astra_driver.h.

◆ connect_mutex_

boost::mutex astra_wrapper::AstraDriver::connect_mutex_
private

Definition at line 163 of file astra_driver.h.

◆ data_skip_

int astra_wrapper::AstraDriver::data_skip_
private

Definition at line 199 of file astra_driver.h.

◆ data_skip_color_counter_

int astra_wrapper::AstraDriver::data_skip_color_counter_
private

Definition at line 202 of file astra_driver.h.

◆ data_skip_depth_counter_

int astra_wrapper::AstraDriver::data_skip_depth_counter_
private

Definition at line 203 of file astra_driver.h.

◆ data_skip_ir_counter_

int astra_wrapper::AstraDriver::data_skip_ir_counter_
private

Definition at line 201 of file astra_driver.h.

◆ depth_frame_id_

std::string astra_wrapper::AstraDriver::depth_frame_id_
private

Definition at line 180 of file astra_driver.h.

◆ depth_ir_offset_x_

double astra_wrapper::AstraDriver::depth_ir_offset_x_
private

Definition at line 190 of file astra_driver.h.

◆ depth_ir_offset_y_

double astra_wrapper::AstraDriver::depth_ir_offset_y_
private

Definition at line 191 of file astra_driver.h.

◆ depth_raw_subscribers_

bool astra_wrapper::AstraDriver::depth_raw_subscribers_
private

Definition at line 213 of file astra_driver.h.

◆ depth_registration_

bool astra_wrapper::AstraDriver::depth_registration_
private

Definition at line 185 of file astra_driver.h.

◆ depth_subscribers_

bool astra_wrapper::AstraDriver::depth_subscribers_
private

Definition at line 212 of file astra_driver.h.

◆ depth_time_offset_

ros::Duration astra_wrapper::AstraDriver::depth_time_offset_
private

Definition at line 197 of file astra_driver.h.

◆ depth_video_mode_

AstraVideoMode astra_wrapper::AstraDriver::depth_video_mode_
private

Definition at line 176 of file astra_driver.h.

◆ device_

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

Definition at line 139 of file astra_driver.h.

◆ device_id_

std::string astra_wrapper::AstraDriver::device_id_
private

Definition at line 141 of file astra_driver.h.

◆ device_manager_

boost::shared_ptr<AstraDeviceManager> astra_wrapper::AstraDriver::device_manager_
private

Definition at line 138 of file astra_driver.h.

◆ get_camera_info

ros::ServiceServer astra_wrapper::AstraDriver::get_camera_info
private

get_serial server

Definition at line 144 of file astra_driver.h.

◆ get_device_type_server

ros::ServiceServer astra_wrapper::AstraDriver::get_device_type_server
private

Definition at line 146 of file astra_driver.h.

◆ get_ir_exposure_server

ros::ServiceServer astra_wrapper::AstraDriver::get_ir_exposure_server
private

Definition at line 149 of file astra_driver.h.

◆ get_ir_gain_server

ros::ServiceServer astra_wrapper::AstraDriver::get_ir_gain_server
private

Definition at line 147 of file astra_driver.h.

◆ get_serial_server

ros::ServiceServer astra_wrapper::AstraDriver::get_serial_server
private

Definition at line 145 of file astra_driver.h.

◆ ir_frame_id_

std::string astra_wrapper::AstraDriver::ir_frame_id_
private

Definition at line 178 of file astra_driver.h.

◆ ir_info_manager_

boost::shared_ptr<camera_info_manager::CameraInfoManager> astra_wrapper::AstraDriver::ir_info_manager_
private

Definition at line 172 of file astra_driver.h.

◆ ir_info_url_

std::string astra_wrapper::AstraDriver::ir_info_url_
private

Definition at line 182 of file astra_driver.h.

◆ ir_subscribers_

bool astra_wrapper::AstraDriver::ir_subscribers_
private

Definition at line 210 of file astra_driver.h.

◆ ir_time_offset_

ros::Duration astra_wrapper::AstraDriver::ir_time_offset_
private

Definition at line 195 of file astra_driver.h.

◆ ir_video_mode_

AstraVideoMode astra_wrapper::AstraDriver::ir_video_mode_
private

Definition at line 174 of file astra_driver.h.

◆ nh_

ros::NodeHandle& astra_wrapper::AstraDriver::nh_
private

Definition at line 135 of file astra_driver.h.

◆ old_config_

Config astra_wrapper::AstraDriver::old_config_
private

Definition at line 218 of file astra_driver.h.

◆ pnh_

ros::NodeHandle& astra_wrapper::AstraDriver::pnh_
private

Definition at line 136 of file astra_driver.h.

◆ projector_info_subscribers_

bool astra_wrapper::AstraDriver::projector_info_subscribers_
private

Definition at line 214 of file astra_driver.h.

◆ pub_color_

image_transport::CameraPublisher astra_wrapper::AstraDriver::pub_color_
private

Definition at line 165 of file astra_driver.h.

◆ pub_depth_

image_transport::CameraPublisher astra_wrapper::AstraDriver::pub_depth_
private

Definition at line 166 of file astra_driver.h.

◆ pub_depth_raw_

image_transport::CameraPublisher astra_wrapper::AstraDriver::pub_depth_raw_
private

Definition at line 167 of file astra_driver.h.

◆ pub_ir_

image_transport::CameraPublisher astra_wrapper::AstraDriver::pub_ir_
private

Definition at line 168 of file astra_driver.h.

◆ pub_projector_info_

ros::Publisher astra_wrapper::AstraDriver::pub_projector_info_
private

Definition at line 169 of file astra_driver.h.

◆ reconfigure_server_

boost::shared_ptr<ReconfigureServer> astra_wrapper::AstraDriver::reconfigure_server_
private

reconfigure server

Definition at line 159 of file astra_driver.h.

◆ reset_ir_exposure_server

ros::ServiceServer astra_wrapper::AstraDriver::reset_ir_exposure_server
private

Definition at line 155 of file astra_driver.h.

◆ reset_ir_gain_server

ros::ServiceServer astra_wrapper::AstraDriver::reset_ir_gain_server
private

Definition at line 154 of file astra_driver.h.

◆ rgb_preferred_

bool astra_wrapper::AstraDriver::rgb_preferred_
private

Definition at line 205 of file astra_driver.h.

◆ set_ir_exposure_server

ros::ServiceServer astra_wrapper::AstraDriver::set_ir_exposure_server
private

Definition at line 150 of file astra_driver.h.

◆ set_ir_flood_server

ros::ServiceServer astra_wrapper::AstraDriver::set_ir_flood_server
private

Definition at line 151 of file astra_driver.h.

◆ set_ir_gain_server

ros::ServiceServer astra_wrapper::AstraDriver::set_ir_gain_server
private

Definition at line 148 of file astra_driver.h.

◆ set_laser_server

ros::ServiceServer astra_wrapper::AstraDriver::set_laser_server
private

Definition at line 152 of file astra_driver.h.

◆ set_ldp_server

ros::ServiceServer astra_wrapper::AstraDriver::set_ldp_server
private

Definition at line 153 of file astra_driver.h.

◆ switch_ir_camera

ros::ServiceServer astra_wrapper::AstraDriver::switch_ir_camera
private

Definition at line 156 of file astra_driver.h.

◆ use_device_time_

bool astra_wrapper::AstraDriver::use_device_time_
private

Definition at line 216 of file astra_driver.h.

◆ uvc_flip_

int astra_wrapper::AstraDriver::uvc_flip_
private

Definition at line 219 of file astra_driver.h.

◆ video_modes_lookup_

std::map<int, AstraVideoMode> astra_wrapper::AstraDriver::video_modes_lookup_
private

Definition at line 187 of file astra_driver.h.

◆ z_offset_mm_

int astra_wrapper::AstraDriver::z_offset_mm_
private

Definition at line 192 of file astra_driver.h.

◆ z_scaling_

double astra_wrapper::AstraDriver::z_scaling_
private

Definition at line 193 of file astra_driver.h.


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


ros_astra_camera
Author(s): Tim Liu
autogenerated on Wed Mar 2 2022 00:52:57