34 CheckerboardFinder::CheckerboardFinder() :
46 std::string topic_name;
47 nh.
param<std::string>(
"topic", topic_name,
"/points");
115 for (
int i = 0; i < 50; ++i)
118 robot_calibration_msgs::CalibrationData tmp_msg(*msg);
130 geometry_msgs::PointStamped rgbd;
131 geometry_msgs::PointStamped world;
142 ROS_ERROR(
"OpenCV does not support unorganized cloud/image.");
147 sensor_msgs::ImagePtr image_msg(
new sensor_msgs::Image);
149 image_msg->encoding =
"bgr8";
150 image_msg->height =
cloud_.height;
151 image_msg->width =
cloud_.width;
152 image_msg->step = image_msg->width *
sizeof (uint8_t) * 3;
153 image_msg->data.resize(image_msg->step * image_msg->height);
154 for (
size_t y = 0;
y <
cloud_.height;
y++)
156 for (
size_t x = 0;
x <
cloud_.width;
x++)
158 uint8_t* pixel = &(image_msg->data[
y * image_msg->step +
x * 3]);
179 std::vector<cv::Point2f> points;
181 cv::Size checkerboard_size(
points_x_, points_y_);
182 int found = cv::findChessboardCorners(bridge->image, checkerboard_size,
183 points, cv::CALIB_CB_ADAPTIVE_THRESH);
190 sensor_msgs::PointCloud2 cloud;
194 cloud.header.frame_id =
cloud_.header.frame_id;
201 int idx_cam = msg->observations.size() + 0;
202 int idx_chain = msg->observations.size() + 1;
203 msg->observations.resize(msg->observations.size() + 2);
207 msg->observations[idx_cam].features.resize(
points_x_ * points_y_);
208 msg->observations[idx_chain].features.resize(
points_x_ * points_y_);
212 rgbd.header =
cloud_.header;
217 for (
size_t i = 0; i < points.size(); ++i)
223 int index = (int)(points[i].
y) *
cloud_.width + (int)(points[i].
x);
224 rgbd.point.x = (xyz + index)[X];
225 rgbd.point.y = (xyz + index)[Y];
226 rgbd.point.z = (xyz + index)[Z];
229 if (std::isnan(rgbd.point.x) ||
230 std::isnan(rgbd.point.y) ||
231 std::isnan(rgbd.point.z))
237 msg->observations[idx_cam].features[i] = rgbd;
239 msg->observations[idx_chain].features[i] = world;
242 iter_cloud[0] = rgbd.point.x;
243 iter_cloud[1] = rgbd.point.y;
244 iter_cloud[2] = rgbd.point.z;
251 msg->observations[idx_cam].cloud =
cloud_;
bool find(robot_calibration_msgs::CalibrationData *msg)
Once the robot has been moved into the proper position and settled, this function will be called...
sensor_msgs::PointCloud2 cloud_
void cameraCallback(const sensor_msgs::PointCloud2 &cloud)
void publish(const boost::shared_ptr< M > &message) const
Base class for a feature finder.
ros::Publisher publisher_
Incoming sensor_msgs::PointCloud2.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool findInternal(robot_calibration_msgs::CalibrationData *msg)
This class processes the point cloud input to find a checkerboard.
double square_size_
Size of checkerboard.
TFSIMD_FORCE_INLINE const tfScalar & y() const
std::string camera_sensor_name_
Name of checkerboard frame.
std::string frame_id_
Should we output debug image/cloud?
robot_calibration_msgs::ExtendedCameraInfo getDepthCameraInfo()
bool output_debug_
Size of a square on checkboard (in meters)
std::string chain_sensor_name_
bool init(ros::NodeHandle &n)
virtual bool init(const std::string &name, ros::NodeHandle &nh)
Initialize the feature finder.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std::string getName()
Get the name of this feature finder.
Calibration code lives under this namespace.
bool waiting_
Outgoing sensor_msgs::PointCloud2.
bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
ros::Subscriber subscriber_
int points_y_
Size of checkerboard.
DepthCameraInfoManager depth_camera_manager_
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()
void setPointCloud2FieldsByString(int n_fields,...)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)