Files
teleoperation/src/aruco_detector.cpp

149 lines
4.4 KiB
C++

#include <ros/ros.h>
#include <vector>
#include <iostream>
#include <sstream>
#include <tf/transform_broadcaster.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/video/tracking.hpp>
#include <aruco/aruco.h>
#include <teleoperation/utils.hpp>
/*
* This is the ROS Node for detecting the ArUco markers.
*
* Node: aruco_detector
*
* It subscribes to a webcam, detects the markers, transforms them
* into the correct coordinate frame (z-up) and publishes on TF
* relatively to the odom frame
*
*/
static const std::string ARUCO_WINDOW = "Aruco window";
class ImageConverter {
ros::NodeHandle nh_;
tf::TransformBroadcaster aruco_pub;
image_transport::ImageTransport it_;
image_transport::Subscriber image_sub_;
public:
ImageConverter() :
it_(nh_)
{
// Subscribe to input video feed
image_sub_ = it_.subscribe("/usb_cam/image_raw", 1,
&ImageConverter::imageCb, this);
// Create output windows
cv::namedWindow(ARUCO_WINDOW);
ROS_INFO("ARUCO: UP");
}
~ImageConverter() {
// Clean Up
cv::destroyWindow(ARUCO_WINDOW);
}
void imageCb(const sensor_msgs::ImageConstPtr& msg) {
// This function gets called when an image arrives
cv_bridge::CvImageConstPtr cv_ptr;
try
{
// Create OpenCV, share memory with original message
cv_ptr = cv_bridge::toCvShare(msg,
sensor_msgs::image_encodings::BGR8);
}
catch (cv_bridge::Exception& e)
{
ROS_ERROR("cv_bridge exception: %s", e.what());
return;
}
// Define parameters of markers and camera
cv::Mat cam_mat = (cv::Mat_<double>(3, 3) <<
690., 0.0, 320,
0.0, 690., 225,
0.0, 0.0, 1.0);
cv::Mat distortion = (cv::Mat_<double>(4, 1) <<
-0.05,
0,
0,
-0.0015);
aruco::CameraParameters cam(cam_mat, distortion, cv_ptr->image.size());
aruco::MarkerDetector detector;
std::vector<aruco::Marker> markers;
float m_size = 0.15;
detector.detect(cv_ptr->image, markers, cam, m_size);
// Draw all aruco into the window and publish on tf
cv::Mat aruco_demo = cv_ptr->image.clone();
for (int i = 0; i < markers.size(); i++) {
markers[i].draw(aruco_demo, cv::Scalar(0, 0, 255), 2);
cv::Mat rot_cv;
cv::Rodrigues(markers[i].Rvec, rot_cv);
// Transform the coordinates of the aruco markers so that they
// are in the Z-up, X-forward frame
tf::Matrix3x3 rot(
rot_cv.at<float>(0, 0),
rot_cv.at<float>(0, 1),
rot_cv.at<float>(0, 2),
rot_cv.at<float>(1, 0),
rot_cv.at<float>(1, 1),
rot_cv.at<float>(1, 2),
rot_cv.at<float>(2, 0),
rot_cv.at<float>(2, 1),
rot_cv.at<float>(2, 2)
);
tf::Vector3 trans(
markers[i].Tvec.at<float>(0),
markers[i].Tvec.at<float>(1),
markers[i].Tvec.at<float>(2)
);
tf::Matrix3x3 hmat(
0, 0, -1,
1, 0, 0,
0, -1, 0
);
tf::Matrix3x3 another(
0, 0, -1,
1, 0, 0,
0, -1, 0
);
rot = hmat * rot * another; // This transforms the coords
trans = hmat * trans;
tf::Transform aruco_tf(rot, trans);
std::string id = "Aruco_";
id += stuff_to_str(markers[i].id);
id += "_frame";
// Publish the transform
this->aruco_pub.sendTransform(tf::StampedTransform(
aruco_tf, ros::Time::now(), "odom",
id.c_str()));
}
cv::imshow(ARUCO_WINDOW, aruco_demo);
cv::waitKey(2);
}
};
int main(int argc, char** argv) {
ros::init(argc, argv, "aruco_detector");
ROS_INFO("ARUCO: STARTING");
ImageConverter ic;
ros::spin();
return 0;
}