33 #ifndef ASTRA_DEVICE_H 34 #define ASTRA_DEVICE_H 43 #include <boost/shared_ptr.hpp> 44 #include <boost/cstdint.hpp> 45 #include <boost/bind.hpp> 46 #include <boost/function.hpp> 48 #include <sensor_msgs/Image.h> 74 const std::string getUri()
const;
75 const std::string getVendor()
const;
76 const std::string
getName()
const;
80 const std::string getStringID()
const;
84 bool hasIRSensor()
const;
85 bool hasColorSensor()
const;
86 bool hasDepthSensor()
const;
89 void startColorStream();
90 void startDepthStream();
92 void stopAllStreams();
95 void stopColorStream();
96 void stopDepthStream();
98 bool isIRStreamStarted();
99 bool isColorStreamStarted();
100 bool isDepthStreamStarted();
102 bool isImageRegistrationModeSupported()
const;
103 void setImageRegistrationMode(
bool enabled);
104 void setDepthColorSync(
bool enabled);
110 const std::vector<AstraVideoMode>& getSupportedIRVideoModes()
const;
111 const std::vector<AstraVideoMode>& getSupportedColorVideoModes()
const;
112 const std::vector<AstraVideoMode>& getSupportedDepthVideoModes()
const;
114 bool isIRVideoModeSupported(
const AstraVideoMode& video_mode)
const;
115 bool isColorVideoModeSupported(
const AstraVideoMode& video_mode)
const;
116 bool isDepthVideoModeSupported(
const AstraVideoMode& video_mode)
const;
122 void setIRFrameCallback(FrameCallbackFunction
callback);
123 void setColorFrameCallback(FrameCallbackFunction callback);
124 void setDepthFrameCallback(FrameCallbackFunction callback);
126 float getIRFocalLength (
int output_y_resolution)
const;
127 float getColorFocalLength (
int output_y_resolution)
const;
128 float getDepthFocalLength (
int output_y_resolution)
const;
129 float getBaseline ()
const;
131 bool isCameraParamsValid();
132 char* getSerialNumber();
133 char* getDeviceType();
135 int getIRGain()
const;
136 int getIRExposure()
const;
139 void setIRGain(
int gain);
140 void setIRExposure(
int exposure);
141 void setLaser(
bool enable);
142 void setIRFlood(
bool enable);
143 void setLDP(
bool enable);
145 void switchIRCamera(
int cam);
147 void setAutoExposure(
bool enable);
148 void setAutoWhiteBalance(
bool enable);
150 bool getAutoExposure()
const;
151 bool getAutoWhiteBalance()
const;
153 void setUseDeviceTimer(
bool enable);
187 char serial_number[12];
188 char device_type[32];
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
boost::shared_ptr< AstraFrameListener > ir_frame_listener
boost::shared_ptr< AstraFrameListener > depth_frame_listener
boost::shared_ptr< openni::VideoStream > depth_video_stream_
boost::shared_ptr< AstraFrameListener > color_frame_listener
std::string getName(void *handle)
std::vector< AstraVideoMode > ir_video_modes_
OBCameraParams m_CamParams
std::vector< AstraVideoMode > color_video_modes_
void callback(const sensor_msgs::ImageConstPtr &msg)
boost::shared_ptr< openni::VideoStream > color_video_stream_
boost::function< void(sensor_msgs::ImagePtr image)> FrameCallbackFunction
boost::shared_ptr< openni::VideoStream > ir_video_stream_
std::ostream & operator<<(std::ostream &stream, const AstraDevice &device)
std::vector< AstraVideoMode > depth_video_modes_
boost::shared_ptr< openni::Device > openni_device_
OB_DEVICE_NO device_type_no
boost::shared_ptr< openni::DeviceInfo > device_info_
bool depth_video_started_
bool color_video_started_
bool image_registration_activated_