38 #include <boost/date_time/posix_time/posix_time.hpp>
39 #include <boost/thread/thread.hpp>
49 data_skip_ir_counter_(0),
50 data_skip_color_counter_(0),
51 data_skip_depth_counter_ (0),
52 ir_subscribers_(false),
53 color_subscribers_(false),
54 depth_subscribers_(false),
55 depth_raw_subscribers_(false),
56 enable_reconnect_(false),
57 serialnumber_as_name_(false)
72 ROS_DEBUG(
"Waiting for dynamic reconfigure configuration.");
73 boost::this_thread::sleep(boost::posix_time::milliseconds(100));
75 ROS_DEBUG(
"Dynamic reconfigure configuration received.");
82 <<
"should be plugged into each bus");
146 std::string serial_number;
150 serial_number =
device_->getStringID();
152 std::string color_name, ir_name;
153 color_name =
"rgb_" + serial_number;
154 ir_name =
"depth_" + serial_number;
171 bool stream_reset =
false;
184 ROS_ERROR(
"Undefined IR video mode received from dynamic reconfigure");
190 ROS_ERROR(
"Undefined color video mode received from dynamic reconfigure");
196 ROS_ERROR(
"Undefined depth video mode received from dynamic reconfigure");
226 if (
device_->isIRVideoModeSupported(ir_video_mode))
228 if (ir_video_mode !=
device_->getIRVideoMode())
230 device_->setIRVideoMode(ir_video_mode);
241 if (
device_->isColorVideoModeSupported(color_video_mode))
243 if (color_video_mode !=
device_->getColorVideoMode())
245 device_->setColorVideoMode(color_video_mode);
255 if (
device_->isDepthVideoModeSupported(depth_video_mode))
257 if (depth_video_mode !=
device_->getDepthVideoMode())
259 device_->setDepthVideoMode(depth_video_mode);
279 if (
device_->isImageRegistrationModeSupported())
288 ROS_ERROR(
"Could not set image registration. Reason: %s", exception.
what());
299 ROS_ERROR(
"Could not set color depth synchronization. Reason: %s", exception.
what());
309 ROS_ERROR(
"Could not set auto exposure. Reason: %s", exception.
what());
319 ROS_ERROR(
"Could not set auto white balance. Reason: %s", exception.
what());
328 ROS_INFO_STREAM(
"Forcing exposure set, when auto exposure/white balance disabled");
341 ROS_ERROR(
"Could not set exposure. Reason: %s", exception.
what());
352 int current_exposure_ =
device_->getExposure();
370 ROS_ERROR(
"Could not set exposure. Reason: %s", exception.
what());
378 ROS_WARN_STREAM(
"Callback in " << __FUNCTION__ <<
"failed due to null device");
388 if (
device_->isIRStreamStarted())
390 ROS_ERROR(
"Cannot stream RGB and IR at the same time. Streaming RGB only.");
405 boost::this_thread::sleep(boost::posix_time::milliseconds(100));
417 if (need_ir && !
device_->isIRStreamStarted())
431 ROS_WARN_STREAM(
"Callback in " << __FUNCTION__ <<
"failed due to null device");
442 if (need_depth && !
device_->isDepthStreamStarted())
449 else if (!need_depth &&
device_->isDepthStreamStarted())
460 ROS_WARN_STREAM(
"Callback in " << __FUNCTION__ <<
"failed due to null device");
470 if (
device_->isColorStreamStarted())
472 ROS_ERROR(
"Cannot stream RGB and IR at the same time. Streaming RGB only.");
534 uint16_t* data =
reinterpret_cast<uint16_t*
>(&image->data[0]);
535 for (
unsigned int i = 0; i < image->width * image->height; ++i)
542 uint16_t* data =
reinterpret_cast<uint16_t*
>(&image->data[0]);
543 for (
unsigned int i = 0; i < image->width * image->height; ++i)
545 data[i] =
static_cast<uint16_t
>(data[i] *
z_scaling_);
548 sensor_msgs::CameraInfoPtr cam_info;
583 sensor_msgs::CameraInfoPtr info = boost::make_shared<sensor_msgs::CameraInfo>();
586 info->height = height;
589 info->D.resize(5, 0.0);
594 info->K[0] = info->K[4] =
f;
595 info->K[2] = (width / 2) - 0.5;
598 info->K[5] = (width * (3./8.)) - 0.5;
603 info->R[0] = info->R[4] = info->R[8] = 1.0;
607 info->P[0] = info->P[5] =
f;
608 info->P[2] = info->K[2];
609 info->P[6] = info->K[5];
618 sensor_msgs::CameraInfoPtr info;
623 if ( info->width != width )
626 ROS_WARN_ONCE(
"Image resolution doesn't match calibration of the RGB camera. Using default parameters.");
637 info->header.stamp = time;
646 sensor_msgs::CameraInfoPtr info;
650 info = boost::make_shared<sensor_msgs::CameraInfo>(
ir_info_manager_->getCameraInfo());
651 if ( info->width != width )
654 ROS_WARN_ONCE(
"Image resolution doesn't match calibration of the IR camera. Using default parameters.");
665 info->header.stamp = time;
677 double scaling = (double)width / 640;
679 sensor_msgs::CameraInfoPtr info =
getIRCameraInfo(width, height, time);
696 info->P[3] = -
device_->getBaseline() * info->P[0];
704 ROS_WARN (
"~device_id is not set! Using first device.");
731 device_manager_->getConnectedDeviceURIs();
734 if (device_id.size() > 1 && device_id[0] ==
'#')
736 std::istringstream device_number_str(device_id.substr(1));
738 device_number_str >> device_number;
739 int device_index = device_number - 1;
740 if (device_index >= available_device_URIs->size() || device_index < 0)
743 "Invalid device number %i, there are %zu devices connected.",
744 device_number, available_device_URIs->size());
748 return available_device_URIs->at(device_index);
755 else if (device_id.size() > 1 && device_id.find(
'@') != std::string::npos && device_id.find(
'/') == std::string::npos)
758 size_t index = device_id.find(
'@');
762 "%s is not a valid device URI, you must give the bus number before the @.",
765 if (index >= device_id.size() - 1)
768 "%s is not a valid device URI, you must give the device number after the @, specify 0 for any device on this bus",
773 std::istringstream device_number_str(device_id.substr(index+1));
775 device_number_str >> device_number;
778 std::string bus = device_id.substr(0, index);
781 for (
size_t i = 0; i < available_device_URIs->size(); ++i)
783 std::string
s = (*available_device_URIs)[i];
784 if (
s.find(bus) != std::string::npos)
787 std::ostringstream ss;
788 ss << bus <<
'/' << device_number;
789 if (device_number == 0 ||
s.find(ss.str()) != std::string::npos)
799 for(std::vector<std::string>::const_iterator it = available_device_URIs->begin();
800 it != available_device_URIs->end(); ++it)
803 std::string serial = device_manager_->getSerial(*it);
804 if (serial.size() > 0 && device_id == serial)
809 ROS_WARN(
"Could not query serial number of device \"%s\":", exception.
what());
814 bool match_found =
false;
815 std::string matched_uri;
816 for (
size_t i = 0; i < available_device_URIs->size(); ++i)
818 std::string
s = (*available_device_URIs)[i];
819 if (
s.find(device_id) != std::string::npos)
829 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());
854 ROS_INFO(
"No matching device found.... waiting for devices. Reason: %s", exception.
what());
855 boost::this_thread::sleep(boost::posix_time::seconds(3));
860 ROS_ERROR(
"Could not retrieve device. Reason: %s", exception.
what());
868 ROS_DEBUG(
"Waiting for device initialization..");
869 boost::this_thread::sleep(boost::posix_time::milliseconds(100));
878 unsigned first = uri.find(
'@');
879 unsigned last = uri.find(
'/', first);
880 std::string bus_id = uri.substr (first+1,last-first-1);
881 int rtn = atoi(bus_id.c_str());
893 for (std::size_t i = 0; i != list->size(); ++i)
922 ROS_INFO(
"Waiting for device initialization, before configuring and restarting publishers");
923 boost::this_thread::sleep(boost::posix_time::milliseconds(100));
942 <<
"/white balance are disabled. Temporarily working"
943 <<
" around this issue");
944 ROS_WARN_STREAM(
"Toggling exposure and white balance to auto on re-connect"
945 <<
", otherwise image will be very dark");
946 device_->setAutoExposure(
true);
947 device_->setAutoWhiteBalance(
true);
950 boost::this_thread::sleep(boost::posix_time::milliseconds(2500));
951 ROS_WARN_STREAM(
"Resetting auto exposure and white balance to previous values");
967 <<
", reason: " << exception.
what());
974 ROS_WARN_STREAM(
"Detected loss of connection. Stopping all streams and resetting device");
1094 std::map<int, OpenNI2VideoMode>::const_iterator it;
1100 video_mode = it->second;
1109 static const float bad_point = std::numeric_limits<float>::quiet_NaN ();
1111 sensor_msgs::ImagePtr new_image = boost::make_shared<sensor_msgs::Image>();
1113 new_image->header = raw_image->header;
1114 new_image->width = raw_image->width;
1115 new_image->height = raw_image->height;
1116 new_image->is_bigendian = 0;
1118 new_image->step =
sizeof(float)*raw_image->width;
1120 std::size_t data_size = new_image->width*new_image->height;
1121 new_image->data.resize(data_size*
sizeof(
float));
1123 const unsigned short* in_ptr =
reinterpret_cast<const unsigned short*
>(&raw_image->data[0]);
1124 float* out_ptr =
reinterpret_cast<float*
>(&new_image->data[0]);
1126 for (std::size_t i = 0; i<data_size; ++i, ++in_ptr, ++out_ptr)
1128 if (*in_ptr==0 || *in_ptr==0x7FF)
1130 *out_ptr = bad_point;
1133 *out_ptr =
static_cast<float>(*in_ptr)/1000.0f;