RobotModel generalizes a robot model. More...
#include <RobotModel.hpp>

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 ¤tRobotState) |
| virtual | ~RobotModel () |
| the destructor of the RobotModel object More... | |
Private Attributes | |
| RobotStatePtr | mCurrentRobotState |
RobotModel generalizes a robot model.
Definition at line 37 of file RobotModel.hpp.
| robot_model_services::RobotModel::RobotModel | ( | ) |
the constructor of the RobotModel object
Definition at line 23 of file RobotModel.cpp.
|
virtual |
the destructor of the RobotModel object
Definition at line 24 of file RobotModel.cpp.
|
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
| position | the position |
| orientation | the orientation |
Definition at line 26 of file RobotModel.cpp.
|
pure virtual |
calculates the target robot state
| currentRobotState | the current robot state |
| position | the position |
| orientation | the orientation |
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.
|
pure virtual |
Implemented in robot_model_services::MILDRobotModel.
| float robot_model_services::RobotModel::getBase_TranslationalMovementCosts | ( | const RobotStatePtr & | targetRobotState | ) |
| targetRobotState | the target state |
Definition at line 30 of file RobotModel.cpp.
|
pure virtual |
| sourceRobotState | the source state |
| targetRobotState | the target state |
Implemented in robot_model_services::MILDRobotModel.
|
pure virtual |
Implemented in robot_model_services::MILDRobotModel.
| RobotStatePtr robot_model_services::RobotModel::getCurrentRobotState | ( | ) |
Definition at line 50 of file RobotModel.cpp.
|
pure virtual |
Implemented in robot_model_services::MILDRobotModel.
|
pure virtual |
Client used for communication with the global_planner to calculate movement costs
Implemented in robot_model_services::MILDRobotModel.
|
pure virtual |
Implemented in robot_model_services::MILDRobotModel.
| float robot_model_services::RobotModel::getPTU_PanMovementCosts | ( | const RobotStatePtr & | targetRobotState | ) |
Definition at line 34 of file RobotModel.cpp.
|
pure virtual |
Implemented in robot_model_services::MILDRobotModel.
| float robot_model_services::RobotModel::getPTU_TiltMovementCosts | ( | const RobotStatePtr & | targetRobotState | ) |
Definition at line 38 of file RobotModel.cpp.
|
pure virtual |
Implemented in robot_model_services::MILDRobotModel.
|
pure virtual |
Implemented in robot_model_services::MILDRobotModel.
|
pure virtual |
| orientation | the orientation to reach |
Implemented in robot_model_services::MILDRobotModel.
|
pure virtual |
Implemented in robot_model_services::MILDRobotModel.
| void robot_model_services::RobotModel::setCurrentRobotState | ( | const RobotStatePtr & | currentRobotState | ) |
| currentRobotState | sets the current robot state ptr |
Definition at line 46 of file RobotModel.cpp.
|
private |
Definition at line 39 of file RobotModel.hpp.