Go to the documentation of this file.
45 #include <aruco_msgs/MarkerArray.h>
47 #include <std_msgs/UInt32MultiArray.h>
90 sensor_msgs::CameraInfoConstPtr msg = ros::topic::waitForMessage<sensor_msgs::CameraInfo>(
"/camera_info",
nh_);
111 marker_msg_ = aruco_msgs::MarkerArray::Ptr(
new aruco_msgs::MarkerArray());
135 ROS_ERROR_STREAM(
"Error in lookupTransform of " << childFrame <<
" in " << refFrame);
150 if (!publishMarkers && !publishMarkersList && !publishImage && !publishDebug)
153 ros::Time curr_stamp = msg->header.stamp;
174 for (std::size_t i = 0; i <
markers_.size(); ++i)
176 aruco_msgs::Marker & marker_i =
marker_msg_->markers.at(i);
177 marker_i.header.stamp = curr_stamp;
179 marker_i.confidence = 1.0;
195 for (std::size_t i = 0; i <
markers_.size(); ++i)
197 aruco_msgs::Marker & marker_i =
marker_msg_->markers.at(i);
199 transform =
static_cast<tf::Transform>(cameraToReference) * transform;
210 if (publishMarkersList)
213 for (std::size_t i = 0; i <
markers_.size(); ++i)
220 for (std::size_t i = 0; i <
markers_.size(); ++i)
228 for (std::size_t i = 0; i <
markers_.size(); ++i)
237 out_msg.
header.stamp = curr_stamp;
248 debug_msg.
header.stamp = curr_stamp;
257 ROS_ERROR(
"cv_bridge exception: %s", e.what());
262 int main(
int argc,
char **argv)
264 ros::init(argc, argv,
"aruco_marker_publisher");
ros::Publisher marker_pub_
#define ROS_ERROR_STREAM(args)
sensor_msgs::ImagePtr toImageMsg() const
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
std::vector< aruco::Marker > markers_
std_msgs::UInt32MultiArray marker_list_msg_
image_transport::ImageTransport it_
tf::TransformListener tfListener_
uint32_t getNumSubscribers() const
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)
aruco_msgs::MarkerArray::Ptr marker_msg_
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
std::string reference_frame_
std::vector< aruco::Marker > detect(const cv::Mat &input)
image_transport::Publisher image_pub_
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::Subscriber image_sub_
aruco::CameraParameters camParam_
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())
aruco::CameraParameters rosCameraInfo2ArucoCamParams(const sensor_msgs::CameraInfo &cam_info, bool useRectifiedParameters)
rosCameraInfo2ArucoCamParams gets the camera intrinsics from a CameraInfo message and copies them to ...
std::string camera_frame_
std::string marker_frame_
tf::Transform arucoMarker2Tf(const aruco::Marker &marker)
void publish(const sensor_msgs::Image &message) const
int main(int argc, char **argv)
bool getTransform(const std::string &refFrame, const std::string &childFrame, tf::StampedTransform &transform)
ros::Publisher marker_list_pub_
T param(const std::string ¶m_name, const T &default_val) const
uint32_t getNumSubscribers() const
void image_callback(const sensor_msgs::ImageConstPtr &msg)
ros::Subscriber cam_info_sub_
image_transport::Publisher debug_pub_
cv::Mat getThresholdedImage(uint32_t idx=0)
aruco::MarkerDetector mDetector_
aruco_ros
Author(s): Rafael Muñoz Salinas
, Bence Magyar
autogenerated on Sat Sep 23 2023 02:26:51