37 #include <aruco/aruco.h> 38 #include <aruco/cvdrawingutils.h> 44 #include <aruco_ros/aruco_ros_utils.h> 47 #include <visualization_msgs/Marker.h> 49 #include <dynamic_reconfigure/server.h> 50 #include <aruco_ros/ArucoThresholdConfig.h> 51 using namespace aruco;
89 : cam_info_received(false),
94 std::string refinementMethod;
95 nh.
param<std::string>(
"corner_refinement", refinementMethod,
"LINES");
96 if ( refinementMethod ==
"SUBPIX" )
98 else if ( refinementMethod ==
"HARRIS" )
100 else if ( refinementMethod ==
"NONE" )
110 ROS_INFO_STREAM(
"Threshold method: " <<
" th1: " << th1 <<
" th2: " << th2);
123 pose_pub = nh.
advertise<geometry_msgs::PoseStamped>(
"pose", 100);
124 transform_pub = nh.
advertise<geometry_msgs::TransformStamped>(
"transform", 100);
125 position_pub = nh.
advertise<geometry_msgs::Vector3Stamped>(
"position", 100);
126 marker_pub = nh.
advertise<visualization_msgs::Marker>(
"marker", 10);
127 pixel_pub = nh.
advertise<geometry_msgs::PointStamped>(
"pixel", 10);
130 nh.
param<
int>(
"marker_id", marker_id, 300);
131 nh.
param<std::string>(
"reference_frame", reference_frame,
"");
132 nh.
param<std::string>(
"camera_frame", camera_frame,
"");
133 nh.
param<std::string>(
"marker_frame", marker_frame,
"");
135 nh.
param<
bool>(
"rotate_marker_axis", rotate_marker_axis_,
true);
137 ROS_ASSERT(camera_frame !=
"" && marker_frame !=
"");
139 if ( reference_frame.empty() )
140 reference_frame = camera_frame;
142 ROS_INFO(
"Aruco node started with marker size of %f m and marker id to track: %d",
143 marker_size, marker_id);
144 ROS_INFO(
"Aruco node will publish pose to TF with %s as parent and %s as child.",
145 reference_frame.c_str(), marker_frame.c_str());
151 const std::string& childFrame,
177 ROS_ERROR_STREAM(
"Error in lookupTransform of " << childFrame <<
" in " << refFrame);
196 ROS_DEBUG(
"No subscribers, not looking for aruco markers");
201 if(cam_info_received)
208 inImage = cv_ptr->image;
213 mDetector.
detect(inImage, markers, camParam, marker_size,
false);
215 for(
size_t i=0; i<markers.size(); ++i)
218 if(markers[i].
id == marker_id)
224 if ( reference_frame != camera_frame )
226 getTransform(reference_frame,
233 * static_cast<tf::Transform>(rightToLeft)
237 reference_frame, marker_frame);
239 geometry_msgs::PoseStamped poseMsg;
241 poseMsg.header.frame_id = reference_frame;
242 poseMsg.header.stamp = curr_stamp;
245 geometry_msgs::TransformStamped transformMsg;
247 transform_pub.
publish(transformMsg);
249 geometry_msgs::Vector3Stamped positionMsg;
250 positionMsg.header = transformMsg.header;
251 positionMsg.vector = transformMsg.transform.translation;
252 position_pub.
publish(positionMsg);
254 geometry_msgs::PointStamped pixelMsg;
255 pixelMsg.header = transformMsg.header;
256 pixelMsg.point.x = markers[i].getCenter().x;
257 pixelMsg.point.y = markers[i].getCenter().y;
258 pixelMsg.point.z = 0;
262 visualization_msgs::Marker visMarker;
263 visMarker.header = transformMsg.header;
265 visMarker.type = visualization_msgs::Marker::CUBE;
266 visMarker.action = visualization_msgs::Marker::ADD;
267 visMarker.pose = poseMsg.pose;
269 visMarker.scale.y = 0.001;
271 visMarker.color.r = 1.0;
272 visMarker.color.g = 0;
273 visMarker.color.b = 0;
274 visMarker.color.a = 1.0;
280 markers[i].draw(inImage,cv::Scalar(0,0,255),2);
284 if(camParam.
isValid() && marker_size>0)
286 for(
size_t i=0; i<markers.size(); ++i)
296 out_msg.
header.stamp = curr_stamp;
306 debug_msg.
header.stamp = curr_stamp;
314 ROS_ERROR(
"cv_bridge exception: %s", e.what());
334 cam_info_received =
true;
342 if (config.normalizeImage)
344 ROS_WARN(
"normalizeImageIllumination is unimplemented!");
bool getTransform(const std::string &refFrame, const std::string &childFrame, tf::StampedTransform &transform)
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
void detect(const cv::Mat &input, std::vector< Marker > &detectedMarkers, cv::Mat camMatrix=cv::Mat(), cv::Mat distCoeff=cv::Mat(), float markerSizeMeters=-1, bool setYPerpendicular=true)
void setThresholdParams(double param1, double param2)
void getMinMaxSize(float &min, float &max)
tf::StampedTransform rightToLeft
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void getThresholdParams(double ¶m1, double ¶m2) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ros::Publisher marker_pub
CornerRefinementMethod getCornerRefinementMethod() const
void image_callback(const sensor_msgs::ImageConstPtr &msg)
uint32_t getNumSubscribers() const
aruco::CameraParameters camParam
ROSCPP_DECL void spin(Spinner &spinner)
pcl::PointCloud< myPointXYZRID > transform(pcl::PointCloud< myPointXYZRID > pc, float x, float y, float z, float rot_x, float rot_y, float rot_z)
void reconf_callback(aruco_ros::ArucoThresholdConfig &config, uint32_t level)
ros::Publisher transform_pub
tf::Transform arucoMarker2Tf(const aruco::Marker &marker, bool rotate_marker_axis=true)
ros::Publisher position_pub
image_transport::Publisher image_pub
image_transport::Subscriber image_sub
void publish(const sensor_msgs::Image &message) const
int main(int argc, char **argv)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
static void draw3dAxis(cv::Mat &Image, Marker &m, const CameraParameters &CP)
ThresholdMethods getThresholdMethod() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Main class for marker detection.
aruco::CameraParameters rosCameraInfo2ArucoCamParams(const sensor_msgs::CameraInfo &cam_info, bool useRectifiedParameters)
rosCameraInfo2ArucoCamParams gets the camera intrinsics from a CameraInfo message and copies them to ...
const cv::Mat & getThresholdedImage()
Parameters of the camera.
uint32_t getNumSubscribers() const
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
#define ROS_INFO_STREAM(args)
int getDesiredSpeed() const
image_transport::Publisher debug_pub
void cam_info_callback(const sensor_msgs::CameraInfo &msg)
std::string reference_frame
dynamic_reconfigure::Server< aruco_ros::ArucoThresholdConfig > dyn_rec_server
static void transformStampedTFToMsg(const StampedTransform &bt, geometry_msgs::TransformStamped &msg)
tf::TransformListener _tfListener
#define ROS_ERROR_STREAM(args)
void setCornerRefinementMethod(CornerRefinementMethod method)
sensor_msgs::ImagePtr toImageMsg() const
ros::Subscriber cam_info_sub
image_transport::ImageTransport it