Public Member Functions | Static Public Member Functions | Private Attributes
april.ros.TagPublisher Class Reference
Inheritance diagram for april.ros.TagPublisher:
Inheritance graph
[legend]

List of all members.

Public Member Functions

GraphName getDefaultNodeName ()
void onStart (final ConnectedNode node)

Static Public Member Functions

static void detectionToTagPose (TagDetection d, Transform transform, april_msgs.TagPose tag, MessageFactory msgFactory)
static BufferedImage messageToBufferedImage (sensor_msgs.Image message)
static BufferedImage messageToBufferedImageFast (sensor_msgs.Image message)
static Quaternion projectionMatrixToQuaternion (double M[][])
static Transform projectionMatrixToTransform (double M[][])
static Vector3 projectionMatrixToTranslationVector (double M[][])
static void tagPoseToVisualizationMarker (april_msgs.TagPose tag, visualization_msgs.Marker marker, double tagVisMagnification, double tagSize, MessageFactory msgFactory)
static void tagPoseToVisualizationText (april_msgs.TagPose tag, visualization_msgs.Marker marker)

Private Attributes

TagDetector detector
boolean focalLengthAvailable = false
double focalLengthX
double focalLengthY

Detailed Description

Definition at line 66 of file TagPublisher.java.


Member Function Documentation

static void april.ros.TagPublisher.detectionToTagPose ( TagDetection  d,
Transform  transform,
april_msgs.TagPose  tag,
MessageFactory  msgFactory 
) [inline, static]

Definition at line 200 of file TagPublisher.java.

Definition at line 320 of file TagPublisher.java.

static BufferedImage april.ros.TagPublisher.messageToBufferedImage ( sensor_msgs.Image  message) [inline, static]

Simple but inefficient conversion of Image message to Buffered Image.

Definition at line 78 of file TagPublisher.java.

static BufferedImage april.ros.TagPublisher.messageToBufferedImageFast ( sensor_msgs.Image  message) [inline, static]

Efficient but channel flipped conversion of Image message to Buffered Image. The image message data stores data in 3 bytes as RGBRGBR...., which is not supported directly by BufferedImage. The only 3 byte representation supported by BufferedImage is 3BYTE_BGR. Since the tags are unaffected by color, we flip the R and B channels in this efficient copy.

TODO(10/2/2012): This has a bug, and the image appears shifted. Reverting to inefficient method for now

Definition at line 114 of file TagPublisher.java.

void april.ros.TagPublisher.onStart ( final ConnectedNode  node) [inline]

Definition at line 325 of file TagPublisher.java.

static Quaternion april.ros.TagPublisher.projectionMatrixToQuaternion ( double  M[][]) [inline, static]

Compute tag orientation as a Quaternion. Tag orientation is computed from the rotational component of the projection matrix. The methodology was taken from http://en.wikipedia.org/wiki/Rotation_matrix#Quaternion

Definition at line 153 of file TagPublisher.java.

static Transform april.ros.TagPublisher.projectionMatrixToTransform ( double  M[][]) [inline, static]

Compute the entire tag pose from the projection matrix

Definition at line 195 of file TagPublisher.java.

static Vector3 april.ros.TagPublisher.projectionMatrixToTranslationVector ( double  M[][]) [inline, static]

Compute tag location in the standard ROS frame convention for optical frames. Tag location is computed from the translational component of the projection matrix. To get more details about the frame convention, see REP 103 (http://www.ros.org/reps/rep-0103.html)

Definition at line 144 of file TagPublisher.java.

static void april.ros.TagPublisher.tagPoseToVisualizationMarker ( april_msgs.TagPose  tag,
visualization_msgs.Marker  marker,
double  tagVisMagnification,
double  tagSize,
MessageFactory  msgFactory 
) [inline, static]

Definition at line 247 of file TagPublisher.java.

static void april.ros.TagPublisher.tagPoseToVisualizationText ( april_msgs.TagPose  tag,
visualization_msgs.Marker  marker 
) [inline, static]

Definition at line 303 of file TagPublisher.java.


Member Data Documentation

TagDetector april.ros.TagPublisher.detector [private]

Definition at line 70 of file TagPublisher.java.

Definition at line 68 of file TagPublisher.java.

Definition at line 72 of file TagPublisher.java.

Definition at line 73 of file TagPublisher.java.


The documentation for this class was generated from the following file:


april_tags_node
Author(s): Piyush Khandelwal
autogenerated on Mon Jan 6 2014 11:54:27