Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

marker creators utility #61

Open
wants to merge 13 commits into
base: melodic-devel
Choose a base branch
from
3 changes: 0 additions & 3 deletions README

This file was deleted.

39 changes: 39 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
See [ROS wiki](http://wiki.ros.org/ar_track_alvar) for the users document.

# <img src="ar_track_alvar/readme_images/MarkerData_0.png" width="50"> ar_track_alvar

### Convention
We always consider the orientation shown below as the reference orientation of the mark. You can distinguish this orientation with the two empty squares represented by the red box on this example.

<img src="ar_track_alvar/readme_images/MarkerRef.png" width="100">

When you create a new tag, an XML file will be generated with it. On this file you will find the description of the corners of each tag like this one:
```
<corner x="-2" y="-2" z="0" />
<corner x="2" y="-2" z="0" />
<corner x="2" y="2" z="0" />
<corner x="-2" y="2" z="0" />
```
If you want to manually modify this file, assume that the corners are as follows.

<img src="ar_track_alvar/readme_images/corners.png" width="100">

Finally, we will consider the following 3D marker for each tag.

<img src="ar_track_alvar/readme_images/MarkerAxes.png" width="100">

### Identifiers
Each tags represents an identifier. In these nodes, the identifiers are numbers between 0 and 65535.
The identifiers used to create a tag will be specified in the name of the PNG, a generated XML file.

e.g :
For a single marker :
```
MarkerData_0.png
MarkerData_0.xml
```
For a cube :
```
MarkerData_1_2_3_4_5_6.png
MarkerData_1_2_3_4_5_6.xml
```
15 changes: 12 additions & 3 deletions ar_track_alvar/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ catkin_package(
dynamic_reconfigure
)

include_directories(include
include_directories(include
${catkin_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${TinyXML_INCLUDE_DIRS}
Expand All @@ -77,6 +77,7 @@ set(GENCPP_DEPS ar_track_alvar_msgs_gencpp std_msgs_gencpp sensor_msgs_gencpp ge
add_library(ar_track_alvar
src/Camera.cpp
src/CaptureDevice.cpp
src/Color.cpp
src/Pose.cpp
src/Marker.cpp
src/MarkerDetector.cpp
Expand Down Expand Up @@ -145,6 +146,14 @@ add_executable(createMarker src/SampleMarkerCreator.cpp)
target_link_libraries(createMarker ar_track_alvar ${catkin_LIBRARIES})
add_dependencies(createMarker ${PROJECT_NAME}_gencpp ${GENCPP_DEPS})

add_executable(createCube src/CubeCreator.cpp)
target_link_libraries(createCube ar_track_alvar ${catkin_LIBRARIES})
add_dependencies(createCube ${PROJECT_NAME}_gencpp ${GENCPP_DEPS})

add_executable(createDeportedMarker src/DeportedMarkerCreator.cpp)
target_link_libraries(createDeportedMarker ar_track_alvar ${catkin_LIBRARIES})
add_dependencies(createDeportedMarker ${PROJECT_NAME}_gencpp ${GENCPP_DEPS})

install(TARGETS ${ALVAR_TARGETS} ${KINECT_FILTERING_TARGETS}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
Expand All @@ -161,12 +170,12 @@ install(DIRECTORY launch bundles

if (CATKIN_ENABLE_TESTING)
find_package(catkin REQUIRED COMPONENTS roslaunch rostest)

file(GLOB LAUNCH_FILES launch/*.launch test/*.test)
foreach(LAUNCH_FILE ${LAUNCH_FILES})
roslaunch_add_file_check(${LAUNCH_FILE} USE_TEST_DEPENDENCIES)
endforeach()

catkin_download_test_data(
${PROJECT_NAME}_4markers_tork.bag
http://download.ros.org/data/ar_track_alvar/ar_track_alvar_4markers_tork_2017-02-08-11-21-14.bag
Expand Down
76 changes: 76 additions & 0 deletions ar_track_alvar/Marker_creation.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
# <img src="ar_track_alvar/readme_images/MarkerData_0.png" width="50"> Marker creation

## Deported marker generation
A tag called "Deported marker" is a single 2D marker that refers to a position offset to its own.

### Usage
```
$ rosrun ar_track_alvar createDeportedMarker
```
First, enter the ID you want to use. The identifiers are chosen by you between 0 and 65535. Be careful, all the tags (deported or not), **must have a different identifier**, that is why the node can automatically increases the identifiers of tags.

The reference unit use on this node is the centimeter but you can change it with option '-u'.
After specifying the size of the tag, you can describe the position offset on X, Y, and Z.

<img src="readme_images/MarkerFlagExample.png" width="150">

### Tips
- Always take 1 cm margin on the size of your tag to keep a white border for better detection.
- Be carefull about the tag orientation

## Cube generation
A tag called "Cube" is composed of 6 tags assembled in a cube. Only the master tag will be displayed regardless of the orientation of the cube.

### Usage
```
$ rosrun ar_track_alvar createCube
```
First, enter the ID you want to use. The identifiers are chosen by you between 0 and 65535. Be careful, all the tags (deported or not), **must have a different identifier**, that is why the node can automatically increases the identifiers of tags (**+6 per cube**). The master identifier will always be the first one present in the PNG and XML files name.

The reference unit use on this node is the centimeter but you can change it with option '-u'.
After specifying the size of the tag, specified the size of the cube and ... this is all you need to do !!

The node will generate a pattern that you have to cut and stick.
:exclamation: Once the PNG is printed, do not cut all markers independently, but only the entire pattern.

### Tips
- Always take 1 cm margin on the size of your tag to keep a white border for better detection.
- If you have to cut all the tags of the pattern, make sure to stick them with the correct order and orientation.

## Colors

For deported markers and cubes, you can add color. Six colors are available in addition to black !!

<img src="readme_images/colors.png" width="600">

## Options

Several options can be added when you run the generators.

### For deported markers

- **65535** marker with number 65535
- **-1 \"hello world\"** marker with string
- **-2 catalog.xml** marker with file reference
- **-3 http://wiki.ros.org** marker with URL
- **-u 96** use units corresponding to 1.0 unit per 96 pixels
- **-uin** use inches as units (assuming 96 dpi)
- **-ucm** use cm's as units (assuming 96 dpi) <default>
- **-s 5.0** use marker size 5.0x5.0 units (default 9.0x9.0)
- **-r 5** marker content resolution -- 0 uses default
- **-m 2.0** marker margin resolution -- 0 uses default
- **-p** prompt marker placements interactively from the user
- **-c B** marker color : B:blue R:red G:green P:pink S:sky Y:yellow -- default black

### For cubes

- **65535** marker with number 65535
- **-u 96** use units corresponding to 1.0 unit per 96 pixels
- **-uin** use inches as units (assuming 96 dpi)
- **-ucm** use cm's as units (assuming 96 dpi) <default>
- **-sm 5.0** use marker size 5.0x5.0 units (default 9.0x9.0)
- **-sc 5.0** use cube size 5.0x5.0 units (default 9.0x9.0)
- **-r 5** marker content resolution -- 0 uses default
- **-m 1.0** marker margin resolution -- 0 uses default
- **-p** prompt marker placements interactively from the user
- **-c B** cube color : B:blue R:red G:green P:pink S:sky Y:yellow -- default black
24 changes: 24 additions & 0 deletions ar_track_alvar/include/ar_track_alvar/Color.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
#include "ar_track_alvar/MultiMarker.h"
#include "highgui.h"
using namespace std;
using namespace alvar;

namespace col
{
enum color_t
{
COLOR_BLACK,
COLOR_RED,
COLOR_BLUE,
COLOR_GREEN,
COLOR_YELLOW,
COLOR_PINK,
COLOR_SKY
};

color_t get_color(char color_name);

unsigned char get_color(color_t p_color);

void change_color(IplImage *p_img, unsigned char p_color = 0);
}
44 changes: 22 additions & 22 deletions ar_track_alvar/include/ar_track_alvar/Marker.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,17 +58,17 @@ namespace alvar {
bool UpdateContentBasic(std::vector<Point<CvPoint2D64f> > &_marker_corners_img, IplImage *gray, Camera *cam, int frame_no = 0);

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
bool valid;

/** \brief Compares the marker corners with the previous match.
/** \brief Compares the marker corners with the previous match.
*
* In some cases the tracking of the marker can be accepted solely based on this.
* Returns the marker orientation and an error value describing the pixel error
* Returns the marker orientation and an error value describing the pixel error
* relative to the marker diameter.
*/
void CompareCorners(std::vector<Point<CvPoint2D64f> > &_marker_corners_img, int *orientation, double *error);
/** \brief Compares the marker corners with the previous match.
/** \brief Compares the marker corners with the previous match.
*/
void CompareContent(std::vector<Point<CvPoint2D64f> > &_marker_corners_img, IplImage *gray, Camera *cam, int *orientation) const;
/** \brief Updates the \e marker_content from the image using \e Homography
Expand All @@ -77,11 +77,11 @@ namespace alvar {
/** \brief Updates the markers \e pose estimation
*/
void UpdatePose(std::vector<Point<CvPoint2D64f> > &_marker_corners_img, Camera *cam, int orientation, int frame_no = 0, bool update_pose = true);
/** \brief Decodes the marker content. Please call \e UpdateContent before this.
/** \brief Decodes the marker content. Please call \e UpdateContent before this.
* This virtual method is meant to be implemented by heirs.
*/
virtual bool DecodeContent(int *orientation);

/** \brief Returns the content as a matrix
*/
CvMat *GetContent() const {
Expand All @@ -101,10 +101,10 @@ namespace alvar {
/** \brief Get edge length (to support different size markers */
double GetMarkerEdgeLength() const { return edge_length; }
/** \brief Destructor */
~Marker();
/** \brief Default constructor
virtual ~Marker();
/** \brief Default constructor
* \param _edge_length Length of the marker's edge in whatever units you are using (e.g. cm)
* \param _res The marker content resolution in pixels (this is actually
* \param _res The marker content resolution in pixels (this is actually
* \param _margin The marker margin resolution in pixels (The actual captured marker image has pixel resolution of _margin+_res+_margin)
*/
Marker(double _edge_length = 0, int _res = 0, double _margin = 0);
Expand All @@ -119,7 +119,7 @@ namespace alvar {
virtual void SetId(unsigned long _id) {};

/**
* Returns the resolution (the number of square rows and columns) of the
* Returns the resolution (the number of square rows and columns) of the
* marker content area. The total number of content squares within the
* content area is resolution*resolution.
*/
Expand Down Expand Up @@ -168,7 +168,7 @@ namespace alvar {
CvMat *marker_content;

public:

/** \brief Marker color points in marker coordinates */
std::vector<PointDouble> marker_points;
/** \brief Marker corners in marker coordinates */
Expand Down Expand Up @@ -198,11 +198,11 @@ namespace alvar {
double default_margin() { return 1.5; }

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
/** \brief \e MarkerArtoolkit supports only 'id' as data type */
unsigned long id;
/** \brief Constructor */
MarkerArtoolkit(double _edge_length = 0, int _res = 0, double _margin = 0) :
MarkerArtoolkit(double _edge_length = 0, int _res = 0, double _margin = 0) :
Marker(_edge_length, (_res?_res:3), (_margin?_margin:1.5))
{
}
Expand Down Expand Up @@ -230,7 +230,7 @@ namespace alvar {
bool DetectResolution(std::vector<Point<CvPoint2D64f> > &_marker_corners_img, IplImage *gray, Camera *cam);

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
static const int MAX_MARKER_STRING_LEN=2048;
enum MarkerContentType {
MARKER_CONTENT_TYPE_NUMBER,
Expand All @@ -242,16 +242,16 @@ namespace alvar {

/** \brief \e MarkerData content can be presented either as number (\e MARKER_CONTENT_TYPE_NUMBER) or string */
union {
unsigned long id;
char str[MAX_MARKER_STRING_LEN];
unsigned long id;
char str[MAX_MARKER_STRING_LEN];
} data;

/** \brief Default constructor
/** \brief Default constructor
* \param _edge_length Length of the marker's edge in whatever units you are using (e.g. cm)
* \param _res The marker content resolution in pixels (this is actually
* \param _res The marker content resolution in pixels (this is actually
* \param _margin The marker margin resolution in pixels (The actual captured marker image has pixel resolution of _margin+_res+_margin)
*/
MarkerData(double _edge_length = 0, int _res = 0, double _margin = 0) :
MarkerData(double _edge_length = 0, int _res = 0, double _margin = 0) :
Marker(_edge_length, _res, (_margin?_margin:2))
{
}
Expand All @@ -260,11 +260,11 @@ namespace alvar {
/** \brief Set the ID */
void SetId(unsigned long _id) { data.id = _id; }
/** \brief Updates the \e marker_content from the image using \e Homography
* Compared to the basic implementation in \e Marker this will also detect the marker
* Compared to the basic implementation in \e Marker this will also detect the marker
* resolution automatically when the marker resolution is specified to be 0.
*/
virtual bool UpdateContent(std::vector<Point<CvPoint2D64f> > &_marker_corners_img, IplImage *gray, Camera *cam, int frame_no = 0);
/** \brief \e DecodeContent should be called after \e UpdateContent to fill \e content_type, \e decode_error and \e data
/** \brief \e DecodeContent should be called after \e UpdateContent to fill \e content_type, \e decode_error and \e data
*/
bool DecodeContent(int *orientation);
/** \brief Updates the \e marker_content by "encoding" the given parameters
Expand Down Expand Up @@ -293,7 +293,7 @@ namespace alvar {
template<typename T>
class ALVAR_EXPORT MarkerIteratorImpl : public MarkerIterator {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
typedef typename std::vector<T, Eigen::aligned_allocator<T> >::const_iterator const_iterator_aligntype;
MarkerIteratorImpl(const_iterator_aligntype i) : _begin(i), _i(i) {
_data = this;
Expand Down
22 changes: 17 additions & 5 deletions ar_track_alvar/include/ar_track_alvar/MultiMarker.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,9 +55,9 @@ class ALVAR_EXPORT MultiMarker {
bool LoadXML(const char* fname);

public:
// The marker information is stored in all three tables using
// the indices-order given in constructor.
// One idea is that the same 'pointcloud' could contain feature
// The marker information is stored in all three tables using
// the indices-order given in constructor.
// One idea is that the same 'pointcloud' could contain feature
// points after marker-corner-points. This way they would be
// optimized simultaneously with marker corners...
std::map<int, CvPoint3D64f> pointcloud;
Expand All @@ -71,7 +71,7 @@ class ALVAR_EXPORT MultiMarker {
double _GetPose(MarkerIterator &begin, MarkerIterator &end, Camera* cam, Pose& pose, IplImage* image);

int _SetTrackMarkers(MarkerDetectorImpl &marker_detector, Camera* cam, Pose& pose, IplImage *image);
int master_id; //The id of the first marker specified in the XML file
int master_id; //The id of the first marker specified in the XML file


/** \brief Resets the multi marker. */
Expand All @@ -97,7 +97,7 @@ class ALVAR_EXPORT MultiMarker {
/** \brief Default constructor */
MultiMarker() {}

/** \brief Calculates the pose of the camera from multi marker. Method uses the true 3D coordinates of
/** \brief Calculates the pose of the camera from multi marker. Method uses the true 3D coordinates of
markers to get the initial pose and then optimizes it by minimizing the reprojection error.

\param markers Vector of markers seen by camera.
Expand Down Expand Up @@ -143,6 +143,18 @@ class ALVAR_EXPORT MultiMarker {
*/
void PointCloudAdd(int marker_id, double edge_length, Pose &pose);

/** \brief Translate all corner in 3D space
\param marker_id Id of the marker to be translate.
\param x,y,z Values of translation
*/
void PointCloudTranslate(int marker_id, double x, double y, double z);

/**\brief Rotate all corner in 3D space
\param marker_id Id of the marker to be rotate.
\param rot matrix of rotation
*/
void PointCloudRotate(int marker_id, int rot[9]);

/** \brief Copies the 3D point cloud from other multi marker object.
*/
void PointCloudCopy(const MultiMarker *m);
Expand Down
Loading