initial commit
This commit is contained in:
107
src/aruco_detector.cpp
Normal file
107
src/aruco_detector.cpp
Normal file
@@ -0,0 +1,107 @@
|
||||
#include <ros/ros.h>
|
||||
#include <vector>
|
||||
#include <iostream>
|
||||
#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("/nao_robot/camera/front/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;
|
||||
ROS_INFO("IN IMAGE CB");
|
||||
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);
|
||||
ROS_INFO("OUTPUT STUFF");
|
||||
|
||||
// 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);
|
||||
std::string id = "Aruco_";
|
||||
id += std::to_string(markers[i].id);
|
||||
id += "_frame";
|
||||
tf::Transform aruco_tf;
|
||||
aruco_tf.setIdentity();
|
||||
aruco_tf.setOrigin(tf::Vector3(x, y, z));
|
||||
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;
|
||||
}
|
||||
47
src/aruco_effector.cpp
Normal file
47
src/aruco_effector.cpp
Normal file
@@ -0,0 +1,47 @@
|
||||
#include <ros/ros.h>
|
||||
#include <vector>
|
||||
#include <iostream>
|
||||
#include <tf/transform_broadcaster.h>
|
||||
#include <tf/transform_listener.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>
|
||||
|
||||
int main(int argc, char** argv) {
|
||||
ros::init(argc, argv, "aruco_effector");
|
||||
ros::NodeHandle node;
|
||||
|
||||
tf::TransformListener tflisten;
|
||||
ros::Rate rate(1.0);
|
||||
while (node.ok()) {
|
||||
tf::StampedTransform l_transform, r_transform;
|
||||
try {
|
||||
tflisten.lookupTransform("Aruco_1_frame", "Aruco_0_frame",
|
||||
ros::Time(0), l_transform);
|
||||
ROS_INFO("LEFT FRAME");
|
||||
std::cout << l_transform.getOrigin().x() << std::endl;
|
||||
std::cout << l_transform.getOrigin().y() << std::endl;
|
||||
std::cout << l_transform.getOrigin().z() << std::endl;
|
||||
}
|
||||
catch (tf::TransformException &ex) {
|
||||
// ROS_ERROR("%s", ex.what());
|
||||
}
|
||||
try {
|
||||
tflisten.lookupTransform("Aruco_2_frame", "Aruco_0_frame",
|
||||
ros::Time(0), r_transform);
|
||||
ROS_INFO("RIGHT FRAME");
|
||||
std::cout << r_transform.getOrigin().x() << std::endl;
|
||||
std::cout << r_transform.getOrigin().y() << std::endl;
|
||||
std::cout << r_transform.getOrigin().z() << std::endl;
|
||||
}
|
||||
catch (tf::TransformException &ex) {
|
||||
// ROS_ERROR("%s", ex.what());
|
||||
}
|
||||
rate.sleep();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
Reference in New Issue
Block a user