Files
teleoperation/src/aruco_detector.cpp
2019-01-17 17:30:43 +01:00

128 lines
4.0 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>
static const std::string OPENCV_WINDOW = "Original image";
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_)
{
// Subscrive to input video feed
image_sub_ = it_.subscribe("/usb_cam/image_raw", 1,
&ImageConverter::imageCb, this);
// Create output windows
cv::namedWindow(OPENCV_WINDOW);
cv::namedWindow(ARUCO_WINDOW);
}
~ImageConverter() {
// Clean Up
cv::destroyWindow(OPENCV_WINDOW);
cv::destroyWindow(ARUCO_WINDOW);
}
void imageCb(const sensor_msgs::ImageConstPtr& msg) {
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;
}
// Output Original Image (bcs y not)
cv::imshow(OPENCV_WINDOW, cv_ptr->image);
// Do Aruco
cv::Mat cam_mat = (cv::Mat_<double>(3, 3) <<
274.139508945831, 0.0, 141.184472810944,
0.0, 275.741846757374, 106.693773654172,
0.0, 0.0, 1.0);
cv::Mat distortion = (cv::Mat_<double>(4, 1) <<
-0.0870160932911717,
0.128210165050533,
0.003379500659424,
-0.00106205540818586);
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 and print aruco
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);
float x = markers[i].Tvec.at<float>(0);
float y = markers[i].Tvec.at<float>(1);
float z = markers[i].Tvec.at<float>(2);
// cv::Mat rot_mat;
// cv::Rodrigues(markers[i].Rvec, rot_mat);
// float roll = atan2(
// rot_mat.at<float>(2,1),
// rot_mat.at<float>(2,2));
// float pitch = -atan2(
// rot_mat.at<float>(2,0),
// sqrt(
// pow(rot_mat.at<float>(2,1),2) +
// pow(rot_mat.at<float>(2,2),2)));
// float yaw = atan2(
// rot_mat.at<float>(1,0),
// rot_mat.at<float>(0,0));
std::string id = "Aruco_";
// int to str basically
std::ostringstream ss;
ss << markers[i].id;
id += ss.str();
id += "_frame";
tf::Transform aruco_tf;
aruco_tf.setIdentity();
// tf::Quaternion q;
// q.setRPY(roll, pitch, yaw);
aruco_tf.setOrigin(tf::Vector3(x, y, z));
// aruco_tf.setRotation(q);
this->aruco_pub.sendTransform(tf::StampedTransform(
aruco_tf, ros::Time::now(), "CameraTop_optical_frame",
id.c_str()));
}
cv::imshow(ARUCO_WINDOW, aruco_demo);
cv::waitKey(2);
}
};
int main(int argc, char** argv) {
ros::init(argc, argv, "aruco_detector");
ImageConverter ic;
ros::spin();
return 0;
}