Go to the documentation of this file.
47 #include <visualization_msgs/Marker.h>
49 #include <dynamic_reconfigure/server.h>
50 #include <aruco_ros/ArucoThresholdConfig.h>
92 "Corner refinement options have been removed in ArUco 3.0.0, corner_refinement ROS parameter is deprecated");
95 std::string thresh_method;
98 case aruco::MarkerDetector::ThresMethod::THRES_ADAPTIVE:
99 thresh_method =
"THRESH_ADAPTIVE";
101 case aruco::MarkerDetector::ThresMethod::THRES_AUTO_FIXED:
102 thresh_method =
"THRESH_AUTO_FIXED";
105 thresh_method =
"UNKNOWN";
112 float min_marker_size;
113 nh.
param<
float>(
"min_marker_size", min_marker_size, 0.02);
115 std::string detection_mode;
116 nh.
param<std::string>(
"detection_mode", detection_mode,
"DM_FAST");
117 if (detection_mode ==
"DM_FAST")
119 else if (detection_mode ==
"DM_VIDEO_FAST")
125 ROS_INFO_STREAM(
"Marker size min: " << min_marker_size <<
"% of image area");
177 ROS_ERROR_STREAM(
"Error in lookupTransform of " << childFrame <<
" in " << refFrame);
192 ROS_DEBUG(
"No subscribers, not looking for ArUco markers");
199 ros::Time curr_stamp = msg->header.stamp;
211 for (std::size_t i = 0; i <
markers.size(); ++i)
230 geometry_msgs::PoseStamped poseMsg;
233 poseMsg.header.stamp = curr_stamp;
236 geometry_msgs::TransformStamped transformMsg;
240 geometry_msgs::Vector3Stamped positionMsg;
241 positionMsg.header = transformMsg.header;
242 positionMsg.vector = transformMsg.transform.translation;
245 geometry_msgs::PointStamped pixelMsg;
246 pixelMsg.header = transformMsg.header;
247 pixelMsg.point.x =
markers[i].getCenter().x;
248 pixelMsg.point.y =
markers[i].getCenter().y;
249 pixelMsg.point.z = 0;
253 visualization_msgs::Marker visMarker;
254 visMarker.header = transformMsg.header;
256 visMarker.type = visualization_msgs::Marker::CUBE;
257 visMarker.action = visualization_msgs::Marker::ADD;
258 visMarker.pose = poseMsg.pose;
261 visMarker.scale.z = 0.001;
262 visMarker.color.r = 1.0;
263 visMarker.color.g = 0;
264 visMarker.color.b = 0;
265 visMarker.color.a = 1.0;
277 for (std::size_t i = 0; i <
markers.size(); ++i)
287 out_msg.
header.stamp = curr_stamp;
297 debug_msg.
header.stamp = curr_stamp;
305 ROS_ERROR(
"cv_bridge exception: %s", e.what());
328 if (config.normalizeImage)
330 ROS_WARN(
"normalizeImageIllumination is unimplemented!");
335 int main(
int argc,
char **argv)
#define ROS_ERROR_STREAM(args)
ros::Subscriber cam_info_sub
sensor_msgs::ImagePtr toImageMsg() const
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
image_transport::ImageTransport it
uint32_t getNumSubscribers() const
void reconf_callback(aruco_ros::ArucoThresholdConfig &config, uint32_t level)
void setDetectionMode(DetectionMode dm, float minMarkerSize=0)
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
static void draw3dAxis(cv::Mat &Image, const CameraParameters &CP, const cv::Mat &Rvec, const cv::Mat &Tvec, float axis_size)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
std::vector< aruco::Marker > detect(const cv::Mat &input)
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ros::Publisher marker_pub
std::vector< aruco::Marker > markers
image_transport::Publisher image_pub
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
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())
ros::Publisher transform_pub
void image_callback(const sensor_msgs::ImageConstPtr &msg)
ros::Publisher position_pub
aruco::CameraParameters camParam
aruco::CameraParameters rosCameraInfo2ArucoCamParams(const sensor_msgs::CameraInfo &cam_info, bool useRectifiedParameters)
rosCameraInfo2ArucoCamParams gets the camera intrinsics from a CameraInfo message and copies them to ...
bool hasParam(const std::string &key) const
int main(int argc, char **argv)
tf::Transform arucoMarker2Tf(const aruco::Marker &marker)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
#define ROS_INFO_STREAM(args)
void publish(const sensor_msgs::Image &message) const
image_transport::Subscriber image_sub
static void transformStampedTFToMsg(const StampedTransform &bt, geometry_msgs::TransformStamped &msg)
void cam_info_callback(const sensor_msgs::CameraInfo &msg)
std::string reference_frame
tf::TransformListener _tfListener
image_transport::Publisher debug_pub
aruco::MarkerDetector mDetector
T param(const std::string ¶m_name, const T &default_val) const
bool getTransform(const std::string &refFrame, const std::string &childFrame, tf::StampedTransform &transform)
uint32_t getNumSubscribers() const
tf::StampedTransform rightToLeft
cv::Mat getThresholdedImage(uint32_t idx=0)
dynamic_reconfigure::Server< aruco_ros::ArucoThresholdConfig > dyn_rec_server
aruco_ros
Author(s): Rafael Muñoz Salinas
, Bence Magyar
autogenerated on Sat Sep 23 2023 02:26:51