33 #ifndef ASTRA_DRIVER_H 34 #define ASTRA_DRIVER_H 36 #include <boost/shared_ptr.hpp> 37 #include <boost/cstdint.hpp> 38 #include <boost/bind.hpp> 39 #include <boost/function.hpp> 41 #include <sensor_msgs/Image.h> 43 #include <dynamic_reconfigure/server.h> 44 #include <astra_camera/AstraConfig.h> 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" 82 typedef astra_camera::AstraConfig
Config;
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);
ros::ServiceServer set_ir_exposure_server
void setDepthVideoMode(const AstraVideoMode &depth_video_mode)
void readConfigFromParameterServer()
sensor_msgs::CameraInfoPtr getColorCameraInfo(int width, int height, ros::Time time) const
std::string resolveDeviceURI(const std::string &device_id)
ros::ServiceServer get_camera_info
get_serial server
bool getIRGainCb(astra_camera::GetIRGainRequest &req, astra_camera::GetIRGainResponse &res)
sensor_msgs::CameraInfoPtr getProjectorCameraInfo(int width, int height, ros::Time time) const
int data_skip_ir_counter_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
reconfigure server
bool setIRExposureCb(astra_camera::SetIRExposureRequest &req, astra_camera::SetIRExposureResponse &res)
image_transport::CameraPublisher pub_depth_raw_
image_transport::CameraPublisher pub_depth_
ros::ServiceServer set_laser_server
void genVideoModeTableMap()
bool color_depth_synchronization_
image_transport::CameraPublisher pub_color_
bool depth_raw_subscribers_
boost::mutex connect_mutex_
ros::ServiceServer reset_ir_gain_server
sensor_msgs::ImageConstPtr rawToFloatingPointConversion(sensor_msgs::ImageConstPtr raw_image)
ros::Duration ir_time_offset_
AstraVideoMode color_video_mode_
sensor_msgs::CameraInfoPtr getIRCameraInfo(int width, int height, ros::Time time) const
ros::ServiceServer get_serial_server
ros::Duration depth_time_offset_
sensor_msgs::CameraInfoPtr getDefaultCameraInfo(int width, int height, double f) const
ros::Publisher pub_projector_info_
bool getDeviceTypeCb(astra_camera::GetDeviceTypeRequest &req, astra_camera::GetDeviceTypeResponse &res)
bool getCameraInfoCb(astra_camera::GetCameraInfoRequest &req, astra_camera::GetCameraInfoResponse &res)
std::string color_frame_id_
int lookupVideoModeFromDynConfig(int mode_nr, AstraVideoMode &video_mode)
boost::shared_ptr< camera_info_manager::CameraInfoManager > color_info_manager_
Camera info manager objects.
boost::shared_ptr< AstraDevice > device_
bool getIRExposureCb(astra_camera::GetIRExposureRequest &req, astra_camera::GetIRExposureResponse &res)
bool setIRGainCb(astra_camera::SetIRGainRequest &req, astra_camera::SetIRGainResponse &res)
void newColorFrameCallback(sensor_msgs::ImagePtr image)
double depth_ir_offset_x_
AstraVideoMode depth_video_mode_
sensor_msgs::CameraInfo convertAstraCameraInfo(OBCameraParams p, ros::Time time) const
boost::shared_ptr< camera_info_manager::CameraInfoManager > ir_info_manager_
void newIRFrameCallback(sensor_msgs::ImagePtr image)
ros::Duration color_time_offset_
ros::ServiceServer set_ir_gain_server
std::string color_info_url_
void advertiseROSTopics()
void configCb(Config &config, uint32_t level)
void newDepthFrameCallback(sensor_msgs::ImagePtr image)
dynamic_reconfigure::Server< Config > ReconfigureServer
int data_skip_color_counter_
void setColorVideoMode(const AstraVideoMode &color_video_mode)
ros::ServiceServer set_ir_flood_server
ros::ServiceServer get_device_type_server
std::string depth_frame_id_
void setIRVideoMode(const AstraVideoMode &ir_video_mode)
ros::ServiceServer get_ir_exposure_server
std::set< std::string > alreadyOpen
std::map< int, AstraVideoMode > video_modes_lookup_
double depth_ir_offset_y_
int data_skip_depth_counter_
ros::ServiceServer switch_ir_camera
astra_camera::AstraConfig Config
void applyConfigToOpenNIDevice()
ros::ServiceServer set_ldp_server
ros::ServiceServer get_ir_gain_server
bool setLDPCb(astra_camera::SetLDPRequest &req, astra_camera::SetLDPResponse &res)
AstraDriver(ros::NodeHandle &n, ros::NodeHandle &pnh)
bool setIRFloodCb(astra_camera::SetIRFloodRequest &req, astra_camera::SetIRFloodResponse &res)
bool resetIRGainCb(astra_camera::ResetIRGainRequest &req, astra_camera::ResetIRGainResponse &res)
bool getSerialCb(astra_camera::GetSerialRequest &req, astra_camera::GetSerialResponse &res)
image_transport::CameraPublisher pub_ir_
sensor_msgs::CameraInfoPtr getDepthCameraInfo(int width, int height, ros::Time time) const
bool setLaserCb(astra_camera::SetLaserRequest &req, astra_camera::SetLaserResponse &res)
bool resetIRExposureCb(astra_camera::ResetIRExposureRequest &req, astra_camera::ResetIRExposureResponse &res)
ros::ServiceServer reset_ir_exposure_server
bool projector_info_subscribers_
AstraVideoMode ir_video_mode_
boost::shared_ptr< AstraDeviceManager > device_manager_
bool switchIRCameraCb(astra_camera::SwitchIRCameraRequest &req, astra_camera::SwitchIRCameraResponse &res)