20 #ifndef ROBOTMODEL_HPP_ 21 #define ROBOTMODEL_HPP_ 25 #include "nav_msgs/Path.h" 57 virtual bool isPositionReachable(
const geometry_msgs::Point &sourcePosition,
const geometry_msgs::Point &targetPosition) = 0;
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;
107 virtual float getDistance(
const geometry_msgs::Point &sourcePosition,
const geometry_msgs::Point &targetPosition) = 0;
void setCurrentRobotState(const RobotStatePtr ¤tRobotState)
float getBase_RotationalMovementCosts(const RobotStatePtr &targetRobotState)
float getPTU_PanMovementCosts(const RobotStatePtr &targetRobotState)
Eigen::Matrix< Precision, 3, 1 > SimpleVector3
virtual float getDistance(const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition)=0
float getPTU_TiltMovementCosts(const RobotStatePtr &targetRobotState)
virtual geometry_msgs::Pose getRobotPose()=0
boost::shared_ptr< RobotModel > RobotModelPtr
Definition for the shared pointer type of the class.
this namespace contains all generally usable classes.
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 ...
float getBase_TranslationalMovementCosts(const RobotStatePtr &targetRobotState)
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()
virtual ~RobotModel()
the destructor of the RobotModel object
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
RobotStatePtr mCurrentRobotState
virtual bool isPoseReachable(const robot_model_services::SimpleVector3 &position, const robot_model_services::SimpleQuaternion &orientation)=0
RobotModel()
the constructor of the RobotModel object
RobotModel generalizes a robot model.