00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include "ellipses_nodelet.h"
00031 #include <iomanip>
00032 #include <opencv/cv.h>
00033 #include <opencv/highgui.h>
00034 #include <sensor_msgs/image_encodings.h>
00035 #include "boost/date_time/posix_time/posix_time.hpp"
00036 #include <image_geometry/pinhole_camera_model.h>
00037 #include <tuw_ellipses/TransformArrayStamped.h>
00038
00039 #include <pluginlib/class_list_macros.h>
00040 PLUGINLIB_DECLARE_CLASS(tuw, EllipsesDetectionNode, tuw::EllipsesDetectionNode, nodelet::Nodelet)
00041 using namespace tuw;
00042
00043 EllipsesDetectionNode::~EllipsesDetectionNode() {
00044 }
00045
00046 EllipsesDetectionNode::EllipsesDetectionNode() :
00047 EllipsesDetection(new EllipsesDetectionNode::ParametersNode()), n_(), callback_counter_(0), imageTransport_(n_) {
00048
00049 }
00050
00051 const EllipsesDetectionNode::ParametersNode *EllipsesDetectionNode::param() {
00052 return (EllipsesDetectionNode::ParametersNode*) param_;
00053 }
00054
00055 void EllipsesDetectionNode::init() {
00056 sub_camera_ = imageTransport_.subscribeCamera( "image", 1, &EllipsesDetectionNode::imageCallback, this );
00057 pub_viz_marker_ = n_.advertise<visualization_msgs::Marker>("visualization_marker", 1000);
00058 pub_perceptions_ = n_.advertise<tuw_ellipses::TransformArrayStamped>("perceptions", 1000);
00059 }
00060
00061 void EllipsesDetectionNode::imageCallback(const sensor_msgs::ImageConstPtr& image_msg, const sensor_msgs::CameraInfoConstPtr& camer_info) {
00062
00063 if(callback_counter_ == 0) timeCallbackReceived_ = boost::posix_time::microsec_clock::local_time();
00064 callback_counter_++;
00065 if((param()->image_skip >= 0) && (callback_counter_ % (param()->image_skip+1) != 0)) return;
00066 timeCallbackReceivedLast_ = timeCallbackReceived_;
00067 timeCallbackReceived_ = boost::posix_time::microsec_clock::local_time();
00068
00069 image_geometry::PinholeCameraModel cam_model;
00070 cam_model.fromCameraInfo ( camer_info );
00071 try {
00072 if((image_mono_ == NULL) || !param()->debug_freeze) {
00073 image_mono_ = cv_bridge::toCvCopy(image_msg, sensor_msgs::image_encodings::MONO8);
00074 camera_info_ = camer_info;
00075 }
00076 } catch (cv_bridge::Exception& e) {
00077 ROS_ERROR("cv_bridge exception: %s", e.what());
00078 return;
00079 }
00080
00081
00082 timeDetectionStart_ = boost::posix_time::microsec_clock::local_time();
00083 next();
00084 std::vector<cv::RotatedRect> ellipses;
00085 cv::Mat intrinsic(cam_model.intrinsicMatrix());
00086 cv::Mat projection(cam_model.projectionMatrix());
00087 fit_ellipses_opencv (image_mono_->image, intrinsic, cam_model.distortionCoeffs(), projection, image_msg->header.stamp.toBoost() );
00088 createRings();
00089 createTransforms(image_msg->header);
00090 timeDetectionEnd_ = boost::posix_time::microsec_clock::local_time();
00091 publishTf();
00092 publishPerceptions(image_msg->header);
00093 publishMarker(image_msg->header);
00094
00095 if (param()->show_camera_image) {
00096 cv::Mat img_debug;
00097 std::stringstream ss;
00098 ss << "capture: " << std::setw(3) << (timeDetectionStart_ - timeCallbackReceived_).total_milliseconds() << "ms, ";
00099 ss << "detection: " << std::setw(3) << (timeDetectionEnd_ - timeDetectionStart_).total_milliseconds() << "ms, ";
00100 ss << "total: " << std::setw(3) << (timeDetectionEnd_ - timeCallbackReceived_).total_milliseconds() << "ms, ";
00101 ss << "interval: " << std::setw(3) << (timeCallbackReceived_ - timeCallbackReceivedLast_).total_milliseconds() << "ms";
00102 if((timeCallbackReceived_ - timeCallbackReceivedLast_).total_milliseconds() > 0) {
00103 ss << " = " << std::setw(3) << 1000 /(timeCallbackReceived_ - timeCallbackReceivedLast_).total_milliseconds() << "Hz";
00104 }
00105 cvtColor(image_mono_->image, img_debug, CV_GRAY2BGR);
00106 draw_ellipses(img_debug);
00107 cv::putText(img_debug, ss.str(), cv::Point(10, 15), cv::FONT_HERSHEY_PLAIN, 0.6, cv::Scalar::all(0), 1, CV_AA);
00108 cv::imshow( param()->node_name + std::string(" - input"), img_debug);
00109 if(param()->debug) {
00110 cv::imshow( param()->node_name + std::string(" - edges"), imgEdges_);
00111 if(!imgGradient_.empty()) {
00112 cv::imshow( param()->node_name + std::string(" - gradient"), imgGradient_ * (0xFFFF/0x1FF));
00113 }
00114 if(!imgDirection_.empty()) {
00115 cv::imshow( param()->node_name + std::string(" - direction"), imgDirection_ * 0xFFFF/0x1FF);
00116 }
00117 if(!imgSobelDx_.empty()) {
00118 cv::imshow( param()->node_name + std::string(" - imgSobelDx_"), imgSobelDx_ * (0xFFFF/0x1FF));
00119 }
00120 if(!imgSobelDy_.empty()) {
00121 cv::imshow( param()->node_name + std::string(" - imgSobelDy_"), imgSobelDy_ * (0xFFFF/0x1FF));
00122 }
00123 }
00124 cv::waitKey(param()->show_camera_image_waitkey);
00125 }
00126 }
00127
00128 void EllipsesDetectionNode::onInit()
00129 {
00130 init();
00131 }
00132
00133 void EllipsesDetectionNode::createTransforms(const std_msgs::Header &header) {
00134 if(param()->pose_estimation == POSE_ESTIMATION_OFF) return;
00135 estimatePoses();
00136 tf::Transform trans;
00137 tf::StampedTransform st;
00138 char frame[0xFF];
00139 markerTransforms_.clear();
00140 for(unsigned int i = 0; i < 2; i++) {
00141 if(param()->skip_second_tf && (i == 1)) continue;
00142 for(std::list<Marker>::iterator it = markers_.begin(); it != markers_.end(); it++) {
00143 Marker &m = *it;
00144 sprintf(frame, "t%i-%i", i, m.id);
00145 std::string child_frame = tf::resolve(param()->tf_prefix, frame);
00146 tf::Quaternion roation;
00147 tf::Vector3 translation;
00148 tf::Matrix3x3 R;
00149 translation.setValue(m.translations[i].x, m.translations[i].y, m.translations[i].z);
00150 R.setValue (m.R[i](0,0), m.R[i](0,1), m.R[i](0,2), m.R[i](1,0), m.R[i](1,1), m.R[i](1,2), m.R[i](2,0), m.R[i](2,1), m.R[i](2,2));
00151 R.getRotation(roation);
00152 trans = tf::Transform(roation, translation);
00153 st = tf::StampedTransform(trans, header.stamp, header.frame_id, child_frame);
00154 markerTransforms_.push_back(st);
00155 }
00156 }
00157 }
00158
00159
00160 void EllipsesDetectionNode::publishTf() {
00161 for(std::list<tf::StampedTransform>::iterator it = markerTransforms_.begin(); it != markerTransforms_.end(); it++) {
00162 transformBroadcaster_.sendTransform(*it);
00163 }
00164
00165 }
00166
00167 void EllipsesDetectionNode::publishMarker (const std_msgs::Header &header) {
00168 msg_line_list_.header = header;
00169 msg_line_list_.ns = "nomrals";
00170 msg_line_list_.action = visualization_msgs::Marker::ADD;
00171 msg_line_list_.pose.orientation.w = 1.0;
00172 msg_line_list_.id = 0;
00173 msg_line_list_.type = visualization_msgs::Marker::LINE_LIST;
00174 msg_line_list_.scale.x = 0.01;
00175 msg_line_list_.color.r = 1.0;
00176 msg_line_list_.color.g = 0.0;
00177 msg_line_list_.color.b = 0.0;
00178 msg_line_list_.color.a = 1.0;
00179 geometry_msgs::Point p0, p1;
00180 for(unsigned int i = 0; i < 2; i++) {
00181 msg_line_list_.points.clear();
00182 msg_line_list_.ns = "nomrals-" + boost::lexical_cast<std::string>(i);
00183 msg_line_list_.color.r = 0.5 + 0.5*i;
00184 for(std::list<Marker>::iterator it = markers_.begin(); it != markers_.end(); it++) {
00185 Marker &m = *it;
00186 p0.x = m.translations[i].x, p0.y = m.translations[i].y, p0.z = m.translations[i].z;
00187 p1.x = p0.x + m.normals[i][0]/2., p1.y = p0.y + m.normals[i][1]/2., p1.z = p0.z + m.normals[i][2]/2.;
00188 msg_line_list_.points.push_back(p0);
00189 msg_line_list_.points.push_back(p1);
00190 }
00191 pub_viz_marker_.publish(msg_line_list_);
00192 }
00193 }
00194
00195 void EllipsesDetectionNode::publishPerceptions (const std_msgs::Header &header) {
00196 if(pub_perceptions_.getNumSubscribers() < 1) return;
00197 tuw_ellipses::TransformArrayStamped msg;
00198 if(markerTransforms_.size() > 0) {
00199 msg.header = header;
00200 msg.child_frame_id.resize(markerTransforms_.size());
00201 msg.transform.resize(markerTransforms_.size());
00202 std::list<tf::StampedTransform>::iterator it = markerTransforms_.begin();
00203 for(unsigned int i; i < markerTransforms_.size(); it++, i++) {
00204 geometry_msgs::Vector3 &desT = msg.transform[i].translation;
00205 geometry_msgs::Quaternion &desQ = msg.transform[i].rotation;
00206 tf::Vector3 &srcT = it->getOrigin();
00207 tf::Quaternion srcQ = it->getRotation();
00208 desT.x = srcT.x(), desT.y = srcT.y(), desT.z = srcT.z();
00209 desQ.x = srcQ.x(), desQ.y = srcQ.y(), desQ.z = srcQ.z(), desQ.w = srcQ.w();
00210 msg.child_frame_id[i] = it->child_frame_id_;
00211 }
00212 pub_perceptions_.publish(msg);
00213 }
00214
00215 }