IKRatingModule is a generalization for the rating of the inverse kinematic parameters. More...
#include <IKRatingModule.h>

Public Member Functions | |
| virtual double | getPanAngleRating (const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition, double sourceRotationBase, double targetRotationBase)=0 |
| IKRatingModule () | |
| constructor of the IKRatingModule object | |
| virtual | ~IKRatingModule () |
| destructor of the IKRatingModule object. | |
IKRatingModule is a generalization for the rating of the inverse kinematic parameters.
Definition at line 34 of file IKRatingModule.h.
constructor of the IKRatingModule object
Definition at line 23 of file IKRatingModule.cpp.
| robot_model_services::IKRatingModule::~IKRatingModule | ( | ) | [virtual] |
destructor of the IKRatingModule object.
Definition at line 24 of file IKRatingModule.cpp.
| virtual double robot_model_services::IKRatingModule::getPanAngleRating | ( | const geometry_msgs::Point & | sourcePosition, |
| const geometry_msgs::Point & | targetPosition, | ||
| double | sourceRotationBase, | ||
| double | targetRotationBase | ||
| ) | [pure virtual] |
| sourcePosition | [in] the MILD's current position |
| targetPosition | [in] the MILD's target position |
| sourceRotationBase | [in] the MILD's current rotation |
| targetRotationBase | [in] the MILD's target rotation |
Implemented in robot_model_services::AngleApproximationIKRatingModule, robot_model_services::SimpleIKRatingModule, and robot_model_services::NavigationPathIKRatingModule.