Classes | Defines | Functions
calibration.hpp File Reference

Allows for calibration of the ceiling cameras using AR markers. More...

#include <ros/ros.h>
#include <ar_track_alvar_msgs/AlvarMarkers.h>
#include <geometry_msgs/Pose.h>
#include <vector>
#include <string>
#include <tf/transform_broadcaster.h>
Include dependency graph for calibration.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  calibration
 The main calibration object. More...

Defines

#define CAMERA_LINK_NAME   "calibration_ceiling_camera_"
#define FIXED_LINK_NAME   "fixed_calibration_marker_"
#define URDF   "ceiling.urdf.xacro"

Functions

int main (int argc, char **argv)

Detailed Description

Allows for calibration of the ceiling cameras using AR markers.

The calibration node uses AR tags in a fixed world location to determine the location of the cameras. These locations are then printed to the terminal for use in a URDF. It is assumed the marker tags are published in the same frame as the camera.

Author:
Russell Toris, WPI - russell.toris@gmail.com
Date:
August 22, 2014

Definition in file calibration.hpp.


Define Documentation

#define CAMERA_LINK_NAME   "calibration_ceiling_camera_"

Definition at line 39 of file calibration.hpp.

#define FIXED_LINK_NAME   "fixed_calibration_marker_"

The link name of the AR markers.

The link name of the cameras.

#define URDF   "ceiling.urdf.xacro"

The URDF file to write.

Definition at line 27 of file calibration.hpp.


Function Documentation

int main ( int  argc,
char **  argv 
)

Creates and runs the calibration node.

Parameters:
argcargument count that is passed to ros::init
argvarguments that are passed to ros::init
Returns:
EXIT_SUCCESS if the node runs correctly

Definition at line 254 of file calibration.cpp.



rail_ceiling
Author(s): Russell Toris , David Kent
autogenerated on Sat Jun 8 2019 20:39:22