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 <simple_Jtranspose_controller/MoveToPose.h>
00049 #include <std_srvs/Empty.h>
00050 #include <boost/scoped_ptr.hpp>
00051
00052 namespace controller {
00053
00054
00055 class CartesianTrajectoryController : public pr2_controller_interface::Controller
00056 {
00057 public:
00058 CartesianTrajectoryController();
00059 ~CartesianTrajectoryController();
00060
00061 bool init(pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle& n);
00062
00063 void starting();
00064 void update();
00065 bool moveTo(const geometry_msgs::PoseStamped& pose,
00066 const geometry_msgs::Twist& tolerance=geometry_msgs::Twist(), double duration=0);
00067 bool checkMoving(simple_Jtranspose_controller::CheckMoving::Request &req, simple_Jtranspose_controller::CheckMoving::Response &res);
00068
00069 private:
00070 KDL::Frame getPose();
00071 void TransformToFrame(const tf::Transform& trans, KDL::Frame& frame);
00072
00073
00074 void command(const tf::MessageFilter<geometry_msgs::PoseStamped>::MConstPtr& pose_msg);
00075
00076
00077 bool moveTo(simple_Jtranspose_controller::MoveToPose::Request &req, simple_Jtranspose_controller::MoveToPose::Response &resp);
00078 bool preempt(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
00079
00080 ros::NodeHandle node_;
00081 ros::ServiceServer move_to_srv_, preempt_srv_, check_moving_srv_;
00082
00083 std::string controller_name_;
00084 ros::Time last_time_, time_started_;
00085 double time_passed_, max_duration_;
00086 bool is_moving_, request_preempt_, exceed_tolerance_;
00087
00088 KDL::Frame pose_begin_, pose_end_, pose_current_;
00089 KDL::Twist twist_current_, tolerance_;
00090
00091
00092 pr2_mechanism_model::RobotState *robot_state_;
00093 pr2_mechanism_model::Chain chain_;
00094
00095
00096 KDL::Chain kdl_chain_;
00097 boost::scoped_ptr<KDL::ChainFkSolverPos> jnt_to_pose_solver_;
00098 KDL::JntArray jnt_pos_;
00099
00100
00101 std::vector<KDL::VelocityProfile_Trap> motion_profile_;
00102
00103
00104 CartesianPoseController* pose_controller_;
00105
00106 tf::TransformListener tf_;
00107
00108
00109
00110 std::string root_name_;
00111 };
00112
00113
00114 }
00115 #endif