IKRatingModule.h
Go to the documentation of this file.
1 
20 #ifndef IKRATINGMODULE_H
21 #define IKRATINGMODULE_H
22 
23 #include "nav_msgs/Path.h"
24 
25 namespace robot_model_services {
35  public:
40 
44  virtual ~IKRatingModule();
45 
54  virtual double getPanAngleRating(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition, double sourceRotationBase, double targetRotationBase) = 0;
55  };
56 
61 }
62 
63 #endif /* IKRATINGMODULE_H */
IKRatingModule is a generalization for the rating of the inverse kinematic parameters.
IKRatingModule()
constructor of the IKRatingModule object
boost::shared_ptr< IKRatingModule > IKRatingModulePtr
Definition for the shared pointer type of the class.
this namespace contains all generally usable classes.
Definition: DebugHelper.hpp:27
virtual double getPanAngleRating(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition, double sourceRotationBase, double targetRotationBase)=0
virtual ~IKRatingModule()
destructor of the IKRatingModule object.


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