44 #include <boost/date_time/posix_time/posix_time.hpp>
45 #include <boost/thread/thread.hpp>
56 data_skip_ir_counter_(0),
57 data_skip_color_counter_(0),
58 data_skip_depth_counter_ (0),
59 ir_subscribers_(false),
60 color_subscribers_(false),
61 depth_subscribers_(false),
62 depth_raw_subscribers_(false),
71 int bootOrder, devnums;
72 if (!pnh.
getParam(
"bootorder", bootOrder))
77 if (!pnh.
getParam(
"devnums", devnums))
90 if( (shmid = shmget((key_t)0401, 1, 0666|IPC_CREAT)) == -1 )
92 ROS_ERROR(
"Create Share Memory Error:%s", strerror(errno));
94 shm = (
char *)shmat(shmid, 0, 0);
97 ROS_INFO(
"*********** device_id %s already open device************************ ",
device_id_.c_str());
102 if( (shmid = shmget((key_t)0401, 1, 0666|IPC_CREAT)) == -1 )
104 ROS_ERROR(
"Create Share Memory Error:%s", strerror(errno));
106 shm = (
char *)shmat(shmid, 0, 0);
107 while( *shm!=bootOrder)
109 boost::this_thread::sleep(boost::posix_time::milliseconds(10));
113 ROS_INFO(
"*********** device_id %s already open device************************ ",
device_id_.c_str());
114 *shm = (bootOrder+1);
116 if( bootOrder==devnums )
122 if(shmctl(shmid, IPC_RMID, 0) == -1)
149 ROS_DEBUG(
"Waiting for dynamic reconfigure configuration.");
150 boost::this_thread::sleep(boost::posix_time::milliseconds(100));
152 ROS_DEBUG(
"Dynamic reconfigure configuration received.");
217 std::string serial_number =
device_->getStringID();
218 std::string color_name, ir_name;
220 color_name =
"rgb_" + serial_number;
221 ir_name =
"depth_" + serial_number;
253 res.device_type = std::string(
device_->getDeviceType());
259 res.gain =
device_->getIRGain();
271 res.exposure =
device_->getIRExposure();
277 device_->setIRExposure(req.exposure);
313 device_->setIRFlood(req.enable);
319 if (req.camera ==
"left")
321 else if (req.camera ==
"right")
332 if (config.depth_mode != 13 && config.depth_mode != 14)
334 config.depth_mode = 13;
336 if (config.ir_mode != 13 && config.ir_mode != 14 && config.ir_mode != 16)
344 if (config.depth_mode != 13 && config.depth_mode != 17)
346 config.depth_mode = 13;
348 if (config.ir_mode != 13 && config.ir_mode != 17)
356 if (config.depth_mode != 13 && config.depth_mode != 14)
358 config.depth_mode = 13;
360 if (config.ir_mode != 13 && config.ir_mode != 14)
366 bool stream_reset =
false;
384 ROS_ERROR(
"Undefined IR video mode received from dynamic reconfigure");
390 ROS_ERROR(
"Undefined color video mode received from dynamic reconfigure");
396 ROS_ERROR(
"Undefined depth video mode received from dynamic reconfigure");
425 if (
device_->isIRVideoModeSupported(ir_video_mode))
427 if (ir_video_mode !=
device_->getIRVideoMode())
429 device_->setIRVideoMode(ir_video_mode);
440 if (
device_->isColorVideoModeSupported(color_video_mode))
442 if (color_video_mode !=
device_->getColorVideoMode())
444 device_->setColorVideoMode(color_video_mode);
454 if (
device_->isDepthVideoModeSupported(depth_video_mode))
456 if (depth_video_mode !=
device_->getDepthVideoMode())
458 device_->setDepthVideoMode(depth_video_mode);
481 if (
device_->isImageRegistrationModeSupported())
490 ROS_ERROR(
"Could not set image registration. Reason: %s", exception.
what());
501 ROS_ERROR(
"Could not set color depth synchronization. Reason: %s", exception.
what());
511 ROS_ERROR(
"Could not set auto exposure. Reason: %s", exception.
what());
521 ROS_ERROR(
"Could not set auto white balance. Reason: %s", exception.
what());
532 bool ir_started =
device_->isIRStreamStarted();
533 bool color_started =
device_->isColorStreamStarted();
541 ROS_ERROR(
"Cannot stream RGB and IR at the same time. Streaming RGB only.");
561 ROS_ERROR(
"Cannot stream RGB and IR at the same time. Streaming IR only.");
602 if (need_depth && !
device_->isDepthStreamStarted())
609 else if (!need_depth &&
device_->isDepthStreamStarted())
662 for (
unsigned int i = 0; i < image->width * image->height; ++i)
670 for (
unsigned int i = 0; i < image->width * image->height; ++i)
675 sensor_msgs::CameraInfoPtr cam_info;
708 sensor_msgs::CameraInfo info;
712 info.D.resize(5, 0.0);
713 info.D[0] = p.
r_k[0];
714 info.D[1] = p.
r_k[1];
715 info.D[2] = p.
r_k[3];
716 info.D[3] = p.
r_k[4];
717 info.D[4] = p.
r_k[2];
727 for (
int i = 0; i < 9; i++)
729 info.R[i] = p.
r2l_r[i];
733 info.P[0] = info.K[0];
734 info.P[2] = info.K[2];
735 info.P[3] = p.
r2l_t[0];
736 info.P[5] = info.K[4];
737 info.P[6] = info.K[5];
738 info.P[7] = p.
r2l_t[1];
740 info.P[11] = p.
r2l_t[2];
742 info.header.stamp = time;
750 sensor_msgs::CameraInfoPtr info = boost::make_shared<sensor_msgs::CameraInfo>();
753 info->height = height;
756 info->D.resize(5, 0.0);
761 info->K[0] = info->K[4] =
f;
762 info->K[2] = (width / 2) - 0.5;
765 info->K[5] = (width * (3./8.)) - 0.5;
770 info->R[0] = info->R[4] = info->R[8] = 1.0;
774 info->P[0] = info->P[5] =
f;
775 info->P[2] = info->K[2];
776 info->P[6] = info->K[5];
785 sensor_msgs::CameraInfoPtr info;
790 if ( info->width != width )
793 ROS_WARN_ONCE(
"Image resolution doesn't match calibration of the RGB camera. Using default parameters.");
800 if (
device_->isCameraParamsValid())
803 info = boost::make_shared<sensor_msgs::CameraInfo>(
ir_info_manager_->getCameraInfo());
804 info->D.resize(5, 0.0);
810 info->height = height;
812 for (
int i = 0; i < 9; i++)
814 info->K[i] = cinfo.K[i];
815 info->R[i] = cinfo.R[i];
818 for (
int i = 0; i < 12; i++)
820 info->P[i] = cinfo.P[i];
823 double scaling = (double)width / 640;
824 info->K[0] *= scaling;
825 info->K[2] *= scaling;
826 info->K[4] *= scaling;
827 info->K[5] *= scaling;
828 info->P[0] *= scaling;
829 info->P[2] *= scaling;
830 info->P[5] *= scaling;
831 info->P[6] *= scaling;
842 info->header.stamp = time;
851 sensor_msgs::CameraInfoPtr info;
855 info = boost::make_shared<sensor_msgs::CameraInfo>(
ir_info_manager_->getCameraInfo());
856 if ( info->width != width )
859 ROS_WARN_ONCE(
"Image resolution doesn't match calibration of the IR camera. Using default parameters.");
868 if (
device_->isCameraParamsValid())
871 info->D.resize(5, 0.0);
891 info->P[0] = info->K[0];
892 info->P[2] = info->K[2];
893 info->P[5] = info->K[4];
894 info->P[6] = info->K[5];
897 double scaling = (double)width / 640;
898 info->K[0] *= scaling;
899 info->K[2] *= scaling;
900 info->K[4] *= scaling;
901 info->K[5] *= scaling;
902 info->P[0] *= scaling;
903 info->P[2] *= scaling;
904 info->P[5] *= scaling;
905 info->P[6] *= scaling;
912 info->header.stamp = time;
923 double scaling = (double)width / 640;
924 sensor_msgs::CameraInfoPtr info =
getIRCameraInfo(width, height, time);
941 info->P[3] = -
device_->getBaseline() * info->P[0];
949 ROS_WARN (
"~device_id is not set! Using first device.");
976 for (
size_t i = 0; i < available_device_URIs->size(); ++i)
978 std::string
s = (*available_device_URIs)[i];
979 ROS_WARN(
"------------id %d, available_device_uri is %s-----------", i,
s.c_str());
984 if (device_id.size() > 1 && device_id[0] ==
'#')
986 std::istringstream device_number_str(device_id.substr(1));
988 device_number_str >> device_number;
989 int device_index = device_number - 1;
990 if (device_index >= available_device_URIs->size() || device_index < 0)
993 "Invalid device number %i, there are %zu devices connected.",
994 device_number, available_device_URIs->size());
998 return available_device_URIs->at(device_index);
1005 else if (device_id.size() > 1 && device_id.find(
'@') != std::string::npos && device_id.find(
'/') == std::string::npos)
1008 size_t index = device_id.find(
'@');
1012 "%s is not a valid device URI, you must give the bus number before the @.",
1015 if (index >= device_id.size() - 1)
1018 "%s is not a valid device URI, you must give a number after the @, specify 0 for first device",
1023 std::istringstream device_number_str(device_id.substr(index+1));
1025 device_number_str >> device_number;
1028 std::string bus = device_id.substr(0, index);
1031 for (
size_t i = 0; i < available_device_URIs->size(); ++i)
1033 std::string
s = (*available_device_URIs)[i];
1034 if (
s.find(bus) != std::string::npos)
1038 if (device_number <= 0)
1048 for(std::vector<std::string>::const_iterator it = available_device_URIs->begin();
1049 it != available_device_URIs->end(); ++it)
1055 if (serial.size() > 0 && device_id == serial)
1061 std::set<std::string>::iterator iter;
1066 if (serial.size() > 0 && device_id == serial)
1076 ROS_WARN(
"Could not query serial number of device \"%s\":", exception.
what());
1081 bool match_found =
false;
1082 std::string matched_uri;
1083 for (
size_t i = 0; i < available_device_URIs->size(); ++i)
1085 std::string
s = (*available_device_URIs)[i];
1086 if (
s.find(device_id) != std::string::npos)
1096 THROW_OPENNI_EXCEPTION(
"Two devices match the given device id '%s': %s and %s.", device_id.c_str(), matched_uri.c_str(),
s.c_str());
1114 if( device_URI ==
"" )
1116 boost::this_thread::sleep(boost::posix_time::milliseconds(500));
1126 ROS_INFO(
"No matching device found.... waiting for devices. Reason: %s", exception.
what());
1127 boost::this_thread::sleep(boost::posix_time::seconds(3));
1132 ROS_ERROR(
"Could not retrieve device. Reason: %s", exception.
what());
1140 ROS_DEBUG(
"Waiting for device initialization..");
1141 boost::this_thread::sleep(boost::posix_time::milliseconds(100));
1298 std::map<int, AstraVideoMode>::const_iterator it;
1304 video_mode = it->second;
1313 static const float bad_point = std::numeric_limits<float>::quiet_NaN ();
1315 sensor_msgs::ImagePtr new_image = boost::make_shared<sensor_msgs::Image>();
1317 new_image->header = raw_image->header;
1318 new_image->width = raw_image->width;
1319 new_image->height = raw_image->height;
1320 new_image->is_bigendian = 0;
1322 new_image->step =
sizeof(float)*raw_image->width;
1324 std::size_t data_size = new_image->width*new_image->height;
1325 new_image->data.resize(data_size*
sizeof(
float));
1327 const unsigned short* in_ptr =
reinterpret_cast<const unsigned short*
>(&raw_image->data[0]);
1328 float* out_ptr =
reinterpret_cast<float*
>(&new_image->data[0]);
1330 for (std::size_t i = 0; i<data_size; ++i, ++in_ptr, ++out_ptr)
1332 if (*in_ptr==0 || *in_ptr==0x7FF)
1334 *out_ptr = bad_point;
1337 *out_ptr =
static_cast<float>(*in_ptr)/1000.0f;