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
00058 #ifndef CARTESIAN_TWIST_CONTROLLER_H
00059 #define CARTESIAN_TWIST_CONTROLLER_H
00060
00061 #include <vector>
00062 #include <boost/scoped_ptr.hpp>
00063 #include <boost/thread/condition.hpp>
00064
00065 #include <ros/node_handle.h>
00066 #include <geometry_msgs/Twist.h>
00067
00068 #include <control_toolbox/pid.h>
00069 #include <kdl/chainfksolver.hpp>
00070 #include <kdl/chain.hpp>
00071 #include <kdl/chainjnttojacsolver.hpp>
00072 #include <kdl/frames.hpp>
00073 #include <pr2_controller_interface/controller.h>
00074 #include <pr2_mechanism_model/chain.h>
00075 #include <realtime_tools/realtime_publisher.h>
00076 #include <tf/transform_datatypes.h>
00077
00078
00079 namespace controller {
00080
00081 class CartesianTwistController : public pr2_controller_interface::Controller
00082 {
00083 public:
00084 CartesianTwistController();
00085 ~CartesianTwistController();
00086
00087 bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00088
00089 void starting();
00090 void update();
00091
00092
00093 KDL::Twist twist_desi_, twist_meas_;
00094
00095 private:
00096 ros::NodeHandle node_;
00097 ros::Subscriber sub_command_;
00098 void command(const geometry_msgs::TwistConstPtr& twist_msg);
00099 double ff_trans_, ff_rot_;
00100 ros::Time last_time_;
00101
00102
00103 std::vector<control_toolbox::Pid> fb_pid_controller_;
00104
00105
00106 pr2_mechanism_model::RobotState *robot_state_;
00107 pr2_mechanism_model::Chain chain_;
00108
00109
00110 KDL::Chain kdl_chain_;
00111 boost::scoped_ptr<KDL::ChainFkSolverVel> jnt_to_twist_solver_;
00112 boost::scoped_ptr<KDL::ChainJntToJacSolver> jac_solver_;
00113 KDL::JntArrayVel jnt_posvel_;
00114 KDL::JntArray jnt_eff_;
00115 KDL::Jacobian jacobian_;
00116 KDL::Wrench wrench_out_;
00117
00118 geometry_msgs::Twist twist_msg_;
00119 };
00120
00121 }
00122
00123
00124 #endif