Orientation.cpp
Go to the documentation of this file.
00001 
00012 // graspdb
00013 #include "graspdb/Orientation.h"
00014 
00015 using namespace std;
00016 using namespace rail::pick_and_place::graspdb;
00017 
00018 Orientation::Orientation(const double x, const double y, const double z, const double w)
00019 {
00020   // set orientation data
00021   x_ = x;
00022   y_ = y;
00023   z_ = z;
00024   w_ = w;
00025 }
00026 
00027 Orientation::Orientation(const geometry_msgs::Quaternion &quaternion)
00028 {
00029   // copy position data
00030   x_ = quaternion.x;
00031   y_ = quaternion.y;
00032   z_ = quaternion.z;
00033   w_ = quaternion.w;
00034 }
00035 
00036 Orientation::Orientation(const tf2::Quaternion &quaternion)
00037 {
00038   // copy position data
00039   x_ = quaternion.getX();
00040   y_ = quaternion.getY();
00041   z_ = quaternion.getZ();
00042   w_ = quaternion.getW();
00043 }
00044 
00045 void Orientation::setX(const double x)
00046 {
00047   x_ = x;
00048 }
00049 
00050 double Orientation::getX() const
00051 {
00052   return x_;
00053 }
00054 
00055 void Orientation::setY(const double y)
00056 {
00057   y_ = y;
00058 }
00059 
00060 double Orientation::getY() const
00061 {
00062   return y_;
00063 }
00064 
00065 void Orientation::setZ(const double z)
00066 {
00067   z_ = z;
00068 }
00069 
00070 double Orientation::getZ() const
00071 {
00072   return z_;
00073 }
00074 
00075 void Orientation::setW(const double w)
00076 {
00077   w_ = w;
00078 }
00079 
00080 double Orientation::getW() const
00081 {
00082   return w_;
00083 }
00084 
00085 geometry_msgs::Quaternion Orientation::toROSQuaternionMessage() const
00086 {
00087   geometry_msgs::Quaternion q;
00088   q.x = x_;
00089   q.y = y_;
00090   q.z = z_;
00091   q.w = w_;
00092   return q;
00093 }
00094 
00095 tf2::Quaternion Orientation::toTF2Quaternion() const
00096 {
00097   tf2::Quaternion q(x_, y_, z_, w_);
00098   return q;
00099 }
00100 
00101 tf2::Matrix3x3 Orientation::toTF2Matrix3x3() const
00102 {
00103   tf2::Quaternion q = this->toTF2Quaternion();
00104   tf2::Matrix3x3 m(q);
00105   return m;
00106 }


graspdb
Author(s): Russell Toris
autogenerated on Thu Jun 6 2019 19:44:01