Go to the documentation of this file.
49 #include <dynamic_reconfigure/server.h>
50 #include <aruco_ros/ArucoThresholdConfig.h>
74 double ticksBefore = cv::getTickCount();
87 ROS_WARN(
"normalizeImageIllumination is unimplemented!");
98 for (
unsigned int i = 0; i <
markers.size(); ++i)
105 geometry_msgs::Pose poseMsg;
113 geometry_msgs::Pose poseMsg;
127 float x[2], y[2], u[2], v[2];
128 for (
unsigned int i = 0; i < 2; ++i)
131 "Marker(" << i <<
") at camera coordinates = (" <<
markers[i].Tvec.at<
float>(0,0) <<
", " <<
markers[i].Tvec.at<
float>(1,0) <<
", " <<
markers[i].Tvec.at<
float>(2,0));
133 x[i] =
markers[i].Tvec.at<
float>(0, 0) /
markers[i].Tvec.at<
float>(2, 0);
134 y[i] =
markers[i].Tvec.at<
float>(1, 0) /
markers[i].Tvec.at<
float>(2, 0);
141 "Mid point between the two markers in the image = (" << (x[0]+x[1])/2 <<
", " << (y[0]+y[1])/2 <<
")");
148 for (
unsigned int i = 0; i < 3; ++i)
149 midPoint3D[i] = (
markers[0].Tvec.at<
float>(i, 0) +
markers[1].Tvec.at<
float>(i, 0)) / 2;
151 float midPointNormalized[2];
152 midPointNormalized[0] = midPoint3D[0] / midPoint3D[2];
153 midPointNormalized[1] = midPoint3D[1] / midPoint3D[2];
158 "3D Mid point between the two markers in undistorted pixel coordinates = (" << u[0] <<
", " << v[0] <<
")");
161 cv::circle(
inImage, cv::Point(u[0], v[0]), 3, cv::Scalar(0, 0, 255), cv::FILLED);
168 for (
unsigned int i = 0; i <
markers.size(); ++i)
178 out_msg.
header.stamp = curr_stamp;
188 debug_msg.
header.stamp = curr_stamp;
194 ROS_DEBUG(
"runtime: %f ms", 1000 * (cv::getTickCount() - ticksBefore) / cv::getTickFrequency());
198 ROS_ERROR(
"cv_bridge exception: %s", e.what());
219 int main(
int argc,
char **argv)
225 dynamic_reconfigure::Server<aruco_ros::ArucoThresholdConfig> server;
226 dynamic_reconfigure::Server<aruco_ros::ArucoThresholdConfig>::CallbackType f_;
228 server.setCallback(f_);
257 ROS_ERROR(
"parent_name and/or child_name was not set!");
263 ROS_INFO(
"ArUco node will publish pose to TF with (%s, %s) and (%s, %s) as (parent,child).",
parent_name.c_str(),
void reconf_callback(aruco_ros::ArucoThresholdConfig &config, std::uint32_t level)
sensor_msgs::ImagePtr toImageMsg() const
int main(int argc, char **argv)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
uint32_t getNumSubscribers() const
aruco::CameraParameters camParam
image_transport::Publisher debug_pub
void setDetectionMode(DetectionMode dm, float minMarkerSize=0)
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
#define ROS_DEBUG_STREAM(args)
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)
static void draw3dCube(cv::Mat &Image, Marker &m, const CameraParameters &CP, int lineSize=1, bool setYperpendicular=false)
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::Subscriber cam_info_sub
image_transport::Publisher image_pub
aruco::CameraParameters rosCameraInfo2ArucoCamParams(const sensor_msgs::CameraInfo &cam_info, bool useRectifiedParameters)
rosCameraInfo2ArucoCamParams gets the camera intrinsics from a CameraInfo message and copies them to ...
tf::Transform arucoMarker2Tf(const aruco::Marker &marker)
void cam_info_callback(const sensor_msgs::CameraInfo &msg)
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
int dctComponentsToRemove
aruco::MarkerDetector mDetector
std::vector< aruco::Marker > markers
T param(const std::string ¶m_name, const T &default_val) const
bool normalizeImageIllumination
void image_callback(const sensor_msgs::ImageConstPtr &msg)
cv::Mat getThresholdedImage(uint32_t idx=0)
aruco_ros
Author(s): Rafael Muñoz Salinas
, Bence Magyar
autogenerated on Sat Sep 23 2023 02:26:51