artoolkitplus.h
Go to the documentation of this file.
1 /***************************************************************************
2  * Copyright (C) 2013 by Markus Bader *
3  * markus.bader@tuwien.ac.at *
4  * *
5  * This program is free software; you can redistribute it and/or modify *
6  * it under the terms of the GNU General Public License as published by *
7  * the Free Software Foundation; either version 2 of the License, or *
8  * (at your option) any later version. *
9  * *
10  * This program is distributed in the hope that it will be useful, *
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of *
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
13  * GNU General Public License for more details. *
14  * *
15  * You should have received a copy of the GNU General Public License *
16  * along with this program; if not, write to the *
17  * Free Software Foundation, Inc., *
18  * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
19  ***************************************************************************/
20 
21 #ifndef ARTOOLKITPLUS_NODE_H
22 #define ARTOOLKITPLUS_NODE_H
23 
24 #include <ros/ros.h>
26 #include <tf/transform_listener.h>
28 #include <dynamic_reconfigure/server.h>
29 #include <tuw_artoolkitplus/ARParamConfig.h>
30 #include <marker_msgs/MarkerDetection.h>
31 
32 #include <list>
33 #include <opencv2/core/core.hpp>
34 #include "ARToolKitPlus/ar.h"
35 #include "ARToolKitPlus/arMulti.h"
36 
37 namespace ARToolKitPlus {
38 class TrackerSingleMarker;
39 class TrackerMultiMarker;
40 class Tracker;
41 
42 
43 
44 class ARTag2D : public ARMarkerInfo {
45 public:
46  static const int NO_PATTERN = -1;
47  static const int PATTERN = 0;
50  : belongsToPattern(NO_PATTERN) {
51  }
52  ARTag2D(const ARTag2D &tag)
53  : belongsToPattern(tag.belongsToPattern) {
54  setARMarkerInfo(tag);
55  }
56  ARTag2D(const ARMarkerInfo &tag)
57  : belongsToPattern(NO_PATTERN) {
58  setARMarkerInfo(tag);
59  }
60  void setARMarkerInfo(const ARMarkerInfo &tag) {
61  ARMarkerInfo *p = (ARMarkerInfo *) this;
62  *p = tag;
63  }
64 };
65 
66 };
67 
68 
69 class MyLogger;
70 
72 public:
73  class Parameter : public tuw_artoolkitplus::ARParamConfig{
74  public:
75  void read_param(ros::NodeHandle &n);
76  void update(const unsigned long &counter);
77  std::string node_name;
78  std::string tf_prefix;
79  std::string pattern_frame;
80  std::string pattern_file;
81  int nPattern;
86  };
89 private:
98  std::vector<ARToolKitPlus::ARTag2D> arTags2D_;
99  std::list<tf::StampedTransform> markerTransforms_;
100  std::vector<int> markerTransformsID_;
106 
107  void initTrackerSingleMarker(const sensor_msgs::CameraInfoConstPtr& camer_info_);
108  void initTrackerMultiMarker(const sensor_msgs::CameraInfoConstPtr& camer_info_);
109 
110  void updateParameterTrackerSingleMarker(const sensor_msgs::CameraInfoConstPtr& camer_info);
111  void updateParameterTrackerMultiMarker(const sensor_msgs::CameraInfoConstPtr& camer_info);
112 
113  void imageCallback(const sensor_msgs::ImageConstPtr& image_msg,
114  const sensor_msgs::CameraInfoConstPtr& info_msg);
115  void estimatePoses(const std_msgs::Header &header);
116  void publishTf();
117  void publishMarkers(const std_msgs::Header &header);
118  void publishPerceptions (const std_msgs::Header &header);
119  void generateDebugImage(cv::Mat &img);
120  void matrix2Tf(const ARFloat M[3][4], tf::Transform &transform);
121  void readParam();
122  void init();
123 
124  void callbackParameters ( tuw_artoolkitplus::ARParamConfig &config, uint32_t level );
125  dynamic_reconfigure::Server<tuw_artoolkitplus::ARParamConfig> reconfigureServer_;
126  dynamic_reconfigure::Server<tuw_artoolkitplus::ARParamConfig>::CallbackType reconfigureFnc_;
127 
128 };
129 
130 #endif // ARTOOLKITPLUS_NODE_H
std::vector< ARToolKitPlus::ARTag2D > arTags2D_
Definition: artoolkitplus.h:98
image_transport::ImageTransport imageTransport_
Definition: artoolkitplus.h:93
static const int PATTERN
Definition: artoolkitplus.h:47
ros::NodeHandle n_
Definition: artoolkitplus.h:90
ARTag2D(const ARMarkerInfo &tag)
Definition: artoolkitplus.h:56
MyLogger * logger_
std::list< tf::StampedTransform > markerTransforms_
Definition: artoolkitplus.h:99
bool update(const T &new_val, T &my_val)
ros::Publisher pub_perceptions_
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
dynamic_reconfigure::Server< tuw_artoolkitplus::ARParamConfig > reconfigureServer_
boost::shared_ptr< ARToolKitPlus::TrackerMultiMarker > trackerMultiMarker_
Definition: artoolkitplus.h:97
ARTag2D(const ARTag2D &tag)
Definition: artoolkitplus.h:52
This file should only be compiled when using ARToolKitPlus as a DLL.
Definition: ar.h:60
std::vector< int > markerTransformsID_
ros::NodeHandle n_param_
Definition: artoolkitplus.h:91
boost::shared_ptr< ARToolKitPlus::TrackerSingleMarker > trackerSingleMarker_
Definition: artoolkitplus.h:96
ros::Publisher pub_markers_
tf::TransformBroadcaster transformBroadcaster_
Definition: artoolkitplus.h:95
static const int NO_PATTERN
Definition: artoolkitplus.h:46
image_transport::CameraSubscriber cameraSubscriber_
Definition: artoolkitplus.h:94
void setARMarkerInfo(const ARMarkerInfo &tag)
Definition: artoolkitplus.h:60
const ARToolKitPlus::ARMultiMarkerInfoT * arMultiMarkerInfo_
dynamic_reconfigure::Server< tuw_artoolkitplus::ARParamConfig >::CallbackType reconfigureFnc_
float ARFloat
Definition: config.h:60
static void init(void)


tuw_artoolkitplus
Author(s): Markus Bader
autogenerated on Sun Sep 4 2016 03:24:33