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
00036 #include <iostream>
00037 #include <aruco/aruco.h>
00038 #include <aruco/cvdrawingutils.h>
00039
00040 #include <opencv2/core/core.hpp>
00041 #include <ros/ros.h>
00042 #include <image_transport/image_transport.h>
00043 #include <cv_bridge/cv_bridge.h>
00044 #include <sensor_msgs/image_encodings.h>
00045 #include <aruco_ros/aruco_ros_utils.h>
00046 #include <aruco_msgs/MarkerArray.h>
00047 #include <tf/transform_listener.h>
00048 #include <std_msgs/UInt32MultiArray.h>
00049
00050 class ArucoMarkerPublisher
00051 {
00052 private:
00053
00054 aruco::MarkerDetector mDetector_;
00055 aruco::CameraParameters camParam_;
00056 vector<aruco::Marker> markers_;
00057
00058
00059 bool useRectifiedImages_;
00060 std::string marker_frame_;
00061 std::string camera_frame_;
00062 std::string reference_frame_;
00063 double marker_size_;
00064
00065
00066 ros::NodeHandle nh_;
00067 image_transport::ImageTransport it_;
00068 image_transport::Subscriber image_sub_;
00069
00070 image_transport::Publisher image_pub_;
00071 image_transport::Publisher debug_pub_;
00072 ros::Publisher marker_pub_;
00073 ros::Publisher marker_list_pub_;
00074 tf::TransformListener tfListener_;
00075
00076 ros::Subscriber cam_info_sub_;
00077 aruco_msgs::MarkerArray::Ptr marker_msg_;
00078 cv::Mat inImage_;
00079 bool useCamInfo_;
00080 std_msgs::UInt32MultiArray marker_list_msg_;
00081
00082 public:
00083 ArucoMarkerPublisher()
00084 : nh_("~")
00085 , it_(nh_)
00086 , useCamInfo_(true)
00087 {
00088 image_sub_ = it_.subscribe("/image", 1, &ArucoMarkerPublisher::image_callback, this);
00089
00090 nh_.param<bool>("use_camera_info", useCamInfo_, true);
00091 if(useCamInfo_)
00092 {
00093 sensor_msgs::CameraInfoConstPtr msg = ros::topic::waitForMessage<sensor_msgs::CameraInfo>("/camera_info", nh_);
00094 camParam_ = aruco_ros::rosCameraInfo2ArucoCamParams(*msg, useRectifiedImages_);
00095 nh_.param<double>("marker_size", marker_size_, 0.05);
00096 nh_.param<bool>("image_is_rectified", useRectifiedImages_, true);
00097 nh_.param<std::string>("reference_frame", reference_frame_, "");
00098 nh_.param<std::string>("camera_frame", camera_frame_, "");
00099 ROS_ASSERT(not camera_frame_.empty());
00100 if(reference_frame_.empty())
00101 reference_frame_ = camera_frame_;
00102 }
00103 else
00104 {
00105 camParam_ = aruco::CameraParameters();
00106 }
00107
00108 image_pub_ = it_.advertise("result", 1);
00109 debug_pub_ = it_.advertise("debug", 1);
00110 marker_pub_ = nh_.advertise<aruco_msgs::MarkerArray>("markers", 100);
00111 marker_list_pub_ = nh_.advertise<std_msgs::UInt32MultiArray>("markers_list", 10);
00112
00113 marker_msg_ = aruco_msgs::MarkerArray::Ptr(new aruco_msgs::MarkerArray());
00114 marker_msg_->header.frame_id = reference_frame_;
00115 marker_msg_->header.seq = 0;
00116 }
00117
00118 bool getTransform(const std::string& refFrame,
00119 const std::string& childFrame,
00120 tf::StampedTransform& transform)
00121 {
00122 std::string errMsg;
00123
00124 if(!tfListener_.waitForTransform(refFrame,
00125 childFrame,
00126 ros::Time(0),
00127 ros::Duration(0.5),
00128 ros::Duration(0.01),
00129 &errMsg))
00130 {
00131 ROS_ERROR_STREAM("Unable to get pose from TF: " << errMsg);
00132 return false;
00133 }
00134 else
00135 {
00136 try
00137 {
00138 tfListener_.lookupTransform(refFrame, childFrame,
00139 ros::Time(0),
00140 transform);
00141 }
00142 catch ( const tf::TransformException& e)
00143 {
00144 ROS_ERROR_STREAM("Error in lookupTransform of " << childFrame << " in " << refFrame);
00145 return false;
00146 }
00147
00148 }
00149 return true;
00150 }
00151
00152 void image_callback(const sensor_msgs::ImageConstPtr& msg)
00153 {
00154 bool publishMarkers = marker_pub_.getNumSubscribers() > 0;
00155 bool publishMarkersList = marker_list_pub_.getNumSubscribers() > 0;
00156 bool publishImage = image_pub_.getNumSubscribers() > 0;
00157 bool publishDebug = debug_pub_.getNumSubscribers() > 0;
00158
00159 if(!publishMarkers && !publishMarkersList && !publishImage && !publishDebug)
00160 return;
00161
00162 ros::Time curr_stamp(ros::Time::now());
00163 cv_bridge::CvImagePtr cv_ptr;
00164 try
00165 {
00166 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::RGB8);
00167 inImage_ = cv_ptr->image;
00168
00169
00170 markers_.clear();
00171
00172
00173 mDetector_.detect(inImage_, markers_, camParam_, marker_size_, false);
00174
00175
00176 if(publishMarkers)
00177 {
00178 marker_msg_->markers.clear();
00179 marker_msg_->markers.resize(markers_.size());
00180 marker_msg_->header.stamp = curr_stamp;
00181 marker_msg_->header.seq++;
00182
00183 for(size_t i=0; i<markers_.size(); ++i)
00184 {
00185 aruco_msgs::Marker & marker_i = marker_msg_->markers.at(i);
00186 marker_i.header.stamp = curr_stamp;
00187 marker_i.id = markers_.at(i).id;
00188 marker_i.confidence = 1.0;
00189 }
00190
00191
00192 if(useCamInfo_)
00193 {
00194
00195 tf::StampedTransform cameraToReference;
00196 cameraToReference.setIdentity();
00197
00198 if ( reference_frame_ != camera_frame_ )
00199 {
00200 getTransform(reference_frame_,
00201 camera_frame_,
00202 cameraToReference);
00203 }
00204
00205
00206 for(size_t i=0; i<markers_.size(); ++i)
00207 {
00208 aruco_msgs::Marker & marker_i = marker_msg_->markers.at(i);
00209 tf::Transform transform = aruco_ros::arucoMarker2Tf(markers_[i]);
00210 transform = static_cast<tf::Transform>(cameraToReference) * transform;
00211 tf::poseTFToMsg(transform, marker_i.pose.pose);
00212 marker_i.header.frame_id = reference_frame_;
00213 }
00214 }
00215
00216
00217 if (marker_msg_->markers.size() > 0)
00218 marker_pub_.publish(marker_msg_);
00219 }
00220
00221 if(publishMarkersList)
00222 {
00223 marker_list_msg_.data.resize(markers_.size());
00224 for(size_t i=0; i<markers_.size(); ++i)
00225 marker_list_msg_.data[i] = markers_[i].id;
00226
00227 marker_list_pub_.publish(marker_list_msg_);
00228 }
00229
00230
00231 for(size_t i=0; i<markers_.size(); ++i)
00232 {
00233 markers_[i].draw(inImage_,cv::Scalar(0,0,255),2);
00234 }
00235
00236
00237 if(camParam_.isValid() && marker_size_!=-1)
00238 {
00239 for(size_t i=0; i<markers_.size(); ++i)
00240 aruco::CvDrawingUtils::draw3dAxis(inImage_, markers_[i], camParam_);
00241 }
00242
00243
00244 if(publishImage)
00245 {
00246
00247 cv_bridge::CvImage out_msg;
00248 out_msg.header.stamp = curr_stamp;
00249 out_msg.encoding = sensor_msgs::image_encodings::RGB8;
00250 out_msg.image = inImage_;
00251 image_pub_.publish(out_msg.toImageMsg());
00252 }
00253
00254
00255 if(publishDebug)
00256 {
00257
00258 cv_bridge::CvImage debug_msg;
00259 debug_msg.header.stamp = curr_stamp;
00260 debug_msg.encoding = sensor_msgs::image_encodings::MONO8;
00261 debug_msg.image = mDetector_.getThresholdedImage();
00262 debug_pub_.publish(debug_msg.toImageMsg());
00263 }
00264
00265 }
00266 catch (cv_bridge::Exception& e)
00267 {
00268 ROS_ERROR("cv_bridge exception: %s", e.what());
00269 }
00270 }
00271 };
00272
00273
00274 int main(int argc,char **argv)
00275 {
00276 ros::init(argc, argv, "aruco_marker_publisher");
00277
00278 ArucoMarkerPublisher node;
00279
00280 ros::spin();
00281 }