40 const geometry_msgs::Point p1,
41 const geometry_msgs::Point p2)
43 return std::sqrt((p1.x-p2.x) * (p1.x-p2.x) +
44 (p1.y-p2.y) * (p1.y-p2.y) +
45 (p1.z-p2.z) * (p1.z-p2.z));
60 std::string topic_name;
61 nh.
param<std::string>(
"action", topic_name,
"/gripper_led_action");
63 ROS_INFO(
"Waiting for %s...", topic_name.c_str());
67 nh.
param<std::string>(
"topic", topic_name,
"/points");
93 std::string gripper_led_frame;
94 nh.
param<std::string>(
"gripper_led_frame", gripper_led_frame,
"wrist_roll_link");
99 for (
int i = 0; i < led_poses.size(); ++i)
101 codes_.push_back(
static_cast<int>(led_poses[i][
"code"]));
105 x =
static_cast<double>(led_poses[i][
"x"]);
106 y =
static_cast<double>(led_poses[i][
"y"]);
107 z =
static_cast<double>(led_poses[i][
"z"]);
112 *pub = nh.
advertise<sensor_msgs::Image>(
static_cast<std::string
>(led_poses[i][
"topic"]), 10);
159 uint8_t code_idx = -1;
161 std::vector<geometry_msgs::PointStamped> rgbd;
162 std::vector<geometry_msgs::PointStamped> world;
164 sensor_msgs::PointCloud2 prev_cloud;
166 robot_calibration_msgs::GripperLedCommandGoal
command;
179 for (
size_t i = 0; i <
trackers_.size(); ++i)
188 code_idx = (code_idx + 1) %
codes_.size();
200 int tracker = code_idx/2;
202 double weight = (code_idx%2 == 0) ? 1: -1;
211 if (done && (weight == -1))
217 geometry_msgs::PointStamped led;
219 led.header.frame_id =
trackers_[tracker].frame_;
223 led.header.frame_id, led);
236 ROS_ERROR(
"Failed to find features before using maximum iterations.");
243 for (
size_t i = 0; i <
trackers_.size(); i++)
245 sensor_msgs::Image image =
trackers_[i].getImage();
251 sensor_msgs::PointCloud2 cloud;
255 cloud.header.frame_id =
cloud_.header.frame_id;
262 const int CAMERA = 0;
264 robot_calibration_msgs::Observation observations[2];
270 geometry_msgs::PointStamped rgbd_pt;
271 geometry_msgs::PointStamped world_pt;
284 rgbd_pt.header.frame_id, world_pt);
299 for (
size_t t2 = 0; t2 <
t; ++t2)
305 ROS_ERROR_STREAM(
"Features not internally consistent: " << expected <<
" " << actual);
311 observations[CAMERA].features.push_back(rgbd_pt);
315 iter_cloud[0] = rgbd_pt.point.x;
316 iter_cloud[1] = rgbd_pt.point.y;
317 iter_cloud[2] = rgbd_pt.point.z;
321 world_pt.header.frame_id =
trackers_[
t].frame_;
323 observations[CHAIN].features.push_back(world_pt);
327 if (observations[CAMERA].features.size() !=
trackers_.size())
335 observations[CAMERA].cloud =
cloud_;
339 msg->observations.push_back(observations[CAMERA]);
340 msg->observations.push_back(observations[CHAIN]);
349 std::string frame,
double x,
double y,
double z) :
371 diff_.resize(height * width);
372 for (std::vector<double>::iterator it = diff_.begin(); it != diff_.end(); ++it)
380 sensor_msgs::PointCloud2& cloud,
381 sensor_msgs::PointCloud2& prev,
382 geometry_msgs::Point& led_point,
386 if ((cloud.width * cloud.height) != diff_.size())
399 double last_distance = 1000.0;
402 const size_t num_points = cloud.data.size() / cloud.point_step;
405 for (
size_t i = 0; i < num_points; i++)
408 geometry_msgs::Point p;
430 double r = (double)((rgb + i)[
R]) - (
double)((prev_rgb + i)[
R]);
431 double g = (double)((rgb + i)[
G]) - (
double)((prev_rgb + i)[
G]);
432 double b = (double)((rgb + i)[
B]) - (
double)((prev_rgb + i)[
B]);
433 if (
r > 0 && g > 0 && b > 0 && weight > 0)
435 diff_[i] += (
r + g + b) * weight;
438 else if (
r < 0 && g < 0 && b < 0 && weight < 0)
440 diff_[i] += (
r + g + b) * weight;
456 const sensor_msgs::PointCloud2& cloud,
460 if (max_ < threshold)
470 if (std::isnan(
point[
X]) ||
481 const sensor_msgs::PointCloud2& cloud,
482 geometry_msgs::PointStamped& centroid)
486 const size_t num_points = cloud.data.size() / cloud.point_step;
489 centroid.header = cloud.header;
490 centroid.point.x = (iter + max_idx_)[
X];
491 centroid.point.y = (iter + max_idx_)[
Y];
492 centroid.point.z = (iter + max_idx_)[
Z];
495 if (std::isnan(centroid.point.x) ||
496 std::isnan(centroid.point.y) ||
497 std::isnan(centroid.point.z))
507 for (
size_t i = 0; i < num_points; i++)
512 if (diff_[i] > (max_*0.75))
519 double dx =
point[
X] - centroid.point.x;
520 double dy =
point[
Y] - centroid.point.y;
521 double dz =
point[
Z] - centroid.point.z;
524 if ((dx*dx) + (dy*dy) + (dz*dz) < (0.05*0.05))
536 centroid.point.x = (centroid.point.x + sum_x)/(points+1);
537 centroid.point.y = (centroid.point.y + sum_y)/(points+1);
538 centroid.point.z = (centroid.point.z + sum_z)/(points+1);
546 sensor_msgs::Image image;
548 image.height = height_;
549 image.width = width_;
552 image.step = width_ * 3;
554 image.data.resize(width_ * height_ * 3);
556 for (
size_t i = 0; i < diff_.size(); i++)
558 if (diff_[i] > max_ * 0.9)
560 image.data[i*3] = 255;
561 image.data[i*3 + 1] = 0;
562 image.data[i*3 + 2] = 0;
564 else if (diff_[i] > 0)
566 image.data[i*3] =
static_cast<uint8_t
>(diff_[i]/2.0);
567 image.data[i*3 + 1] =
static_cast<uint8_t
>(diff_[i]/2.0);
568 image.data[i*3 + 2] =
static_cast<uint8_t
>(diff_[i]/2.0);
573 image.data[i*3 + 1] = 0;
574 image.data[i*3 + 2] = 0;