Position.h
Go to the documentation of this file.
00001 
00012 #ifndef RAIL_PICK_AND_PLACE_GRASPDB_POSITION_H_
00013 #define RAIL_PICK_AND_PLACE_GRASPDB_POSITION_H_
00014 
00015 // ROS
00016 #include <geometry_msgs/Point.h>
00017 #include <geometry_msgs/Vector3.h>
00018 #include <tf2/LinearMath/Vector3.h>
00019 
00020 // C++ Standard Library
00021 #include <string>
00022 
00023 namespace rail
00024 {
00025 namespace pick_and_place
00026 {
00027 namespace graspdb
00028 {
00029 
00037 class Position
00038 {
00039 public:
00049   Position(const double x = 0, const double y = 0, const double z = 0);
00050 
00058   Position(const geometry_msgs::Point &point);
00059 
00067   Position(const geometry_msgs::Vector3 &v);
00068 
00076   Position(const tf2::Vector3 &v);
00077 
00085   void setX(const double x);
00086 
00094   double getX() const;
00095 
00103   void setY(const double y);
00104 
00112   double getY() const;
00113 
00121   void setZ(const double z);
00122 
00130   double getZ() const;
00131 
00137   geometry_msgs::Point toROSPointMessage() const;
00138 
00144   geometry_msgs::Vector3 toROSVector3Message() const;
00145 
00151   tf2::Vector3 toTF2Vector3() const;
00152 
00153 private:
00155   double x_, y_, z_;
00156 };
00157 
00158 }
00159 }
00160 }
00161 
00162 #endif


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