45 #include <aruco_msgs/MarkerArray.h> 47 #include <std_msgs/UInt32MultiArray.h> 93 sensor_msgs::CameraInfoConstPtr msg = ros::topic::waitForMessage<sensor_msgs::CameraInfo>(
"/camera_info",
nh_);
100 ROS_ASSERT(not (camera_frame_.empty() and not reference_frame_.empty()));
101 if(reference_frame_.empty())
102 reference_frame_ = camera_frame_;
111 marker_pub_ = nh_.
advertise<aruco_msgs::MarkerArray>(
"markers", 100);
112 marker_list_pub_ = nh_.
advertise<std_msgs::UInt32MultiArray>(
"markers_list", 10);
114 marker_msg_ = aruco_msgs::MarkerArray::Ptr(
new aruco_msgs::MarkerArray());
116 marker_msg_->header.seq = 0;
120 const std::string& childFrame,
145 ROS_ERROR_STREAM(
"Error in lookupTransform of " << childFrame <<
" in " << refFrame);
160 if(!publishMarkers && !publishMarkersList && !publishImage && !publishDebug)
163 ros::Time curr_stamp = msg->header.stamp;
168 inImage_ = cv_ptr->image;
174 mDetector_.
detect(inImage_, markers_, camParam_, marker_size_,
false);
179 marker_msg_->markers.clear();
180 marker_msg_->markers.resize(markers_.size());
181 marker_msg_->header.stamp = curr_stamp;
182 marker_msg_->header.seq++;
184 for(
size_t i=0; i<markers_.size(); ++i)
186 aruco_msgs::Marker & marker_i = marker_msg_->markers.at(i);
187 marker_i.header.stamp = curr_stamp;
188 marker_i.id = markers_.at(i).id;
189 marker_i.confidence = 1.0;
199 if ( reference_frame_ != camera_frame_ )
207 for(
size_t i=0; i<markers_.size(); ++i)
209 aruco_msgs::Marker & marker_i = marker_msg_->markers.at(i);
211 transform =
static_cast<tf::Transform>(cameraToReference) * transform;
218 if (marker_msg_->markers.size() > 0)
219 marker_pub_.
publish(marker_msg_);
222 if(publishMarkersList)
224 marker_list_msg_.data.resize(markers_.size());
225 for(
size_t i=0; i<markers_.size(); ++i)
226 marker_list_msg_.data[i] = markers_[i].id;
228 marker_list_pub_.
publish(marker_list_msg_);
232 for(
size_t i=0; i<markers_.size(); ++i)
234 markers_[i].draw(inImage_,cv::Scalar(0,0,255),2);
238 if(camParam_.
isValid() && marker_size_>0)
240 for(
size_t i=0; i<markers_.size(); ++i)
249 out_msg.
header.stamp = curr_stamp;
260 debug_msg.
header.stamp = curr_stamp;
269 ROS_ERROR(
"cv_bridge exception: %s", e.what());
277 ros::init(argc, argv,
"aruco_marker_publisher");
std_msgs::UInt32MultiArray marker_list_msg_
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)
ros::Publisher marker_pub_
image_transport::Publisher debug_pub_
ros::Publisher marker_list_pub_
image_transport::ImageTransport it_
void publish(const boost::shared_ptr< M > &message) const
aruco_msgs::MarkerArray::Ptr marker_msg_
tf::TransformListener tfListener_
ros::Subscriber cam_info_sub_
int main(int argc, char **argv)
std::string marker_frame_
std::string reference_frame_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
image_transport::Publisher image_pub_
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
ROSCPP_DECL void spin(Spinner &spinner)
tf::Transform arucoMarker2Tf(const aruco::Marker &marker, bool rotate_marker_axis=true)
void publish(const sensor_msgs::Image &message) const
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
aruco::CameraParameters camParam_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
static void draw3dAxis(cv::Mat &Image, Marker &m, const CameraParameters &CP)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
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()
void image_callback(const sensor_msgs::ImageConstPtr &msg)
bool getTransform(const std::string &refFrame, const std::string &childFrame, tf::StampedTransform &transform)
uint32_t getNumSubscribers() const
image_transport::Subscriber image_sub_
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
vector< aruco::Marker > markers_
std::string camera_frame_
aruco::MarkerDetector mDetector_
#define ROS_ERROR_STREAM(args)
sensor_msgs::ImagePtr toImageMsg() const