RobotModel.hpp
Go to the documentation of this file.
1 
20 #ifndef ROBOTMODEL_HPP_
21 #define ROBOTMODEL_HPP_
22 
25 #include "nav_msgs/Path.h"
26 
27 namespace robot_model_services {
28 
29  // TODO costs -> inverse costs
37  class RobotModel {
38  private:
40  public:
44  RobotModel();
45 
49  virtual ~RobotModel();
50 
55  virtual bool isPoseReachable(const robot_model_services::SimpleVector3 &position, const robot_model_services::SimpleQuaternion &orientation) = 0;
56 
57  virtual bool isPositionReachable(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition) = 0;
58 
62  virtual nav_msgs::Path getNavigationPath(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition, double sourceRotationBase, double targetRotationBase) = 0;
63  virtual nav_msgs::Path getNavigationPath(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition) = 0;
64 
72 
80  virtual RobotStatePtr calculateRobotState(const RobotStatePtr &sourceRobotState, const SimpleVector3 &position, const SimpleQuaternion &orientation) = 0;
81 
86  float getBase_TranslationalMovementCosts(const RobotStatePtr &targetRobotState);
87 
93  virtual float getBase_TranslationalMovementCosts(const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState) = 0;
94 
95  float getPTU_TiltMovementCosts(const RobotStatePtr &targetRobotState);
96 
97  virtual float getPTU_TiltMovementCosts(const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState) = 0;
98 
99  float getPTU_PanMovementCosts(const RobotStatePtr &targetRobotState);
100 
101  virtual float getPTU_PanMovementCosts(const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState) = 0;
102 
103  float getBase_RotationalMovementCosts(const RobotStatePtr &targetRobotState);
104 
105  virtual float getBase_RotationalMovementCosts(const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState) = 0;
106 
107  virtual float getDistance(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition) = 0;
108 
109  virtual geometry_msgs::Pose getRobotPose() = 0;
110 
111  virtual geometry_msgs::Pose getCameraPose() = 0;
112 
116  virtual geometry_msgs::Pose calculateCameraPose(const RobotStatePtr &sourceRobotState) = 0;
117 
121  void setCurrentRobotState(const RobotStatePtr &currentRobotState);
122 
127  };
128 
133 }
134 
135 #endif /* ROBOTMODEL_HPP_ */
void setCurrentRobotState(const RobotStatePtr &currentRobotState)
Definition: RobotModel.cpp:46
float getBase_RotationalMovementCosts(const RobotStatePtr &targetRobotState)
Definition: RobotModel.cpp:42
float getPTU_PanMovementCosts(const RobotStatePtr &targetRobotState)
Definition: RobotModel.cpp:34
Eigen::Matrix< Precision, 3, 1 > SimpleVector3
Definition: typedef.hpp:50
virtual float getDistance(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition)=0
float getPTU_TiltMovementCosts(const RobotStatePtr &targetRobotState)
Definition: RobotModel.cpp:38
virtual geometry_msgs::Pose getRobotPose()=0
boost::shared_ptr< RobotModel > RobotModelPtr
Definition for the shared pointer type of the class.
Definition: RobotModel.hpp:132
this namespace contains all generally usable classes.
Definition: DebugHelper.hpp:27
RobotStatePtr calculateRobotState(const robot_model_services::SimpleVector3 &position, const robot_model_services::SimpleQuaternion &orientation)
calculates the target robot state by assuming the saved current state of the roboter as source state ...
Definition: RobotModel.cpp:26
float getBase_TranslationalMovementCosts(const RobotStatePtr &targetRobotState)
Definition: RobotModel.cpp:30
virtual bool isPositionReachable(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition)=0
virtual nav_msgs::Path getNavigationPath(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition, double sourceRotationBase, double targetRotationBase)=0
RobotStatePtr getCurrentRobotState()
Definition: RobotModel.cpp:50
virtual ~RobotModel()
the destructor of the RobotModel object
Definition: RobotModel.cpp:24
virtual geometry_msgs::Pose getCameraPose()=0
virtual geometry_msgs::Pose calculateCameraPose(const RobotStatePtr &sourceRobotState)=0
Uses a given RobotState to calculate the camera frame.
Eigen::Quaternion< Precision > SimpleQuaternion
Definition: typedef.hpp:64
virtual bool isPoseReachable(const robot_model_services::SimpleVector3 &position, const robot_model_services::SimpleQuaternion &orientation)=0
RobotModel()
the constructor of the RobotModel object
Definition: RobotModel.cpp:23
RobotModel generalizes a robot model.
Definition: RobotModel.hpp:37


asr_robot_model_services
Author(s): Aumann Florian, Borella Jocelyn, Heller Florian, Meißner Pascal, Schleicher Ralf, Stöckle Patrick, Stroh Daniel, Trautmann Jeremias, Walter Milena, Wittenbeck Valerij
autogenerated on Mon Jun 10 2019 12:49:59