00001 00020 #pragma once 00021 00022 #include <boost/tuple/tuple.hpp> 00023 #include "robot_model_services/robot_model/impl/MILDRobotModel.hpp" 00024 #include "robot_model_services/typedef.hpp" 00025 #include "geometry_msgs/Pose.h" 00026 #include <ros/ros.h> 00027 #include <tf/transform_listener.h> 00028 #include "robot_model_services/helper/DebugHelper.hpp" 00029 00030 namespace robot_model_services { 00038 class MILDRobotModelWithApproximatedIK : public MILDRobotModel { 00039 public: 00043 MILDRobotModelWithApproximatedIK(); 00044 00048 virtual ~MILDRobotModelWithApproximatedIK(); 00049 00050 00051 RobotStatePtr calculateRobotState(const RobotStatePtr &sourceRobotState, const SimpleVector3 &position, const SimpleQuaternion &orientation); 00052 00053 }; 00054 00055 typedef boost::shared_ptr<MILDRobotModelWithApproximatedIK> MILDRobotModelWithApproximatedIKPtr; 00056 }