astra_driver.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * Copyright (c) 2016, Orbbec Ltd.
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * * Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in the
13  * documentation and/or other materials provided with the distribution.
14  * * Neither the name of the Willow Garage, Inc. nor the names of its
15  * contributors may be used to endorse or promote products derived from
16  * this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
22  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
23  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
24  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
25  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
26  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
27  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  *
30  * Author: Tim Liu (liuhua@orbbec.com)
31  */
32 
33 #ifndef ASTRA_DRIVER_H
34 #define ASTRA_DRIVER_H
35 
36 #include <boost/shared_ptr.hpp>
37 #include <boost/cstdint.hpp>
38 #include <boost/bind.hpp>
39 #include <boost/function.hpp>
40 
41 #include <sensor_msgs/Image.h>
42 
43 #include <dynamic_reconfigure/server.h>
44 #include <astra_camera/AstraConfig.h>
45 
48 
49 #include <string>
50 #include <vector>
51 
55 #include "astra_camera/GetSerial.h"
56 #include "astra_camera/GetDeviceType.h"
57 #include "astra_camera/GetIRGain.h"
58 #include "astra_camera/SetIRGain.h"
59 #include "astra_camera/GetIRExposure.h"
60 #include "astra_camera/SetIRExposure.h"
61 #include "astra_camera/SetLaser.h"
62 #include "astra_camera/SetLDP.h"
63 #include "astra_camera/ResetIRGain.h"
64 #include "astra_camera/ResetIRExposure.h"
65 #include "astra_camera/GetCameraInfo.h"
66 #include "astra_camera/SetIRFlood.h"
67 #include "astra_camera/SwitchIRCamera.h"
69 
70 #include <ros/ros.h>
71 
72 namespace astra_wrapper
73 {
74 
76 {
77 public:
79  ~AstraDriver();
80 
81 private:
82  typedef astra_camera::AstraConfig Config;
83  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
84 
85  void newIRFrameCallback(sensor_msgs::ImagePtr image);
86  void newColorFrameCallback(sensor_msgs::ImagePtr image);
87  void newDepthFrameCallback(sensor_msgs::ImagePtr image);
88 
89  // Methods to get calibration parameters for the various cameras
90  sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const;
91  sensor_msgs::CameraInfoPtr getColorCameraInfo(int width, int height, ros::Time time) const;
92  sensor_msgs::CameraInfoPtr getIRCameraInfo(int width, int height, ros::Time time) const;
93  sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const;
94  sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const;
95  sensor_msgs::CameraInfo convertAstraCameraInfo(OBCameraParams p, ros::Time time) const;
96 
98 
99  // resolves non-URI device IDs to URIs, e.g. '#1' is resolved to the URI of the first device
100  std::string resolveDeviceURI(const std::string& device_id);
101  void initDevice();
102 
103  void advertiseROSTopics();
104 
105  void imageConnectCb();
106  void depthConnectCb();
107 
108  bool getSerialCb(astra_camera::GetSerialRequest& req, astra_camera::GetSerialResponse& res);
109  bool getDeviceTypeCb(astra_camera::GetDeviceTypeRequest& req, astra_camera::GetDeviceTypeResponse& res);
110  bool getIRGainCb(astra_camera::GetIRGainRequest& req, astra_camera::GetIRGainResponse& res);
111  bool setIRGainCb(astra_camera::SetIRGainRequest& req, astra_camera::SetIRGainResponse& res);
112  bool getIRExposureCb(astra_camera::GetIRExposureRequest& req, astra_camera::GetIRExposureResponse& res);
113  bool setIRExposureCb(astra_camera::SetIRExposureRequest& req, astra_camera::SetIRExposureResponse& res);
114  bool setLaserCb(astra_camera::SetLaserRequest& req, astra_camera::SetLaserResponse& res);
115  bool resetIRGainCb(astra_camera::ResetIRGainRequest& req, astra_camera::ResetIRGainResponse& res);
116  bool resetIRExposureCb(astra_camera::ResetIRExposureRequest& req, astra_camera::ResetIRExposureResponse& res);
117  bool getCameraInfoCb(astra_camera::GetCameraInfoRequest& req, astra_camera::GetCameraInfoResponse& res);
118  bool setIRFloodCb(astra_camera::SetIRFloodRequest& req, astra_camera::SetIRFloodResponse& res);
119  bool switchIRCameraCb(astra_camera::SwitchIRCameraRequest& req, astra_camera::SwitchIRCameraResponse& res);
120  bool setLDPCb(astra_camera::SetLDPRequest& req, astra_camera::SetLDPResponse& res);
121 
122  void configCb(Config &config, uint32_t level);
123 
125 
126  void genVideoModeTableMap();
127  int lookupVideoModeFromDynConfig(int mode_nr, AstraVideoMode& video_mode);
128 
129  sensor_msgs::ImageConstPtr rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image);
130 
131  void setIRVideoMode(const AstraVideoMode& ir_video_mode);
132  void setColorVideoMode(const AstraVideoMode& color_video_mode);
133  void setDepthVideoMode(const AstraVideoMode& depth_video_mode);
134 
137 
140 
141  std::string device_id_;
142 
157 
161 
162  std::set<std::string> alreadyOpen;
163  boost::mutex connect_mutex_;
164  // published topics
170 
173 
177 
178  std::string ir_frame_id_;
179  std::string color_frame_id_;
180  std::string depth_frame_id_ ;
181 
183 
186 
187  std::map<int, AstraVideoMode> video_modes_lookup_;
188 
189  // dynamic reconfigure config
193  double z_scaling_;
194 
198 
200 
204 
206 
209 
215 
217 
220 };
221 
222 }
223 
224 #endif
astra_wrapper::AstraDriver::device_manager_
boost::shared_ptr< AstraDeviceManager > device_manager_
Definition: astra_driver.h:138
astra_wrapper::AstraDriver::data_skip_ir_counter_
int data_skip_ir_counter_
Definition: astra_driver.h:201
astra_wrapper::AstraDriver::set_ir_exposure_server
ros::ServiceServer set_ir_exposure_server
Definition: astra_driver.h:150
astra_wrapper::AstraDriver::getDefaultCameraInfo
sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const
Definition: astra_driver.cpp:748
ros::Publisher
astra_wrapper::AstraDriver::set_laser_server
ros::ServiceServer set_laser_server
Definition: astra_driver.h:152
astra_wrapper::AstraDriver::resolveDeviceURI
std::string resolveDeviceURI(const std::string &device_id)
Definition: astra_driver.cpp:967
astra_wrapper::AstraDriver::get_camera_info
ros::ServiceServer get_camera_info
get_serial server
Definition: astra_driver.h:144
astra_wrapper::AstraDriver::getIRGainCb
bool getIRGainCb(astra_camera::GetIRGainRequest &req, astra_camera::GetIRGainResponse &res)
Definition: astra_driver.cpp:257
boost::shared_ptr
astra_wrapper::AstraDriver::pub_color_
image_transport::CameraPublisher pub_color_
Definition: astra_driver.h:165
astra_wrapper::AstraDriver::depth_raw_subscribers_
bool depth_raw_subscribers_
Definition: astra_driver.h:213
astra_wrapper::AstraDriver::~AstraDriver
~AstraDriver()
Definition: astra_driver.cpp:157
astra_wrapper::AstraDriver::reconfigure_server_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
reconfigure server
Definition: astra_driver.h:159
astra_wrapper::AstraDriver::nh_
ros::NodeHandle & nh_
Definition: astra_driver.h:135
astra_wrapper::AstraDriver::connect_mutex_
boost::mutex connect_mutex_
Definition: astra_driver.h:163
ros.h
astra_wrapper::AstraDriver::setIRExposureCb
bool setIRExposureCb(astra_camera::SetIRExposureRequest &req, astra_camera::SetIRExposureResponse &res)
Definition: astra_driver.cpp:275
astra_wrapper::AstraDriver::imageConnectCb
void imageConnectCb()
Definition: astra_driver.cpp:528
astra_wrapper::AstraDriver::pub_depth_
image_transport::CameraPublisher pub_depth_
Definition: astra_driver.h:166
astra_wrapper::AstraDriver
Definition: astra_driver.h:75
astra_wrapper::AstraDriver::config_init_
bool config_init_
Definition: astra_driver.h:160
astra_wrapper::AstraDriver::pub_depth_raw_
image_transport::CameraPublisher pub_depth_raw_
Definition: astra_driver.h:167
astra_wrapper::AstraDriver::reset_ir_gain_server
ros::ServiceServer reset_ir_gain_server
Definition: astra_driver.h:154
astra_wrapper::AstraDriver::old_config_
Config old_config_
Definition: astra_driver.h:218
astra_wrapper::AstraDriver::getDepthCameraInfo
sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const
Definition: astra_driver.cpp:918
camera_info_manager.h
astra_wrapper::AstraDriver::genVideoModeTableMap
void genVideoModeTableMap()
Definition: astra_driver.cpp:1146
astra_wrapper::AstraDriver::color_depth_synchronization_
bool color_depth_synchronization_
Definition: astra_driver.h:184
astra_video_mode.h
astra_wrapper::AstraDriver::color_video_mode_
AstraVideoMode color_video_mode_
Definition: astra_driver.h:175
astra_wrapper::AstraDriver::device_id_
std::string device_id_
Definition: astra_driver.h:141
astra_wrapper::AstraDriver::pnh_
ros::NodeHandle & pnh_
Definition: astra_driver.h:136
astra_wrapper::AstraDriver::z_offset_mm_
int z_offset_mm_
Definition: astra_driver.h:192
astra_wrapper::AstraDriver::rawToFloatingPointConversion
sensor_msgs::ImageConstPtr rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image)
Definition: astra_driver.cpp:1311
astra_wrapper::AstraDriver::ir_time_offset_
ros::Duration ir_time_offset_
Definition: astra_driver.h:195
astra_wrapper::AstraDriver::pub_projector_info_
ros::Publisher pub_projector_info_
Definition: astra_driver.h:169
astra_wrapper::AstraDriver::getDeviceTypeCb
bool getDeviceTypeCb(astra_camera::GetDeviceTypeRequest &req, astra_camera::GetDeviceTypeResponse &res)
Definition: astra_driver.cpp:251
astra_wrapper::AstraDriver::ir_info_url_
std::string ir_info_url_
Definition: astra_driver.h:182
astra_wrapper::AstraDriver::color_frame_id_
std::string color_frame_id_
Definition: astra_driver.h:179
astra_wrapper::AstraDriver::rgb_preferred_
bool rgb_preferred_
Definition: astra_driver.h:205
astra_wrapper::AstraDriver::lookupVideoModeFromDynConfig
int lookupVideoModeFromDynConfig(int mode_nr, AstraVideoMode &video_mode)
Definition: astra_driver.cpp:1294
astra_wrapper::AstraDriver::color_subscribers_
bool color_subscribers_
Definition: astra_driver.h:211
astra_wrapper::AstraVideoMode
Definition: astra_video_mode.h:59
ros::ServiceServer
astra_wrapper::AstraDriver::uvc_flip_
int uvc_flip_
Definition: astra_driver.h:219
astra_wrapper::AstraDriver::get_serial_server
ros::ServiceServer get_serial_server
Definition: astra_driver.h:145
astra_wrapper::AstraDriver::depth_time_offset_
ros::Duration depth_time_offset_
Definition: astra_driver.h:197
astra_wrapper::AstraDriver::depth_subscribers_
bool depth_subscribers_
Definition: astra_driver.h:212
astra_wrapper::AstraDriver::setIRGainCb
bool setIRGainCb(astra_camera::SetIRGainRequest &req, astra_camera::SetIRGainResponse &res)
Definition: astra_driver.cpp:263
astra_wrapper::AstraDriver::initDevice
void initDevice()
Definition: astra_driver.cpp:1106
astra_wrapper::AstraDriver::depth_registration_
bool depth_registration_
Definition: astra_driver.h:185
astra_wrapper::AstraDriver::newColorFrameCallback
void newColorFrameCallback(sensor_msgs::ImagePtr image)
Definition: astra_driver.cpp:632
astra_wrapper::AstraDriver::getCameraInfoCb
bool getCameraInfoCb(astra_camera::GetCameraInfoRequest &req, astra_camera::GetCameraInfoResponse &res)
Definition: astra_driver.cpp:305
astra_wrapper::AstraDriver::use_device_time_
bool use_device_time_
Definition: astra_driver.h:216
astra_wrapper::AstraDriver::color_info_manager_
boost::shared_ptr< camera_info_manager::CameraInfoManager > color_info_manager_
Camera info manager objects.
Definition: astra_driver.h:172
astra_wrapper::AstraDriver::getIRCameraInfo
sensor_msgs::CameraInfoPtr getIRCameraInfo(int width, int height, ros::Time time) const
Definition: astra_driver.cpp:849
astra_wrapper::AstraDriver::ir_info_manager_
boost::shared_ptr< camera_info_manager::CameraInfoManager > ir_info_manager_
Definition: astra_driver.h:172
astra_wrapper::AstraDriver::getIRExposureCb
bool getIRExposureCb(astra_camera::GetIRExposureRequest &req, astra_camera::GetIRExposureResponse &res)
Definition: astra_driver.cpp:269
astra_wrapper::AstraDriver::device_
boost::shared_ptr< AstraDevice > device_
Definition: astra_driver.h:139
astra_device_type.h
astra_wrapper::AstraDriver::auto_white_balance_
bool auto_white_balance_
Definition: astra_driver.h:208
astra_wrapper::AstraDriver::set_ir_gain_server
ros::ServiceServer set_ir_gain_server
Definition: astra_driver.h:148
astra_wrapper::AstraDriver::depth_ir_offset_x_
double depth_ir_offset_x_
Definition: astra_driver.h:190
astra_wrapper::AstraDriver::depth_video_mode_
AstraVideoMode depth_video_mode_
Definition: astra_driver.h:176
astra_wrapper::AstraDriver::getColorCameraInfo
sensor_msgs::CameraInfoPtr getColorCameraInfo(int width, int height, ros::Time time) const
Definition: astra_driver.cpp:783
image_transport::CameraPublisher
astra_wrapper::AstraDriver::newDepthFrameCallback
void newDepthFrameCallback(sensor_msgs::ImagePtr image)
Definition: astra_driver.cpp:648
astra_wrapper::AstraDriver::ReconfigureServer
dynamic_reconfigure::Server< Config > ReconfigureServer
Definition: astra_driver.h:83
astra_wrapper::AstraDriver::ir_frame_id_
std::string ir_frame_id_
Definition: astra_driver.h:178
astra_wrapper::AstraDriver::newIRFrameCallback
void newIRFrameCallback(sensor_msgs::ImagePtr image)
Definition: astra_driver.cpp:616
astra_wrapper::AstraDriver::color_time_offset_
ros::Duration color_time_offset_
Definition: astra_driver.h:196
astra_wrapper::AstraDriver::data_skip_color_counter_
int data_skip_color_counter_
Definition: astra_driver.h:202
astra_wrapper::AstraDriver::color_info_url_
std::string color_info_url_
Definition: astra_driver.h:182
astra_wrapper::AstraDriver::advertiseROSTopics
void advertiseROSTopics()
Definition: astra_driver.cpp:161
astra_wrapper::AstraDriver::depth_frame_id_
std::string depth_frame_id_
Definition: astra_driver.h:180
astra_wrapper::AstraDriver::setColorVideoMode
void setColorVideoMode(const AstraVideoMode &color_video_mode)
Definition: astra_driver.cpp:438
astra_wrapper::AstraDriver::set_ir_flood_server
ros::ServiceServer set_ir_flood_server
Definition: astra_driver.h:151
image_transport.h
astra_wrapper::AstraDriver::configCb
void configCb(Config &config, uint32_t level)
Definition: astra_driver.cpp:328
astra_device_manager.h
astra_wrapper::AstraDriver::ir_subscribers_
bool ir_subscribers_
Definition: astra_driver.h:210
astra_wrapper::AstraDriver::setIRVideoMode
void setIRVideoMode(const AstraVideoMode &ir_video_mode)
Definition: astra_driver.cpp:423
astra_wrapper
Definition: astra_convert.h:44
astra_wrapper::AstraDriver::data_skip_
int data_skip_
Definition: astra_driver.h:199
astra_device.h
astra_wrapper::AstraDriver::switch_ir_camera
ros::ServiceServer switch_ir_camera
Definition: astra_driver.h:156
astra_wrapper::AstraDriver::depth_ir_offset_y_
double depth_ir_offset_y_
Definition: astra_driver.h:191
ros::Time
astra_wrapper::AstraDriver::Config
astra_camera::AstraConfig Config
Definition: astra_driver.h:82
astra_wrapper::AstraDriver::applyConfigToOpenNIDevice
void applyConfigToOpenNIDevice()
Definition: astra_driver.cpp:467
astra_wrapper::AstraDriver::get_ir_gain_server
ros::ServiceServer get_ir_gain_server
Definition: astra_driver.h:147
astra_wrapper::AstraDriver::get_device_type_server
ros::ServiceServer get_device_type_server
Definition: astra_driver.h:146
astra_wrapper::AstraDriver::setLDPCb
bool setLDPCb(astra_camera::SetLDPRequest &req, astra_camera::SetLDPResponse &res)
Definition: astra_driver.cpp:287
astra_wrapper::AstraDriver::get_ir_exposure_server
ros::ServiceServer get_ir_exposure_server
Definition: astra_driver.h:149
astra_wrapper::AstraDriver::setIRFloodCb
bool setIRFloodCb(astra_camera::SetIRFloodRequest &req, astra_camera::SetIRFloodResponse &res)
Definition: astra_driver.cpp:311
astra_wrapper::AstraDriver::alreadyOpen
std::set< std::string > alreadyOpen
Definition: astra_driver.h:162
astra_wrapper::AstraDriver::resetIRGainCb
bool resetIRGainCb(astra_camera::ResetIRGainRequest &req, astra_camera::ResetIRGainResponse &res)
Definition: astra_driver.cpp:293
astra_wrapper::AstraDriver::video_modes_lookup_
std::map< int, AstraVideoMode > video_modes_lookup_
Definition: astra_driver.h:187
astra_wrapper::AstraDriver::getSerialCb
bool getSerialCb(astra_camera::GetSerialRequest &req, astra_camera::GetSerialResponse &res)
Definition: astra_driver.cpp:245
astra_wrapper::AstraDriver::auto_exposure_
bool auto_exposure_
Definition: astra_driver.h:207
astra_wrapper::AstraDriver::pub_ir_
image_transport::CameraPublisher pub_ir_
Definition: astra_driver.h:168
astra_wrapper::AstraDriver::data_skip_depth_counter_
int data_skip_depth_counter_
Definition: astra_driver.h:203
astra_wrapper::AstraDriver::set_ldp_server
ros::ServiceServer set_ldp_server
Definition: astra_driver.h:153
astra_wrapper::AstraDriver::z_scaling_
double z_scaling_
Definition: astra_driver.h:193
astra_wrapper::AstraDriver::AstraDriver
AstraDriver(ros::NodeHandle &n, ros::NodeHandle &pnh)
Definition: astra_driver.cpp:51
astra_wrapper::AstraDriver::getProjectorCameraInfo
sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const
Definition: astra_driver.cpp:934
uint32_t
unsigned int uint32_t
Definition: OniPlatformWin32.h:67
astra_wrapper::AstraDriver::depthConnectCb
void depthConnectCb()
Definition: astra_driver.cpp:592
astra_wrapper::AstraDriver::setLaserCb
bool setLaserCb(astra_camera::SetLaserRequest &req, astra_camera::SetLaserResponse &res)
Definition: astra_driver.cpp:281
astra_wrapper::AstraDriver::switchIRCameraCb
bool switchIRCameraCb(astra_camera::SwitchIRCameraRequest &req, astra_camera::SwitchIRCameraResponse &res)
Definition: astra_driver.cpp:317
astra_wrapper::AstraDriver::convertAstraCameraInfo
sensor_msgs::CameraInfo convertAstraCameraInfo(OBCameraParams p, ros::Time time) const
Definition: astra_driver.cpp:706
ros::Duration
astra_wrapper::AstraDriver::resetIRExposureCb
bool resetIRExposureCb(astra_camera::ResetIRExposureRequest &req, astra_camera::ResetIRExposureResponse &res)
Definition: astra_driver.cpp:299
astra_wrapper::AstraDriver::reset_ir_exposure_server
ros::ServiceServer reset_ir_exposure_server
Definition: astra_driver.h:155
astra_wrapper::AstraDriver::setDepthVideoMode
void setDepthVideoMode(const AstraVideoMode &depth_video_mode)
Definition: astra_driver.cpp:452
astra_wrapper::AstraDriver::projector_info_subscribers_
bool projector_info_subscribers_
Definition: astra_driver.h:214
astra_wrapper::AstraDriver::readConfigFromParameterServer
void readConfigFromParameterServer()
Definition: astra_driver.cpp:945
ros::NodeHandle
OBCameraParams
Definition: OniCTypes.h:85
astra_wrapper::AstraDriver::ir_video_mode_
AstraVideoMode ir_video_mode_
Definition: astra_driver.h:174


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