Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef CARTESIAN_TRAJECTORY_CONTROLLER_H
00035 #define CARTESIAN_TRAJECTORY_CONTROLLER_H
00036
00037 #include <vector>
00038 #include <string>
00039 #include <kdl/chain.hpp>
00040 #include <kdl/frames.hpp>
00041 #include <kdl/velocityprofile_trap.hpp>
00042 #include <tf/transform_listener.h>
00043 #include <tf/message_filter.h>
00044 #include <ros/ros.h>
00045 #include <geometry_msgs/PoseStamped.h>
00046 #include <pr2_controller_interface/controller.h>
00047 #include <robot_mechanism_controllers/cartesian_pose_controller.h>
00048 #include <pr2_manipulation_controllers/MoveToPose.h>
00049 #include <std_srvs/Empty.h>
00050 #include <boost/scoped_ptr.hpp>
00051
00052 using namespace controller;
00053
00054 namespace pr2_manipulation_controllers {
00055
00056
00057 class CartesianTrajectoryController : public pr2_controller_interface::Controller
00058 {
00059 public:
00060 CartesianTrajectoryController();
00061 ~CartesianTrajectoryController();
00062
00063 bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle& n);
00064
00065 void starting();
00066 void update();
00067 bool moveTo(const geometry_msgs::PoseStamped& pose,
00068 const geometry_msgs::Twist& tolerance=geometry_msgs::Twist(), double duration=0);
00069 bool checkMoving(pr2_manipulation_controllers::CheckMoving::Request &req, pr2_manipulation_controllers::CheckMoving::Response &res);
00070
00071 private:
00072 KDL::Frame getPose();
00073 void TransformToFrame(const tf::Transform& trans, KDL::Frame& frame);
00074
00075
00076 void command(const tf::MessageFilter<geometry_msgs::PoseStamped>::MConstPtr& pose_msg);
00077
00078
00079 bool moveTo(pr2_manipulation_controllers::MoveToPose::Request &req, pr2_manipulation_controllers::MoveToPose::Response &resp);
00080 bool preempt(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
00081
00082 ros::NodeHandle node_;
00083 ros::ServiceServer move_to_srv_, preempt_srv_, check_moving_srv_;
00084
00085 std::string controller_name_;
00086 ros::Time last_time_, time_started_;
00087 double time_passed_, max_duration_;
00088 bool is_moving_, request_preempt_, exceed_tolerance_;
00089
00090 KDL::Frame pose_begin_, pose_end_, pose_current_;
00091 KDL::Twist twist_current_, tolerance_;
00092
00093
00094 pr2_mechanism_model::RobotState *robot_state_;
00095 pr2_mechanism_model::Chain chain_;
00096
00097
00098 KDL::Chain kdl_chain_;
00099 boost::scoped_ptr<KDL::ChainFkSolverPos> jnt_to_pose_solver_;
00100 KDL::JntArray jnt_pos_;
00101
00102
00103 std::vector<KDL::VelocityProfile_Trap> motion_profile_;
00104
00105
00106 CartesianPoseController* pose_controller_;
00107
00108 tf::TransformListener tf_;
00109
00110
00111
00112 std::string root_name_;
00113 };
00114
00115
00116 }
00117 #endif