45 ConnectionBasedNodelet::onInit();
69 async_ = boost::make_shared<message_filters::Synchronizer<ASyncPolicy> >(1000);
75 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(1000);
90 const geometry_msgs::PointStamped::ConstPtr& uv_point,
91 const sensor_msgs::CameraInfo::ConstPtr& camera_info)
95 cv::Mat cv_depth_image = cv_ptr->image;
96 double depth_from_depth_sensor = cv_depth_image.at<
float>((int)uv_point->point.y, (
int)uv_point->point.x);
97 NODELET_INFO(
"timestamp diff is %f", (depth_image->header.stamp - uv_point->header.stamp).toSec());
98 NODELET_INFO(
"(u, v) = (%d, %d)", (
int)uv_point->point.x, (
int)uv_point->point.y);
99 NODELET_INFO(
"(z, d) = (%f, %f)", uv_point->point.z, depth_from_depth_sensor);
100 if (! isnan(depth_from_depth_sensor)) {
101 jsk_recognition_msgs::DepthErrorResult result;
102 result.header.frame_id = depth_image->header.frame_id;
103 result.header.stamp = depth_image->header.stamp;
104 result.u = (int)uv_point->point.x;
105 result.v = (
int)uv_point->point.y;
106 result.center_u = camera_info->P[2];
107 result.center_v = camera_info->P[6];
108 result.true_depth = uv_point->point.z;
109 result.observed_depth = depth_from_depth_sensor;