38 #include <pcl/point_types.h> 41 #include <pcl/registration/registration.h> 42 #include <pcl/registration/transformation_estimation_svd.h> 44 #include <sensor_msgs/Image.h> 45 #include <sensor_msgs/CameraInfo.h> 46 #include <geometry_msgs/PointStamped.h> 51 using namespace Eigen;
56 btm.
setValue(trans(0, 0), trans(0, 1), trans(0, 2),
57 trans(1, 0), trans(1, 1), trans(1, 2),
58 trans(2, 0), trans(2, 1), trans(2, 2));
71 Eigen::Quaternionf quat_out(quat.w(), quat.x(), quat.y(), quat.z());
72 Eigen::Vector3f origin_out(origin.
x(), origin.
y(), origin.
z());
74 out.topLeftCorner<3, 3>() = quat_out.toRotationMatrix();
75 out.topRightCorner<3, 1>() = origin_out;
134 nh_(
"~"), it_(nh_), calibrated(false)
137 nh_.
param<std::string>(
"fixed_frame", fixed_frame,
"/base_link");
138 nh_.
param<std::string>(
"camera_frame", camera_frame,
"/camera_link");
139 nh_.
param<std::string>(
"target_frame", target_frame,
"/calibration_pattern");
140 nh_.
param<std::string>(
"tip_frame", tip_frame,
"/gripper_link");
142 nh_.
param<
int>(
"checkerboard_width", checkerboard_width, 6);
143 nh_.
param<
int>(
"checkerboard_height", checkerboard_height, 7);
144 nh_.
param<
double>(
"checkerboard_grid", checkerboard_grid, 0.027);
147 pattern_detector_.
setPattern(cv::Size(checkerboard_width, checkerboard_height),
150 transform_.translation().setZero();
151 transform_.matrix().topLeftCorner<3, 3>() = Quaternionf().setIdentity().toRotationMatrix();
157 pub_ = it_.
advertise(
"calibration_pattern_out", 1);
158 detector_pub_ = nh_.
advertise<pcl::PointCloud<pcl::PointXYZ> >(
"detector_cloud", 1);
159 physical_pub_ = nh_.
advertise<pcl::PointCloud<pcl::PointXYZ> >(
"physical_points_cloud", 1);
162 ideal_points_.push_back(pcl::PointXYZ(0, 0, 0));
163 ideal_points_.push_back(pcl::PointXYZ((checkerboard_width - 1) * checkerboard_grid, 0, 0));
164 ideal_points_.push_back(pcl::PointXYZ(0, (checkerboard_height - 1) * checkerboard_grid, 0));
165 ideal_points_.push_back(pcl::PointXYZ((checkerboard_width - 1) * checkerboard_grid,
166 (checkerboard_height - 1) * checkerboard_grid, 0));
169 nh_.
param<
double>(
"gripper_tip_x", gripper_tip.point.x, 0.0);
170 nh_.
param<
double>(
"gripper_tip_y", gripper_tip.point.y, 0.0);
171 nh_.
param<
double>(
"gripper_tip_z", gripper_tip.point.z, 0.0);
172 gripper_tip.header.frame_id = tip_frame;
174 ROS_INFO(
"[calibrate] Initialized.");
187 ROS_INFO(
"[calibrate] Got image info!");
192 sensor_msgs::ImagePtr image_msg(
new sensor_msgs::Image);
193 sensor_msgs::PointCloud2 cloud;
209 ROS_ERROR(
"[calibrate] Failed to convert image:\n%s", ex.what());
213 Eigen::Vector3f translation;
214 Eigen::Quaternionf orientation;
216 if (!pattern_detector_.
detectPattern(input_bridge_->image, translation, orientation, output_bridge_->image))
218 ROS_INFO(
"[calibrate] Couldn't detect checkerboard, make sure it's visible in the image.");
226 ros::Time acquisition_time = image_msg->header.stamp;
232 tf::StampedTransform(target_transform, image_msg->header.stamp, image_msg->header.frame_id, target_frame));
236 ROS_WARN(
"[calibrate] TF exception:\n%s", ex.what());
239 publishCloud(ideal_points_, target_transform, image_msg->header.frame_id);
241 overlayPoints(ideal_points_, target_transform, output_bridge_);
244 pub_.
publish(output_bridge_->toImageMsg());
248 cout <<
"Got an image callback!" << endl;
250 calibrate(image_msg->header.frame_id);
256 const std::string frame_id)
259 pcl::PointCloud < pcl::PointXYZ > transformed_detector_points;
263 transformed_detector_points.header.frame_id = frame_id;
264 detector_pub_.
publish(transformed_detector_points);
271 pcl::PointCloud < pcl::PointXYZ > transformed_detector_points;
275 int font_face = cv::FONT_HERSHEY_SCRIPT_SIMPLEX;
276 double font_scale = 1;
280 for (
unsigned int i = 0; i < transformed_detector_points.size(); i++)
282 pcl::PointXYZ pt = transformed_detector_points[i];
283 cv::Point3d pt_cv(pt.x, pt.y, pt.z);
287 cv::circle(image->image, uv, radius, CV_RGB(255, 0, 0), -1);
290 std::stringstream out;
293 text_size = cv::getTextSize(out.str(), font_face, font_scale, thickness, &baseline);
295 cv::Point origin = cvPoint(uv.x - text_size.width / 2, uv.y - radius - baseline);
296 cv::putText(image->image, out.str(), origin, font_face, font_scale, CV_RGB(255, 0, 0), thickness);
302 physical_points_.empty();
303 physical_points_.header.frame_id = fixed_frame;
304 cout <<
"Is the checkerboard correct? " << endl;
305 cout <<
"Move edge of gripper to point 1 in image and press Enter. " << endl;
308 cout <<
"Move edge of gripper to point 2 in image and press Enter. " << endl;
311 cout <<
"Move edge of gripper to point 3 in image and press Enter. " << endl;
314 cout <<
"Move edge of gripper to point 4 in image and press Enter. " << endl;
320 physical_pub_.
publish(physical_points_);
322 pcl::registration::TransformationEstimationSVD < pcl::PointXYZ, pcl::PointXYZ > svd_estimator;
323 svd_estimator.estimateRigidTransformation(physical_points_, image_points_, t);
329 cout <<
"Resulting transform (camera frame -> fixed frame): " << endl << t << endl << endl;
337 ROS_WARN(
"[calibrate] TF exception:\n%s", ex.what());
341 camera_transform_unstamped = camera_transform;
342 trans_full = camera_transform_unstamped.
inverse() * transform;
345 Eigen::Matrix4f t_full_inv = (Eigen::Transform<float, 3, Affine>(t_full).
inverse()).matrix();
347 cout <<
"Resulting transform (fixed frame -> camera frame): " << endl << t_full << endl << endl;
348 printStaticTransform(t_full_inv, fixed_frame, camera_frame);
355 Eigen::Quaternionf quat(transform.topLeftCorner<3, 3>());
356 Eigen::Vector3f translation(transform.topRightCorner<3, 1>());
358 cout <<
"Static transform publisher (use for external kinect): " << endl;
360 cout <<
"rosrun tf static_transform_publisher x y z qx qy qz qw frame_id child_frame_id period_in_ms" << endl;
361 cout <<
"rosrun tf static_transform_publisher " << translation.x() <<
" " << translation.y() <<
" " 362 << translation.z() <<
" " << quat.x() <<
" " << quat.y() <<
" " << quat.z() <<
" " << quat.w()
363 <<
" " << frame1 <<
" " << frame2 <<
" 100" << endl << endl;
367 double yaw, pitch, roll;
369 std::string fixed_frame_urdf(fixed_frame);
373 if (fixed_frame_urdf.size() > 0 && fixed_frame_urdf[0] ==
'/')
374 fixed_frame_urdf.erase(0, 1);
378 cout <<
"URDF output (use for kinect on robot): " << endl;
380 cout <<
"<?xml version=\"1.0\"?>\n<robot>\n" <<
"\t<property name=\"turtlebot_calib_cam_x\" value=\"" 381 << translation.x() <<
"\" />\n" <<
"\t<property name=\"turtlebot_calib_cam_y\" value=\"" << translation.y()
382 <<
"\" />\n" <<
"\t<property name=\"turtlebot_calib_cam_z\" value=\"" << translation.z() <<
"\" />\n" 383 <<
"\t<property name=\"turtlebot_calib_cam_rr\" value=\"" << roll <<
"\" />\n" 384 <<
"\t<property name=\"turtlebot_calib_cam_rp\" value=\"" << pitch <<
"\" />\n" 385 <<
"\t<property name=\"turtlebot_calib_cam_ry\" value=\"" << yaw <<
"\" />\n" 386 <<
"\t<property name=\"turtlebot_kinect_frame_name\" value=\"" << fixed_frame_urdf <<
"\" />\n" <<
"</robot>" 392 geometry_msgs::PointStamped pt_out;
400 ROS_WARN(
"[calibrate] TF exception:\n%s", ex.what());
404 physical_points_.push_back(pcl::PointXYZ(pt_out.point.x, pt_out.point.y, pt_out.point.z));
409 detector_points_.points.resize(pattern_detector_.
ideal_points.size());
410 for (
unsigned int i = 0; i < pattern_detector_.
ideal_points.size(); i++)
413 detector_points_[i].x = pt.x;
414 detector_points_[i].y = pt.y;
415 detector_points_[i].z = pt.z;
421 int main(
int argc,
char** argv)
423 ros::init(argc, argv,
"calibrate_kinect_arm");
const cv::Matx33d & intrinsicMatrix() const
ros::Publisher physical_pub_
void imageCallback(const sensor_msgs::ImageConstPtr &image_msg)
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher detector_pub_
geometry_msgs::PointStamped gripper_tip
ros::Subscriber info_sub_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void getEulerYPR(tfScalar &yaw, tfScalar &pitch, tfScalar &roll, unsigned int solution_number=1) const
pcl::PointCloud< pcl::PointXYZ > ideal_points_
void setCameraMatrices(cv::Matx33d K_, cv::Mat D_)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
void convertIdealPointstoPointcloud()
pcl::PointCloud< pcl::PointXYZ > detector_points_
pcl::PointCloud< pcl::PointXYZ > physical_points_
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
void setValue(const tfScalar &xx, const tfScalar &xy, const tfScalar &xz, const tfScalar &yx, const tfScalar &yy, const tfScalar &yz, const tfScalar &zx, const tfScalar &zy, const tfScalar &zz)
pcl::PointCloud< pcl::PointXYZ > image_points_
ros::Subscriber image_sub_
int main(int argc, char **argv)
image_transport::ImageTransport it_
object_pts_t ideal_points
ROSCPP_DECL void spin(Spinner &spinner)
tf::TransformListener tf_listener_
void infoCallback(const sensor_msgs::CameraInfoConstPtr &info_msg)
Eigen::Transform< float, 3, Eigen::Affine > transform_
image_transport::Publisher pub_
tf::Transform tfFromEigen(Eigen::Matrix4f trans)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void setPattern(cv::Size grid_size_, float square_size_, Pattern pattern_type_, cv::Point3f offset_=cv::Point3f())
TFSIMD_FORCE_INLINE const tfScalar & z() const
void publish(const sensor_msgs::Image &message) const
bool calibrate(const std::string frame_id)
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TFSIMD_FORCE_INLINE Quaternion inverse(const Quaternion &q)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
TFSIMD_FORCE_INLINE const tfScalar & y() const
void pointcloudCallback(const pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
image_geometry::PinholeCameraModel cam_model_
void printStaticTransform(Eigen::Matrix4f &transform, const std::string frame1, const std::string frame2)
PatternDetector pattern_detector_
void overlayPoints(pcl::PointCloud< pcl::PointXYZ > detector_points, tf::Transform &transform, cv_bridge::CvImagePtr &image)
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
void toROSMsg(const sensor_msgs::PointCloud2 &cloud, sensor_msgs::Image &image)
const cv::Mat_< double > & distortionCoeffs() const
ROSCPP_DECL void shutdown()
tf::TransformBroadcaster tf_broadcaster_
cv::Point2d project3dToPixel(const cv::Point3d &xyz) const
cv_bridge::CvImagePtr input_bridge_
cv_bridge::CvImagePtr output_bridge_
Eigen::Matrix4f EigenFromTF(tf::Transform trans)
int detectPattern(cv::Mat &image_in, Eigen::Vector3f &translation, Eigen::Quaternionf &orientation, cv::Mat &image_out)
void publishCloud(pcl::PointCloud< pcl::PointXYZ > detector_points, tf::Transform &transform, const std::string frame_id)
CalibrateKinectCheckerboard()