Go to the documentation of this file.00001
00020 #ifndef ROBOTMODEL_HPP_
00021 #define ROBOTMODEL_HPP_
00022
00023 #include <robot_model_services/robot_model/RobotState.hpp>
00024 #include <robot_model_services/typedef.hpp>
00025 #include "nav_msgs/Path.h"
00026
00027 namespace robot_model_services {
00028
00029
00037 class RobotModel {
00038 private:
00039 RobotStatePtr mCurrentRobotState;
00040 public:
00044 RobotModel();
00045
00049 virtual ~RobotModel();
00050
00055 virtual bool isPoseReachable(const robot_model_services::SimpleVector3 &position, const robot_model_services::SimpleQuaternion &orientation) = 0;
00056
00057 virtual bool isPositionReachable(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition) = 0;
00058
00062 virtual nav_msgs::Path getNavigationPath(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition, double sourceRotationBase, double targetRotationBase) = 0;
00063 virtual nav_msgs::Path getNavigationPath(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition) = 0;
00064
00071 RobotStatePtr calculateRobotState(const robot_model_services::SimpleVector3 &position, const robot_model_services::SimpleQuaternion &orientation);
00072
00080 virtual RobotStatePtr calculateRobotState(const RobotStatePtr &sourceRobotState, const SimpleVector3 &position, const SimpleQuaternion &orientation) = 0;
00081
00086 float getBase_TranslationalMovementCosts(const RobotStatePtr &targetRobotState);
00087
00093 virtual float getBase_TranslationalMovementCosts(const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState) = 0;
00094
00095 float getPTU_TiltMovementCosts(const RobotStatePtr &targetRobotState);
00096
00097 virtual float getPTU_TiltMovementCosts(const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState) = 0;
00098
00099 float getPTU_PanMovementCosts(const RobotStatePtr &targetRobotState);
00100
00101 virtual float getPTU_PanMovementCosts(const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState) = 0;
00102
00103 float getBase_RotationalMovementCosts(const RobotStatePtr &targetRobotState);
00104
00105 virtual float getBase_RotationalMovementCosts(const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState) = 0;
00106
00107 virtual float getDistance(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition) = 0;
00108
00109 virtual geometry_msgs::Pose getRobotPose() = 0;
00110
00111 virtual geometry_msgs::Pose getCameraPose() = 0;
00112
00116 virtual geometry_msgs::Pose calculateCameraPose(const RobotStatePtr &sourceRobotState) = 0;
00117
00121 void setCurrentRobotState(const RobotStatePtr ¤tRobotState);
00122
00126 RobotStatePtr getCurrentRobotState();
00127 };
00128
00132 typedef boost::shared_ptr<RobotModel> RobotModelPtr;
00133 }
00134
00135 #endif
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 Sat Jun 8 2019 18:24:52