Public Member Functions | List of all members
robot_model_services::MILDRobotModelWithApproximatedIK Class Reference

MILDRobotModelWithApproximatedIK implements a model of pan tilt unit robot where the inverse kinematic is defined by an approximation function. More...

#include <MILDRobotModelWithApproximatedIK.hpp>

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

Public Member Functions

RobotStatePtr calculateRobotState (const RobotStatePtr &sourceRobotState, const SimpleVector3 &position, const SimpleQuaternion &orientation)
 calculates the target robot state More...
 
 MILDRobotModelWithApproximatedIK ()
 constructor of the MILDRobotModelWithApproximatedIK More...
 
virtual ~MILDRobotModelWithApproximatedIK ()
 destructor of the MILDRobotModelWithApproximatedIK More...
 
- Public Member Functions inherited from robot_model_services::MILDRobotModel
geometry_msgs::Pose calculateCameraPose (const RobotStatePtr &sourceRobotState)
 Uses a given RobotState to calculate the camera frame. More...
 
float getBase_RotationalMovementCosts (const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState)
 
float getBase_TranslationalMovementCosts (const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState)
 Calculates the movement costs from sourceRobotState to targetRobotState. Returns -1 if pose is not reachable. More...
 
geometry_msgs::Pose getCameraPose ()
 
float getDistance (const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition)
 
nav_msgs::Path getNavigationPath (const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition, double sourceRotationBase, double targetRotationBase)
 
nav_msgs::Path getNavigationPath (const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition)
 
float getPTU_PanMovementCosts (const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState)
 
float getPTU_TiltMovementCosts (const RobotStatePtr &sourceRobotState, const RobotStatePtr &targetRobotState)
 
geometry_msgs::Pose getRobotPose ()
 
bool isPoseReachable (const SimpleVector3 &position, const SimpleQuaternion &orientation)
 
bool isPositionAllowed (const geometry_msgs::Point &position)
 
bool isPositionReachable (const geometry_msgs::Point &sourcePosition, const geometry_msgs::Point &targetPosition)
 
 MILDRobotModel ()
 constructor of the MILDRobotModel More...
 
void setPanAngleLimits (float minAngleDegrees, float maxAngleDegrees)
 sets the angle limits of the pan angle. More...
 
void setRotationAngleLimits (float minAngleDegrees, float maxAngleDegrees)
 sets the angle limits of the rotation angle. More...
 
void setTiltAngleLimits (float minAngleDegrees, float maxAngleDegrees)
 sets the angle limits of the tilt angle. More...
 
virtual ~MILDRobotModel ()
 destructor of the MILDRobotModel More...
 
- Public Member Functions inherited from robot_model_services::RobotModel
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...
 
float getBase_RotationalMovementCosts (const RobotStatePtr &targetRobotState)
 
float getBase_TranslationalMovementCosts (const RobotStatePtr &targetRobotState)
 
RobotStatePtr getCurrentRobotState ()
 
float getPTU_PanMovementCosts (const RobotStatePtr &targetRobotState)
 
float getPTU_TiltMovementCosts (const RobotStatePtr &targetRobotState)
 
 RobotModel ()
 the constructor of the RobotModel object More...
 
void setCurrentRobotState (const RobotStatePtr &currentRobotState)
 
virtual ~RobotModel ()
 the destructor of the RobotModel object More...
 

Additional Inherited Members

- Protected Attributes inherited from robot_model_services::MILDRobotModel
tf::TransformListener listener
 
DebugHelperPtr mDebugHelperPtr
 
std::string mFrameName_map
 
std::string mFrameName_mild_base
 
std::string mFrameName_mild_camera_left
 
std::string mFrameName_mild_camera_mount_link
 
std::string mFrameName_mild_camera_right
 
std::string mFrameName_mild_ptu_base_link
 
std::string mFrameName_mild_ptu_pan_link
 
std::string mFrameName_mild_ptu_pan_link_rotated
 
std::string mFrameName_mild_ptu_tilt_link
 
std::string mFrameName_mild_ptu_tilt_link_rotated
 
MapHelperPtr mMapHelperPtr
 
float mOmegaPan
 
float mOmegaRot
 
float mOmegaTilt
 
boost::tuple< float, float > mPanLimits
 
boost::tuple< float, float > mRotationLimits
 
float mSigma
 
boost::tuple< float, float > mTiltLimits
 
ros::NodeHandle n
 
ros::ServiceClient navigationCostClient
 
float speedFactorBaseMove
 
float speedFactorBaseRot
 
float speedFactorPTU
 
float tolerance
 
bool useGlobalPlanner
 

Detailed Description

MILDRobotModelWithApproximatedIK implements a model of pan tilt unit robot where the inverse kinematic is defined by an approximation function.

Author
Ralf Schleicher
Date
2014
Version
1.0

Definition at line 38 of file MILDRobotModelWithApproximatedIK.hpp.

Constructor & Destructor Documentation

robot_model_services::MILDRobotModelWithApproximatedIK::MILDRobotModelWithApproximatedIK ( )

constructor of the MILDRobotModelWithApproximatedIK

Definition at line 45 of file MILDRobotModelWithApproximatedIK.cpp.

robot_model_services::MILDRobotModelWithApproximatedIK::~MILDRobotModelWithApproximatedIK ( )
virtual

destructor of the MILDRobotModelWithApproximatedIK

Definition at line 62 of file MILDRobotModelWithApproximatedIK.cpp.

Member Function Documentation

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

calculates the target robot state

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

Implements robot_model_services::RobotModel.

Definition at line 67 of file MILDRobotModelWithApproximatedIK.cpp.


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