Public Member Functions | Private Attributes
rail::pick_and_place::graspdb::Orientation Class Reference

Quaternion orientation information. More...

#include <Orientation.h>

List of all members.

Public Member Functions

double getW () const
 W value accessor.
double getX () const
 X value accessor.
double getY () const
 Y value accessor.
double getZ () const
 Z value accessor.
 Orientation (const double x=0, const double y=0, const double z=0, const double w=0)
 Create a new Orientation.
 Orientation (const geometry_msgs::Quaternion &quaternion)
 Create a new Orientation.
 Orientation (const tf2::Quaternion &quaternion)
 Create a new Orientation.
void setW (const double w)
 W value mutator.
void setX (const double x)
 X value mutator.
void setY (const double y)
 Y value mutator.
void setZ (const double z)
 Z value mutator.
geometry_msgs::Quaternion toROSQuaternionMessage () const
tf2::Matrix3x3 toTF2Matrix3x3 () const
tf2::Quaternion toTF2Quaternion () const

Private Attributes

double w_
double x_
double y_
double z_

Detailed Description

Quaternion orientation information.

An orientation simply contains x, y, z, and w values. This class is useful for internal data management within the graspdb library. Convenience functions are added for use with ROS messages.

Definition at line 37 of file Orientation.h.


Constructor & Destructor Documentation

Orientation::Orientation ( const double  x = 0,
const double  y = 0,
const double  z = 0,
const double  w = 0 
)

Create a new Orientation.

Creates a new Orientation with the given x, y, z, and w values (defaults are 0).

Parameters:
xThe x value (default of 0).
yThe y value (default of 0).
zThe z value (default of 0).
wThe w value (default of 0).

Definition at line 18 of file Orientation.cpp.

Orientation::Orientation ( const geometry_msgs::Quaternion &  quaternion)

Create a new Orientation.

Creates a new Orientation with the given x, y, z, and w values from the ROS Quaternion message.

Parameters:
pointThe ROS Quaternion message to extract values from.

Definition at line 27 of file Orientation.cpp.

Orientation::Orientation ( const tf2::Quaternion quaternion)

Create a new Orientation.

Creates a new Orientation with the given x, y, z, and w values from the ROS tf2 Quaternion.

Parameters:
pointThe ROS tf2 Quaternion to extract values from.

Definition at line 36 of file Orientation.cpp.


Member Function Documentation

double Orientation::getW ( ) const

W value accessor.

Get the w value of this Position.

Returns:
The w value.

Definition at line 80 of file Orientation.cpp.

double Orientation::getX ( ) const

X value accessor.

Get the x value of this Position.

Returns:
The x value.

Definition at line 50 of file Orientation.cpp.

double Orientation::getY ( ) const

Y value accessor.

Get the y value of this Position.

Returns:
The y value.

Definition at line 60 of file Orientation.cpp.

double Orientation::getZ ( ) const

Z value accessor.

Get the z value of this Position.

Returns:
The z value.

Definition at line 70 of file Orientation.cpp.

void Orientation::setW ( const double  w)

W value mutator.

Set the w value of this Position.

Parameters:
wThe new w value.

Definition at line 75 of file Orientation.cpp.

void Orientation::setX ( const double  x)

X value mutator.

Set the x value of this Position.

Parameters:
xThe new x value.

Definition at line 45 of file Orientation.cpp.

void Orientation::setY ( const double  y)

Y value mutator.

Set the y value of this Position.

Parameters:
yThe new y value.

Definition at line 55 of file Orientation.cpp.

void Orientation::setZ ( const double  z)

Z value mutator.

Set the z value of this Position.

Parameters:
zThe new z value.

Definition at line 65 of file Orientation.cpp.

geometry_msgs::Quaternion Orientation::toROSQuaternionMessage ( ) const

Converts this Orientation object into a ROS Quaternion message.

Returns:
The ROS Quaternion message with this orientation data.

Definition at line 85 of file Orientation.cpp.

Converts this Orientation object into a ROS tf2 Matrix3x3.

Returns:
The ROS tf2 Matrix3x3 with this orientation data.

Definition at line 101 of file Orientation.cpp.

Converts this Orientation object into a ROS tf2 Quaternion.

Returns:
The ROS tf2 Quaternion with this orientation data.

Definition at line 95 of file Orientation.cpp.


Member Data Documentation

Definition at line 165 of file Orientation.h.

Members to hold values.

Definition at line 165 of file Orientation.h.

Definition at line 165 of file Orientation.h.

Definition at line 165 of file Orientation.h.


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


graspdb
Author(s): Russell Toris
autogenerated on Sun Mar 6 2016 11:39:00