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 <tf/transform_broadcaster.h>
00047 #include <tf/transform_listener.h>
00048
00049 using namespace aruco;
00050
00051 class ArucoSimple
00052 {
00053 private:
00054 cv::Mat inImage;
00055 aruco::CameraParameters camParam;
00056 tf::StampedTransform rightToLeft;
00057 bool useRectifiedImages;
00058 MarkerDetector mDetector;
00059 vector<Marker> markers;
00060 ros::Subscriber cam_info_sub;
00061 bool cam_info_received;
00062 image_transport::Publisher image_pub;
00063 image_transport::Publisher debug_pub;
00064 ros::Publisher pose_pub;
00065 ros::Publisher transform_pub;
00066 ros::Publisher position_pub;
00067 std::string marker_frame;
00068 std::string camera_frame;
00069 std::string reference_frame;
00070
00071 double marker_size;
00072 int marker_id;
00073
00074 ros::NodeHandle nh;
00075 image_transport::ImageTransport it;
00076 image_transport::Subscriber image_sub;
00077
00078 tf::TransformListener _tfListener;
00079
00080 public:
00081 ArucoSimple()
00082 : cam_info_received(false),
00083 nh("~"),
00084 it(nh)
00085 {
00086 image_sub = it.subscribe("/image", 1, &ArucoSimple::image_callback, this);
00087 cam_info_sub = nh.subscribe("/camera_info", 1, &ArucoSimple::cam_info_callback, this);
00088
00089 image_pub = it.advertise("result", 1);
00090 debug_pub = it.advertise("debug", 1);
00091 pose_pub = nh.advertise<geometry_msgs::PoseStamped>("pose", 100);
00092 transform_pub = nh.advertise<geometry_msgs::TransformStamped>("transform", 100);
00093 position_pub = nh.advertise<geometry_msgs::Vector3Stamped>("position", 100);
00094
00095 nh.param<double>("marker_size", marker_size, 0.05);
00096 nh.param<int>("marker_id", marker_id, 300);
00097 nh.param<std::string>("reference_frame", reference_frame, "");
00098 nh.param<std::string>("camera_frame", camera_frame, "");
00099 nh.param<std::string>("marker_frame", marker_frame, "");
00100 nh.param<bool>("image_is_rectified", useRectifiedImages, true);
00101
00102 ROS_ASSERT(camera_frame != "" && marker_frame != "");
00103
00104 if ( reference_frame.empty() )
00105 reference_frame = camera_frame;
00106
00107 ROS_INFO("Aruco node started with marker size of %f m and marker id to track: %d",
00108 marker_size, marker_id);
00109 ROS_INFO("Aruco node will publish pose to TF with %s as parent and %s as child.",
00110 reference_frame.c_str(), marker_frame.c_str());
00111 }
00112
00113 bool getTransform(const std::string& refFrame,
00114 const std::string& childFrame,
00115 tf::StampedTransform& transform)
00116 {
00117 std::string errMsg;
00118
00119 if ( !_tfListener.waitForTransform(refFrame,
00120 childFrame,
00121 ros::Time(0),
00122 ros::Duration(0.5),
00123 ros::Duration(0.01),
00124 &errMsg)
00125 )
00126 {
00127 ROS_ERROR_STREAM("Unable to get pose from TF: " << errMsg);
00128 return false;
00129 }
00130 else
00131 {
00132 try
00133 {
00134 _tfListener.lookupTransform( refFrame, childFrame,
00135 ros::Time(0),
00136 transform);
00137 }
00138 catch ( const tf::TransformException& e)
00139 {
00140 ROS_ERROR_STREAM("Error in lookupTransform of " << childFrame << " in " << refFrame);
00141 return false;
00142 }
00143
00144 }
00145 return true;
00146 }
00147
00148
00149 void image_callback(const sensor_msgs::ImageConstPtr& msg)
00150 {
00151 static tf::TransformBroadcaster br;
00152 if(cam_info_received)
00153 {
00154 ros::Time curr_stamp(ros::Time::now());
00155 cv_bridge::CvImagePtr cv_ptr;
00156 try
00157 {
00158 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::RGB8);
00159 inImage = cv_ptr->image;
00160
00161
00162 markers.clear();
00163
00164 mDetector.detect(inImage, markers, camParam, marker_size, false);
00165
00166 for(size_t i=0; i<markers.size(); ++i)
00167 {
00168
00169 if(markers[i].id == marker_id)
00170 {
00171 tf::Transform transform = aruco_ros::arucoMarker2Tf(markers[i]);
00172 tf::StampedTransform cameraToReference;
00173 cameraToReference.setIdentity();
00174
00175 if ( reference_frame != camera_frame )
00176 {
00177 getTransform(reference_frame,
00178 camera_frame,
00179 cameraToReference);
00180 }
00181
00182 transform =
00183 static_cast<tf::Transform>(cameraToReference)
00184 * static_cast<tf::Transform>(rightToLeft)
00185 * transform;
00186
00187 tf::StampedTransform stampedTransform(transform, curr_stamp,
00188 reference_frame, marker_frame);
00189 br.sendTransform(stampedTransform);
00190 geometry_msgs::PoseStamped poseMsg;
00191 tf::poseTFToMsg(transform, poseMsg.pose);
00192 poseMsg.header.frame_id = reference_frame;
00193 poseMsg.header.stamp = curr_stamp;
00194 pose_pub.publish(poseMsg);
00195
00196 geometry_msgs::TransformStamped transformMsg;
00197 tf::transformStampedTFToMsg(stampedTransform, transformMsg);
00198 transform_pub.publish(transformMsg);
00199
00200 geometry_msgs::Vector3Stamped positionMsg;
00201 positionMsg.header = transformMsg.header;
00202 positionMsg.vector = transformMsg.transform.translation;
00203 position_pub.publish(positionMsg);
00204 }
00205
00206 markers[i].draw(inImage,cv::Scalar(0,0,255),2);
00207 }
00208
00209
00210 if(camParam.isValid() && marker_size!=-1)
00211 {
00212 for(size_t i=0; i<markers.size(); ++i)
00213 {
00214 CvDrawingUtils::draw3dAxis(inImage, markers[i], camParam);
00215 }
00216 }
00217
00218 if(image_pub.getNumSubscribers() > 0)
00219 {
00220
00221 cv_bridge::CvImage out_msg;
00222 out_msg.header.stamp = curr_stamp;
00223 out_msg.encoding = sensor_msgs::image_encodings::RGB8;
00224 out_msg.image = inImage;
00225 image_pub.publish(out_msg.toImageMsg());
00226 }
00227
00228 if(debug_pub.getNumSubscribers() > 0)
00229 {
00230
00231 cv_bridge::CvImage debug_msg;
00232 debug_msg.header.stamp = curr_stamp;
00233 debug_msg.encoding = sensor_msgs::image_encodings::MONO8;
00234 debug_msg.image = mDetector.getThresholdedImage();
00235 debug_pub.publish(debug_msg.toImageMsg());
00236 }
00237 }
00238 catch (cv_bridge::Exception& e)
00239 {
00240 ROS_ERROR("cv_bridge exception: %s", e.what());
00241 return;
00242 }
00243 }
00244 }
00245
00246
00247 void cam_info_callback(const sensor_msgs::CameraInfo &msg)
00248 {
00249 camParam = aruco_ros::rosCameraInfo2ArucoCamParams(msg, useRectifiedImages);
00250
00251
00252
00253 rightToLeft.setIdentity();
00254 rightToLeft.setOrigin(
00255 tf::Vector3(
00256 -msg.P[3]/msg.P[0],
00257 -msg.P[7]/msg.P[5],
00258 0.0));
00259
00260 cam_info_received = true;
00261 cam_info_sub.shutdown();
00262 }
00263 };
00264
00265
00266 int main(int argc,char **argv)
00267 {
00268 ros::init(argc, argv, "aruco_simple");
00269
00270 ArucoSimple node;
00271
00272 ros::spin();
00273 }