Public Member Functions | Private Attributes | List of all members
robot_model_services::RobotModel Class Referenceabstract

RobotModel generalizes a robot model. More...

#include <RobotModel.hpp>

Inheritance diagram for robot_model_services::RobotModel:
Inheritance graph
[legend]

Public Member Functions

virtual geometry_msgs::Pose calculateCameraPose (const RobotStatePtr &sourceRobotState)=0
 Uses a given RobotState to calculate the camera frame. More...
 
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 More...
 
virtual RobotStatePtr calculateRobotState (const RobotStatePtr &sourceRobotState, const SimpleVector3 &position, const SimpleQuaternion &orientation)=0
 calculates the target robot state More...
 
float getBase_RotationalMovementCosts (const RobotStatePtr &targetRobotState)
 
virtual float getBase_RotationalMovementCosts (const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState)=0
 
float getBase_TranslationalMovementCosts (const RobotStatePtr &targetRobotState)
 
virtual float getBase_TranslationalMovementCosts (const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState)=0
 
virtual geometry_msgs::Pose getCameraPose ()=0
 
RobotStatePtr getCurrentRobotState ()
 
virtual float getDistance (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
 
virtual nav_msgs::Path getNavigationPath (const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition)=0
 
float getPTU_PanMovementCosts (const RobotStatePtr &targetRobotState)
 
virtual float getPTU_PanMovementCosts (const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState)=0
 
float getPTU_TiltMovementCosts (const RobotStatePtr &targetRobotState)
 
virtual float getPTU_TiltMovementCosts (const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState)=0
 
virtual geometry_msgs::Pose getRobotPose ()=0
 
virtual bool isPoseReachable (const robot_model_services::SimpleVector3 &position, const robot_model_services::SimpleQuaternion &orientation)=0
 
virtual bool isPositionReachable (const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition)=0
 
 RobotModel ()
 the constructor of the RobotModel object More...
 
void setCurrentRobotState (const RobotStatePtr &currentRobotState)
 
virtual ~RobotModel ()
 the destructor of the RobotModel object More...
 

Private Attributes

RobotStatePtr mCurrentRobotState
 

Detailed Description

RobotModel generalizes a robot model.

Author
Ralf Schleicher
Date
2014
Version
1.0

Definition at line 37 of file RobotModel.hpp.

Constructor & Destructor Documentation

robot_model_services::RobotModel::RobotModel ( )

the constructor of the RobotModel object

Definition at line 23 of file RobotModel.cpp.

robot_model_services::RobotModel::~RobotModel ( )
virtual

the destructor of the RobotModel object

Definition at line 24 of file RobotModel.cpp.

Member Function Documentation

virtual geometry_msgs::Pose robot_model_services::RobotModel::calculateCameraPose ( const RobotStatePtr sourceRobotState)
pure virtual

Uses a given RobotState to calculate the camera frame.

Implemented in robot_model_services::MILDRobotModel.

RobotStatePtr robot_model_services::RobotModel::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

Parameters
positionthe position
orientationthe orientation
Returns
the new robot state

Definition at line 26 of file RobotModel.cpp.

virtual RobotStatePtr robot_model_services::RobotModel::calculateRobotState ( const RobotStatePtr sourceRobotState,
const SimpleVector3 position,
const SimpleQuaternion orientation 
)
pure virtual

calculates the target robot state

Parameters
currentRobotStatethe current robot state
positionthe position
orientationthe orientation
Returns
the new robot state

Implemented in robot_model_services::MILDRobotModelWithExactIK, and robot_model_services::MILDRobotModelWithApproximatedIK.

float robot_model_services::RobotModel::getBase_RotationalMovementCosts ( const RobotStatePtr targetRobotState)

Definition at line 42 of file RobotModel.cpp.

virtual float robot_model_services::RobotModel::getBase_RotationalMovementCosts ( const RobotStatePtr sourceRobotState,
const RobotStatePtr targetRobotState 
)
pure virtual
float robot_model_services::RobotModel::getBase_TranslationalMovementCosts ( const RobotStatePtr targetRobotState)
Parameters
targetRobotStatethe target state
Returns
the rating

Definition at line 30 of file RobotModel.cpp.

virtual float robot_model_services::RobotModel::getBase_TranslationalMovementCosts ( const RobotStatePtr sourceRobotState,
const RobotStatePtr targetRobotState 
)
pure virtual
Parameters
sourceRobotStatethe source state
targetRobotStatethe target state
Returns
the rating to move to the pose.

Implemented in robot_model_services::MILDRobotModel.

virtual geometry_msgs::Pose robot_model_services::RobotModel::getCameraPose ( )
pure virtual
RobotStatePtr robot_model_services::RobotModel::getCurrentRobotState ( )
Returns
the current robot state ptr

Definition at line 50 of file RobotModel.cpp.

virtual float robot_model_services::RobotModel::getDistance ( const geometry_msgs::Point sourcePosition,
const geometry_msgs::Point targetPosition 
)
pure virtual
virtual nav_msgs::Path robot_model_services::RobotModel::getNavigationPath ( const geometry_msgs::Point sourcePosition,
const geometry_msgs::Point targetPosition,
double  sourceRotationBase,
double  targetRotationBase 
)
pure virtual

Client used for communication with the global_planner to calculate movement costs

Implemented in robot_model_services::MILDRobotModel.

virtual nav_msgs::Path robot_model_services::RobotModel::getNavigationPath ( const geometry_msgs::Point sourcePosition,
const geometry_msgs::Point targetPosition 
)
pure virtual
float robot_model_services::RobotModel::getPTU_PanMovementCosts ( const RobotStatePtr targetRobotState)

Definition at line 34 of file RobotModel.cpp.

virtual float robot_model_services::RobotModel::getPTU_PanMovementCosts ( const RobotStatePtr sourceRobotState,
const RobotStatePtr targetRobotState 
)
pure virtual
float robot_model_services::RobotModel::getPTU_TiltMovementCosts ( const RobotStatePtr targetRobotState)

Definition at line 38 of file RobotModel.cpp.

virtual float robot_model_services::RobotModel::getPTU_TiltMovementCosts ( const RobotStatePtr sourceRobotState,
const RobotStatePtr targetRobotState 
)
pure virtual
virtual geometry_msgs::Pose robot_model_services::RobotModel::getRobotPose ( )
pure virtual
virtual bool robot_model_services::RobotModel::isPoseReachable ( const robot_model_services::SimpleVector3 position,
const robot_model_services::SimpleQuaternion orientation 
)
pure virtual
Parameters
orientationthe orientation to reach
Returns
if the orienation is reachable or not

Implemented in robot_model_services::MILDRobotModel.

virtual bool robot_model_services::RobotModel::isPositionReachable ( const geometry_msgs::Point sourcePosition,
const geometry_msgs::Point targetPosition 
)
pure virtual
void robot_model_services::RobotModel::setCurrentRobotState ( const RobotStatePtr currentRobotState)
Parameters
currentRobotStatesets the current robot state ptr

Definition at line 46 of file RobotModel.cpp.

Member Data Documentation

RobotStatePtr robot_model_services::RobotModel::mCurrentRobotState
private

Definition at line 39 of file RobotModel.hpp.


The documentation for this class was generated from the following files:


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:50:00