50 std::string topic_name;
51 nh.
param<std::string>(
"topic", topic_name,
"/points");
61 if (points_x_ % 2 == 1 && points_y_ % 2 == 1)
63 ROS_ERROR(
"Checkerboard is symmetric - orientation estimate can be wrong");
100 template <
typename T>
122 template <
typename T>
126 for (
int i = 0; i < 50; ++i)
129 robot_calibration_msgs::CalibrationData tmp_msg(*msg);
149 if (
msg_.height == 1)
151 ROS_ERROR(
"OpenCV does not support unorganized cloud/image.");
156 sensor_msgs::ImagePtr image_msg(
new sensor_msgs::Image);
158 image_msg->encoding =
"bgr8";
159 image_msg->height =
msg_.height;
160 image_msg->width =
msg_.width;
161 image_msg->step = image_msg->width *
sizeof (uint8_t) * 3;
162 image_msg->data.resize(image_msg->step * image_msg->height);
163 for (
size_t y = 0;
y <
msg_.height;
y++)
165 for (
size_t x = 0;
x <
msg_.width;
x++)
167 uint8_t* pixel = &(image_msg->data[
y * image_msg->step +
x * 3]);
175 std::vector<cv::Point2f> points;
181 sensor_msgs::PointCloud2 cloud;
185 cloud.header.frame_id =
msg_.header.frame_id;
192 int idx_cam = msg->observations.size() + 0;
193 int idx_chain = msg->observations.size() + 1;
194 msg->observations.resize(msg->observations.size() + 2);
198 msg->observations[idx_cam].features.resize(
points_x_ * points_y_);
199 msg->observations[idx_chain].features.resize(
points_x_ * points_y_);
202 geometry_msgs::PointStamped rgbd;
203 rgbd.header =
msg_.header;
204 geometry_msgs::PointStamped world;
209 for (
size_t i = 0; i < points.size(); ++i)
215 int index = (int)(points[i].
y) *
msg_.width + (int)(points[i].
x);
216 rgbd.point.x = (xyz + index)[X];
217 rgbd.point.y = (xyz + index)[Y];
218 rgbd.point.z = (xyz + index)[Z];
221 if (std::isnan(rgbd.point.x) ||
222 std::isnan(rgbd.point.y) ||
223 std::isnan(rgbd.point.z))
229 msg->observations[idx_cam].features[i] = rgbd;
231 msg->observations[idx_chain].features[i] = world;
234 iter_cloud[0] = rgbd.point.x;
235 iter_cloud[1] = rgbd.point.y;
236 iter_cloud[2] = rgbd.point.z;
243 msg->observations[idx_cam].cloud =
msg_;
266 std::vector<cv::Point2f> points;
272 int idx_cam = msg->observations.size() + 0;
273 int idx_chain = msg->observations.size() + 1;
274 msg->observations.resize(msg->observations.size() + 2);
279 msg->observations[idx_chain].features.resize(
points_x_ * points_y_);
282 geometry_msgs::PointStamped rgbd;
283 rgbd.header =
msg_->header;
284 geometry_msgs::PointStamped world;
288 for (
size_t i = 0; i < points.size(); ++i)
295 rgbd.point.x = points[i].x;
296 rgbd.point.y = points[i].y;
299 msg->observations[idx_cam].features[i] = rgbd;
301 msg->observations[idx_chain].features[i] = world;
307 msg->observations[idx_cam].image = *
msg_;
317 template <
typename T>
319 std::vector<cv::Point2f>& points)
335 cv::Size checkerboard_size(
points_x_, points_y_);
336 return cv::findChessboardCorners(bridge->image, checkerboard_size,
337 points, cv::CALIB_CB_ADAPTIVE_THRESH);
bool findCheckerboardPoints(const sensor_msgs::ImagePtr &msg, std::vector< cv::Point2f > &points)
bool findInternal(robot_calibration_msgs::CalibrationData *msg)
bool find(robot_calibration_msgs::CalibrationData *msg)
Once the robot has been moved into the proper position and settled, this function will be called...
Base class for a feature finder.
bool output_debug_
Size of a square on checkboard (in meters)
double square_size_
Size of checkerboard.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
Finds checkerboards in images or point clouds.
ros::Publisher publisher_
Incoming message.
DepthCameraInfoManager depth_camera_manager_
std::string frame_id_
Should we output debug image/cloud?
robot_calibration_msgs::ExtendedCameraInfo getDepthCameraInfo()
std::string chain_sensor_name_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
bool init(const std::string &name, ros::NodeHandle &n)
Initialize the feature finder.
bool init(ros::NodeHandle &n)
virtual bool init(const std::string &name, ros::NodeHandle &nh)
Initialize the feature finder.
int points_y_
Size of checkerboard.
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
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.
ros::Subscriber subscriber_
std::string camera_sensor_name_
Name of checkerboard frame.
#define ROS_ERROR_STREAM(args)
void cameraCallback(const T &msg)
ROSCPP_DECL void spinOnce()
void setPointCloud2FieldsByString(int n_fields,...)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool waiting_
Outgoing sensor_msgs::PointCloud2.