38 #include <std_msgs/Bool.h>    43 #include <ar_track_alvar_msgs/AlvarMarker.h>    44 #include <ar_track_alvar_msgs/AlvarMarkers.h>    48 #include <dynamic_reconfigure/server.h>    49 #include <ar_track_alvar/ParamsConfig.h>    51 using namespace alvar;
    78 void getCapCallback (
const sensor_msgs::ImageConstPtr & image_msg);
   104             IplImage ipl_image = cv_ptr_->image;
   108                         for (
size_t i=0; i<marker_detector.
markers->size(); i++)
   111                         int id = (*(marker_detector.
markers))[i].GetId();
   131                 if (z_axis_cam.
z() > 0)
   137                                 std::string markerFrame = 
"ar_marker_";
   138                                 std::stringstream out;
   140                                 std::string id_string = out.str();
   141                                 markerFrame += id_string;
   142                                 tf::StampedTransform camToMarker (t, image_msg->header.stamp, image_msg->header.frame_id, markerFrame.c_str());
   147                                 rvizMarker_.header.frame_id = image_msg->header.frame_id;
   148                                 rvizMarker_.header.stamp = image_msg->header.stamp;
   155                                 rvizMarker_.type = visualization_msgs::Marker::CUBE;
   156                                 rvizMarker_.action = visualization_msgs::Marker::ADD;
   203                                 ar_track_alvar_msgs::AlvarMarker ar_pose_marker;
   206                             ar_pose_marker.header.stamp = image_msg->header.stamp;
   207                             ar_pose_marker.id = id;
   213                 ROS_ERROR (
"Could not convert from '%s' to 'rgb8'.", image_msg->encoding.c_str ());
   220   ROS_INFO(
"AR tracker reconfigured: %s %.2f %.2f %.2f %.2f", config.enabled ? 
"ENABLED" : 
"DISABLED",
   221            config.max_frequency, config.marker_size, config.max_new_marker_error, config.max_track_error);
   238 int main(
int argc, 
char *argv[])
   244     ROS_WARN(
"Command line arguments are deprecated. Consider using ROS parameters and remappings.");
   247       std::cout << std::endl;
   248       cout << 
"Not enough arguments provided." << endl;
   249       cout << 
"Usage: ./individualMarkersNoKinect <marker size in cm> <max new marker error> <max track error> "   250            << 
"<cam image topic> <cam info topic> <output frame> [ <max frequency> <marker_resolution> <marker_margin>]";
   251       std::cout << std::endl;
   282       ROS_ERROR(
"Param 'output_frame' has to be set.");
   301         arMarkerPub_ = n.
advertise < ar_track_alvar_msgs::AlvarMarkers > (
"ar_pose_marker", 0);
   302         rvizMarkerPub_ = n.
advertise < visualization_msgs::Marker > (
"visualization_marker", 0);
   305   dynamic_reconfigure::Server < ar_track_alvar::ParamsConfig > server;
   306   dynamic_reconfigure::Server<ar_track_alvar::ParamsConfig>::CallbackType 
f;
   309   server.setCallback(f);
 
int main(int argc, char *argv[])
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())
tf::TransformListener * tf_listener
void configCallback(ar_track_alvar::ParamsConfig &config, uint32_t level)
void publish(const boost::shared_ptr< M > &message) const 
image_transport::Subscriber cam_sub_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void SetMarkerSize(double _edge_length=1, int _res=5, double _margin=2)
ros::Publisher rvizMarkerPub_
This file implements a generic marker detector. 
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Publisher arMarkerPub_
tf::TransformBroadcaster * tf_broadcaster
Simple Camera class for calculating distortions, orientation or projections with pre-calibrated camer...
std::vector< M, Eigen::aligned_allocator< M > > * markers
std::string cam_image_topic
MarkerDetector for detecting markers of type M 
TFSIMD_FORCE_INLINE const tfScalar & z() const 
Duration expectedCycleTime() const 
static const Quaternion & getIdentity()
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
MarkerDetector< MarkerData > marker_detector
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
std::string cam_info_topic
Pose representation derived from the Rotation class 
void enableCallback(const std_msgs::BoolConstPtr &msg)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
cv_bridge::CvImagePtr cv_ptr_
visualization_msgs::Marker rvizMarker_
ar_track_alvar_msgs::AlvarMarkers arPoseMarkers_
static void poseTFToMsg(const Pose &bt, geometry_msgs::Pose &msg)
double max_new_marker_error
bool getParam(const std::string &key, std::string &s) const 
int Detect(IplImage *image, Camera *cam, bool track=false, bool visualize=false, double max_new_marker_error=0.08, double max_track_error=0.2, LabelingMethod labeling_method=CVSEQ, bool update_pose=true)
Detect Marker 's from image 
ROSCPP_DECL void spinOnce()
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const 
void getCapCallback(const sensor_msgs::ImageConstPtr &image_msg)