35 #include <boost/lexical_cast.hpp> 36 #include <boost/algorithm/string/replace.hpp> 46 #include <boost/shared_ptr.hpp> 47 #include <boost/make_shared.hpp> 57 ir_video_started_(false),
58 color_video_started_(false),
59 depth_video_started_(false),
60 image_registration_activated_(false),
61 use_device_time_(false)
69 if (device_URI.length() > 0)
165 boost::replace_all(ID_str,
"/",
"");
166 boost::replace_all(ID_str,
".",
"");
167 boost::replace_all(ID_str,
"@",
"");
239 int laser_enable = 1;
274 depth_stream->stop();
277 depth_stream->start();
292 float focal_length = 0.0f;
297 focal_length = (float)output_y_resolution / (2 *
tan(stream->getVerticalFieldOfView() / 2));
305 float focal_length = 0.0f;
310 focal_length = (float)output_y_resolution / (2 *
tan(stream->getVerticalFieldOfView() / 2));
318 float focal_length = 0.0f;
323 focal_length = (float)output_y_resolution / (2 *
tan(stream->getVerticalFieldOfView() / 2));
338 bool supported =
false;
340 std::vector<AstraVideoMode>::const_iterator it =
ir_video_modes_.begin();
341 std::vector<AstraVideoMode>::const_iterator it_end =
ir_video_modes_.end();
343 while (it != it_end && !supported)
345 supported = (*it == video_mode);
356 bool supported =
false;
361 while (it != it_end && !supported)
363 supported = (*it == video_mode);
374 bool supported =
false;
379 while (it != it_end && !supported)
381 supported = (*it == video_mode);
410 stream->setMirroringEnabled(
false);
424 stream->setMirroringEnabled(
false);
436 stream->setMirroringEnabled(
false);
825 stream <<
"Device info (" << device.
getUri() <<
")" << std::endl;
826 stream <<
" Vendor: " << device.
getVendor() << std::endl;
827 stream <<
" Name: " << device.
getName() << std::endl;
828 stream <<
" USB Vendor ID: " << device.
getUsbVendorId() << std::endl;
829 stream <<
" USB Product ID: " << device.
getUsbVendorId() << std::endl << std::endl;
833 stream <<
"IR sensor video modes:" << std::endl;
836 std::vector<AstraVideoMode>::const_iterator it = video_modes.begin();
837 std::vector<AstraVideoMode>::const_iterator it_end = video_modes.end();
838 for (; it != it_end; ++it)
839 stream <<
" - " << *it << std::endl;
843 stream <<
"No IR sensor available" << std::endl;
848 stream <<
"Color sensor video modes:" << std::endl;
851 std::vector<AstraVideoMode>::const_iterator it = video_modes.begin();
852 std::vector<AstraVideoMode>::const_iterator it_end = video_modes.end();
853 for (; it != it_end; ++it)
854 stream <<
" - " << *it << std::endl;
858 stream <<
"No Color sensor available" << std::endl;
863 stream <<
"Depth sensor video modes:" << std::endl;
866 std::vector<AstraVideoMode>::const_iterator it = video_modes.begin();
867 std::vector<AstraVideoMode>::const_iterator it_end = video_modes.end();
868 for (; it != it_end; ++it)
869 stream <<
" - " << *it << std::endl;
873 stream <<
"No Depth sensor available" << std::endl;
void setDepthFrameCallback(FrameCallbackFunction callback)
void setDepthVideoMode(const AstraVideoMode &video_mode)
void setLaser(bool enable)
bool getAutoExposureEnabled() const
struct OBCameraParams OBCameraParams
boost::shared_ptr< AstraFrameListener > ir_frame_listener
Status setAutoWhiteBalanceEnabled(bool enabled)
boost::shared_ptr< AstraFrameListener > depth_frame_listener
void setUseDeviceTimer(bool enable)
boost::shared_ptr< openni::VideoStream > depth_video_stream_
void setCameraParams(OBCameraParams param)
void setIRFrameCallback(FrameCallbackFunction callback)
bool isImageRegistrationModeSupported() const
boost::shared_ptr< AstraFrameListener > color_frame_listener
void setAutoExposure(bool enable)
bool isDepthVideoModeSupported(const AstraVideoMode &video_mode) const
void switchIRCamera(int cam)
bool isDepthStreamStarted()
float getColorFocalLength(int output_y_resolution) const
bool getAutoWhiteBalanceEnabled() const
const std::string getName() const
boost::shared_ptr< openni::VideoStream > getColorVideoStream() const
std::vector< AstraVideoMode > ir_video_modes_
#define THROW_OPENNI_EXCEPTION(format,...)
OBCameraParams m_CamParams
const AstraVideoMode getIRVideoMode()
void setColorVideoMode(const AstraVideoMode &video_mode)
std::vector< AstraVideoMode > color_video_modes_
bool isCameraParamsValid()
const std::vector< AstraVideoMode > & getSupportedColorVideoModes() const
bool hasDepthSensor() const
void setColorFrameCallback(FrameCallbackFunction callback)
const AstraVideoMode getColorVideoMode()
static Status initialize()
boost::shared_ptr< openni::VideoStream > color_video_stream_
bool isIRVideoModeSupported(const AstraVideoMode &video_mode) const
AstraDevice(const std::string &device_URI)
const std::vector< AstraVideoMode > & getSupportedIRVideoModes() const
bool getAutoExposure() const
float getIRFocalLength(int output_y_resolution) const
const AstraVideoMode getDepthVideoMode()
static const char * getExtendedError()
void setImageRegistrationMode(bool enabled)
boost::shared_ptr< openni::VideoStream > getIRVideoStream() const
Status setAutoExposureEnabled(bool enabled)
const std::string getUri() const
void setIRFlood(bool enable)
boost::function< void(sensor_msgs::ImagePtr image)> FrameCallbackFunction
boost::shared_ptr< openni::VideoStream > ir_video_stream_
bool isColorVideoModeSupported(const AstraVideoMode &video_mode) const
std::ostream & operator<<(std::ostream &stream, const AstraDevice &device)
uint16_t getUsbVendorId() const
bool getAutoWhiteBalance() const
OBCameraParams getCameraParams() const
boost::shared_ptr< openni::VideoStream > getDepthVideoStream() const
uint16_t getUsbProductId() const
std::vector< AstraVideoMode > depth_video_modes_
bool hasColorSensor() const
float getBaseline() const
const std::vector< AstraVideoMode > & getSupportedDepthVideoModes() const
const std::string getVendor() const
void setIRExposure(int exposure)
int getIRExposure() const
const std::string getStringID() const
float getDepthFocalLength(int output_y_resolution) const
boost::shared_ptr< openni::Device > openni_device_
OB_DEVICE_NO device_type_no
bool isColorStreamStarted()
boost::shared_ptr< openni::DeviceInfo > device_info_
bool depth_video_started_
const Array< VideoMode > & getSupportedVideoModes() const
const AstraDeviceInfo astra_convert(const openni::DeviceInfo *pInfo)
bool color_video_started_
OB_DEVICE_NO getDeviceTypeNo()
bool image_registration_activated_
void setDepthColorSync(bool enabled)
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
void setAutoWhiteBalance(bool enable)
void setIRVideoMode(const AstraVideoMode &video_mode)
static const _NullString ANY_DEVICE