SampleMarkerCreator.cpp
Go to the documentation of this file.
2 #include "highgui.h"
3 using namespace std;
4 using namespace alvar;
5 
6 struct State {
7  IplImage *img;
8  stringstream filename;
9  double minx, miny, maxx, maxy; // top-left and bottom-right in pixel units
11 
12  // General options
13  bool prompt;
14  double units; // how many pixels per one unit
15  double marker_side_len; // marker side len in current units
16  int marker_type; // 0:MarkerData, 1:ArToolkit
17  double posx, posy; // The position of marker center in the given units
19  double margin_res;
20  bool array;
21 
22  // MarkerData specific options
25 
26  State()
27  : img(0),
28  prompt(false),
29  units(96.0/2.54), // cm assuming 96 dpi
30  marker_side_len(9.0), // 9 cm
31  marker_type(0),
32  posx(0), posy(0),
33  content_res(0), // 0 uses default
34  margin_res(0.0), // 0.0 uses default (can be n*0.5)
35  marker_data_content_type(MarkerData::MARKER_CONTENT_TYPE_NUMBER),
36  marker_data_force_strong_hamming(false)
37  {}
38  ~State() {
39  if (img) cvReleaseImage(&img);
40  }
41  void AddMarker(const char *id) {
42  std::cout<<"ADDING MARKER "<<id<<std::endl;
43  if (marker_type == 0) {
44  MarkerData md(marker_side_len, content_res, margin_res);
45  int side_len = int(marker_side_len*units+0.5);
46  if (img == 0) {
47  img = cvCreateImage(cvSize(side_len, side_len), IPL_DEPTH_8U, 1);
48  filename.str("");
49  filename<<"MarkerData";
50  minx = (posx*units) - (marker_side_len*units/2.0);
51  miny = (posy*units) - (marker_side_len*units/2.0);
52  maxx = (posx*units) + (marker_side_len*units/2.0);
53  maxy = (posy*units) + (marker_side_len*units/2.0);
54  } else {
55  double new_minx = (posx*units) - (marker_side_len*units/2.0);
56  double new_miny = (posy*units) - (marker_side_len*units/2.0);
57  double new_maxx = (posx*units) + (marker_side_len*units/2.0);
58  double new_maxy = (posy*units) + (marker_side_len*units/2.0);
59  if (minx < new_minx) new_minx = minx;
60  if (miny < new_miny) new_miny = miny;
61  if (maxx > new_maxx) new_maxx = maxx;
62  if (maxy > new_maxy) new_maxy = maxy;
63  IplImage *new_img = cvCreateImage(cvSize(int(new_maxx-new_minx+0.5), int(new_maxy-new_miny+0.5)), IPL_DEPTH_8U, 1);
64  cvSet(new_img, cvScalar(255));
65  CvRect roi = cvRect(int(minx-new_minx+0.5), int(miny-new_miny+0.5), img->width, img->height);
66  cvSetImageROI(new_img, roi);
67  cvCopy(img, new_img);
68  cvReleaseImage(&img);
69  img = new_img;
70  roi.x = int((posx*units) - (marker_side_len*units/2.0) - new_minx + 0.5);
71  roi.y = int((posy*units) - (marker_side_len*units/2.0) - new_miny + 0.5);
72  roi.width = int(marker_side_len*units+0.5); roi.height = int(marker_side_len*units+0.5);
73  cvSetImageROI(img, roi);
74  minx = new_minx; miny = new_miny;
75  maxx = new_maxx; maxy = new_maxy;
76  }
77  if (marker_data_content_type == MarkerData::MARKER_CONTENT_TYPE_NUMBER) {
78  int idi = atoi(id);
79  md.SetContent(marker_data_content_type, idi, 0);
80  if (filename.str().length()<64) filename<<"_"<<idi;
81 
82  Pose pose;
83  pose.Reset();
84  pose.SetTranslation(posx, -posy, 0);
85  multi_marker.PointCloudAdd(idi, marker_side_len, pose);
86  } else {
87  md.SetContent(marker_data_content_type, 0, id);
88  const char *p = id;
89  int counter=0;
90  filename<<"_";
91  while(*p) {
92  if (!isalnum(*p)) filename<<"_";
93  else filename<<(char)tolower(*p);
94  p++; counter++;
95  if (counter > 8) break;
96  }
97  }
98  md.ScaleMarkerToImage(img);
99  cvResetImageROI(img);
100  }
101  else if (marker_type == 1) {
102  // Create and save MarkerArtoolkit marker (Note, that this doesn't support multi markers)
103  MarkerArtoolkit md(marker_side_len, content_res, margin_res);
104  int side_len = int(marker_side_len*units+0.5);
105  if (img != 0) cvReleaseImage(&img);
106  img = cvCreateImage(cvSize(side_len, side_len), IPL_DEPTH_8U, 1);
107  filename.str("");
108  filename<<"MarkerArtoolkit";
109  md.SetContent(atoi(id));
110  filename<<"_"<<atoi(id);
111  md.ScaleMarkerToImage(img);
112  }
113  }
114  void Save() {
115  if (img) {
116  std::stringstream filenamexml;
117  filenamexml<<filename.str()<<".xml";
118  filename<<".png";
119  std::cout<<"Saving: "<<filename.str()<<std::endl;
120  cvSaveImage(filename.str().c_str(), img);
121  if (multi_marker.Size() > 1) {
122  std::cout<<"Saving: "<<filenamexml.str()<<std::endl;
123  multi_marker.Save(filenamexml.str().c_str(), alvar::FILE_FORMAT_XML);
124  }
125  }
126  }
127 } st;
128 
129 int main(int argc, char *argv[])
130 {
131  try {
132  if (argc < 2) st.prompt = true;
133  for (int i=1; i<argc; i++) {
134  if (strcmp(argv[i],"-f") == 0)
136  else if (strcmp(argv[i],"-1") == 0)
137  st.marker_data_content_type = MarkerData::MARKER_CONTENT_TYPE_STRING;
138  else if (strcmp(argv[i],"-2") == 0)
139  st.marker_data_content_type = MarkerData::MARKER_CONTENT_TYPE_FILE;
140  else if (strcmp(argv[i],"-3") == 0)
141  st.marker_data_content_type = MarkerData::MARKER_CONTENT_TYPE_HTTP;
142  else if (strcmp(argv[i],"-u") == 0)
143  st.units = atof(argv[++i]);
144  else if (strcmp(argv[i],"-uin") == 0)
145  st.units = (96.0);
146  else if (strcmp(argv[i],"-ucm") == 0)
147  st.units = (96.0/2.54);
148  else if (strcmp(argv[i],"-s") == 0)
149  st.marker_side_len = atof(argv[++i]);
150  else if (strcmp(argv[i],"-r") == 0)
151  st.content_res = atoi(argv[++i]);
152  else if (strcmp(argv[i],"-m") == 0)
153  st.margin_res = atof(argv[++i]);
154  else if (strcmp(argv[i],"-a") == 0)
155  st.marker_type = 1;
156  else if (strcmp(argv[i],"-p") == 0)
157  st.prompt = true;
158  else if (strcmp(argv[i],"-xy") == 0) {
159  st.posx = atof(argv[++i]);
160  st.posy = atof(argv[++i]);
161  }
162  else if (strcmp(argv[i],"-ar") == 0) {
163  st.array = true;
164  }
165  else st.AddMarker(argv[i]);
166  }
167 
168  // Output usage message
169  if (st.prompt) {
170  std::string filename(argv[0]);
171  filename = filename.substr(filename.find_last_of('\\') + 1);
172  std::cout << "SampleMarkerCreator" << std::endl;
173  std::cout << "===================" << std::endl;
174  std::cout << std::endl;
175  std::cout << "Description:" << std::endl;
176  std::cout << " This is an example of how to use the 'MarkerData' and 'MarkerArtoolkit'" << std::endl;
177  std::cout << " classes to generate marker images. This application can be used to" << std::endl;
178  std::cout << " generate markers and multimarker setups that can be used with" << std::endl;
179  std::cout << " SampleMarkerDetector and SampleMultiMarker." << std::endl;
180  std::cout << std::endl;
181  std::cout << "Usage:" << std::endl;
182  std::cout << " " << filename << " [options] argument" << std::endl;
183  std::cout << std::endl;
184  std::cout << " 65535 marker with number 65535" << std::endl;
185  std::cout << " -f 65535 force hamming(8,4) encoding" << std::endl;
186  std::cout << " -1 \"hello world\" marker with string" << std::endl;
187  std::cout << " -2 catalog.xml marker with file reference" << std::endl;
188  std::cout << " -3 www.vtt.fi marker with URL" << std::endl;
189  std::cout << " -u 96 use units corresponding to 1.0 unit per 96 pixels" << std::endl;
190  std::cout << " -uin use inches as units (assuming 96 dpi)" << std::endl;
191  std::cout << " -ucm use cm's as units (assuming 96 dpi) <default>" << std::endl;
192  std::cout << " -s 5.0 use marker size 5.0x5.0 units (default 9.0x9.0)" << std::endl;
193  std::cout << " -r 5 marker content resolution -- 0 uses default" << std::endl;
194  std::cout << " -m 2.0 marker margin resolution -- 0 uses default" << std::endl;
195  std::cout << " -a use ArToolkit style matrix markers" << std::endl;
196  std::cout << " -p prompt marker placements interactively from the user" << std::endl;
197  std::cout << std::endl;
198 
199  // Interactive stuff here
200  if (st.prompt) {
201  st.marker_type = 0;
202  st.marker_data_content_type = MarkerData::MARKER_CONTENT_TYPE_NUMBER;
203  std::cout<<"\nPrompt marker placements interactively"<<std::endl;
204  std::cout<<" units: "<<st.units/96.0*2.54<<" cm "<<st.units/96.0<<" inches"<<std::endl;
205  std::cout<<" marker side: "<<st.marker_side_len<<" units"<<std::endl;
206  bool loop=true;
207  std::string s;
208  int marker_id=0;
209  double posx=0.0, posy=0.0;
210  bool vert=false;
211  while(loop) {
212  std::cout<<" marker id (use -1 to end) ["<<marker_id<<"]: "; std::flush(std::cout);
213  std::getline(std::cin, s); if (s.length() > 0) marker_id=atoi(s.c_str());
214  if (marker_id < 0) break;
215  std::cout<<" x position (in current units) ["<<posx<<"]: "; std::flush(std::cout);
216  std::getline(std::cin, s); if (s.length() > 0) posx=atof(s.c_str());
217  std::cout<<" y position (in current units) ["<<posy<<"]: "; std::flush(std::cout);
218  std::getline(std::cin, s); if (s.length() > 0) posy=atof(s.c_str());
219  st.posx=posx; st.posy=posy;
220  std::stringstream ss;
221  ss<<marker_id;
222  st.AddMarker(ss.str().c_str());
223 
224  // Guess suitable marker_id and placement for the next marker
225  marker_id++;
226  if (posx <= 0) {
227  posx = int(sqrt(double(marker_id)))*st.marker_side_len*2;
228  posy = 0;
229  vert = true;
230  } else if (vert) {
231  posy += (st.marker_side_len*2);
232  if (posy >= posx) vert = false;
233  } else {
234  posx -= (st.marker_side_len*2);
235  }
236  }
237  }
238  }
239  else if(st.array) {
240  st.marker_type = 0;
241  st.marker_data_content_type = MarkerData::MARKER_CONTENT_TYPE_NUMBER;
242  int rows = 0;
243  int cols = 0;
244  double rows_distance = 0;
245  double cols_distance = 0;
246  bool column_major = 1;
247  int first_id = 0;
248  int marker_id = 0;
249  std::string s;
250  std::cout<<"\nPrompt marker placements interactively"<<std::endl;
251  std::cout<<" units: "<<st.units/96.0*2.54<<" cm "<<st.units/96.0<<" inches"<<std::endl;
252  std::cout<<" marker side: "<<st.marker_side_len<<" units"<<std::endl;
253  std::cout<<"Array rows : "; std::flush(std::cout);
254  std::getline(std::cin, s); if (s.length() > 0) rows=atoi(s.c_str());
255  std::cout<<"Array cols : "; std::flush(std::cout);
256  std::getline(std::cin, s); if (s.length() > 0) cols=atoi(s.c_str());
257  std::cout<<"Rows distance : "; std::flush(std::cout);
258  std::getline(std::cin, s); if (s.length() > 0) rows_distance=atof(s.c_str());
259  std::cout<<"Cols distance : "; std::flush(std::cout);
260  std::getline(std::cin, s); if (s.length() > 0) cols_distance=atof(s.c_str());
261  std::cout<<"Column major (1 or 0) : "; std::flush(std::cout);
262  std::getline(std::cin, s); if (s.length() > 0) column_major=atoi(s.c_str());
263  std::cout<<"First marker ID : "; std::flush(std::cout);
264  std::getline(std::cin, s); if (s.length() > 0) first_id=atoi(s.c_str());
265  if(!column_major) {
266  for(int row = 0; row<rows; row++)
267  for(int col = 0; col<cols; col++)
268  {
269  st.posy=row*rows_distance; st.posx=col*cols_distance;
270  marker_id = first_id + row*cols + col;
271  std::stringstream ss;
272  ss<<marker_id;
273  st.AddMarker(ss.str().c_str());
274  }
275  }
276  else {
277  for(int col = 0; col<cols; col++)
278  for(int row = 0; row<rows; row++)
279  {
280  st.posy=row*rows_distance; st.posx=col*cols_distance;
281  marker_id = first_id + col*rows + row;
282  std::stringstream ss;
283  ss<<marker_id;
284  st.AddMarker(ss.str().c_str());
285  }
286  }
287 
288  }
289  st.Save();
290  return 0;
291  }
292  catch (const std::exception &e) {
293  std::cout << "Exception: " << e.what() << endl;
294  }
295  catch (...) {
296  std::cout << "Exception: unknown" << std::endl;
297  }
298 }
Main ALVAR namespace.
Definition: Alvar.h:174
filename
size_t Size()
Return the number of markers added using PointCloudAdd.
Definition: MultiMarker.h:157
XmlRpcServer s
void SetContent(unsigned long _id)
Updates the marker_content by "encoding" the given parameters.
Definition: Marker.cpp:607
MarkerData contains matrix of Hamming encoded data.
Definition: Marker.h:221
Base class for using MultiMarker.
Definition: MultiMarker.h:47
MarkerData::MarkerContentType marker_data_content_type
stringstream filename
bool marker_data_force_strong_hamming
MultiMarker multi_marker
struct State st
void SetContent(MarkerContentType content_type, unsigned long id, const char *str, bool force_strong_hamming=false, bool verbose=false)
Updates the marker_content by "encoding" the given parameters.
Definition: Marker.cpp:957
void Reset()
Definition: Pose.cpp:69
Pose representation derived from the Rotation class
Definition: Pose.h:50
MarkerArtoolkit for using matrix markers similar with the ones used in ARToolkit. ...
Definition: Marker.h:194
double marker_side_len
XML file format.
Definition: FileFormat.h:66
void PointCloudAdd(int marker_id, double edge_length, Pose &pose)
Adds marker corners to 3D point cloud of multi marker.
int main(int argc, char *argv[])
This file implements a multi-marker.
void ScaleMarkerToImage(IplImage *image) const
Draw the marker filling the ROI in the given image.
Definition: Marker.cpp:342
IplImage * img
double margin_res
void SetTranslation(const CvMat *tra)
Definition: Pose.cpp:150
void AddMarker(const char *id)
bool Save(const char *fname, FILE_FORMAT format=FILE_FORMAT_DEFAULT)
Saves multi marker configuration to a text file.


ar_track_alvar
Author(s): Scott Niekum
autogenerated on Thu Jun 6 2019 19:27:24