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
00069 #ifndef CARTESIAN_POSE_CONTROLLER_H
00070 #define CARTESIAN_POSE_CONTROLLER_H
00071
00072 #include <vector>
00073 #include <boost/scoped_ptr.hpp>
00074 #include <boost/thread/condition.hpp>
00075
00076 #include <ros/node_handle.h>
00077
00078 #include <geometry_msgs/PoseStamped.h>
00079 #include <geometry_msgs/Twist.h>
00080
00081 #include <control_toolbox/pid.h>
00082 #include <kdl/chainfksolver.hpp>
00083 #include <kdl/chain.hpp>
00084 #include <kdl/chainjnttojacsolver.hpp>
00085 #include <kdl/frames.hpp>
00086 #include <message_filters/subscriber.h>
00087 #include <pr2_controller_interface/controller.h>
00088 #include <pr2_mechanism_model/chain.h>
00089 #include <realtime_tools/realtime_publisher.h>
00090 #include <tf/message_filter.h>
00091 #include <tf/transform_datatypes.h>
00092 #include <tf/transform_listener.h>
00093
00094
00095 namespace controller {
00096
00097 class CartesianPoseController : public pr2_controller_interface::Controller
00098 {
00099 public:
00100 CartesianPoseController();
00101 ~CartesianPoseController();
00102
00103 bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00104 void starting();
00105 void update();
00106
00107 void command(const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
00108
00109
00110 KDL::Frame pose_desi_, pose_meas_;
00111 KDL::Twist twist_ff_;
00112
00113
00114 KDL::Twist twist_error_;
00115
00116 private:
00117 KDL::Frame getPose();
00118
00119 ros::NodeHandle node_;
00120 std::string controller_name_, root_name_;
00121 ros::Time last_time_;
00122
00123
00124 pr2_mechanism_model::RobotState *robot_state_;
00125 pr2_mechanism_model::Chain chain_;
00126
00127
00128 std::vector<control_toolbox::Pid> pid_controller_;
00129
00130
00131 KDL::Chain kdl_chain_;
00132 boost::scoped_ptr<KDL::ChainFkSolverPos> jnt_to_pose_solver_;
00133 boost::scoped_ptr<KDL::ChainJntToJacSolver> jac_solver_;
00134 KDL::JntArray jnt_pos_;
00135 KDL::JntArray jnt_eff_;
00136 KDL::Jacobian jacobian_;
00137
00138
00139 boost::scoped_ptr<realtime_tools::RealtimePublisher<geometry_msgs::Twist> > state_error_publisher_;
00140 boost::scoped_ptr<realtime_tools::RealtimePublisher<geometry_msgs::PoseStamped> > state_pose_publisher_;
00141 unsigned int loop_count_;
00142
00143 tf::TransformListener tf_;
00144 message_filters::Subscriber<geometry_msgs::PoseStamped> sub_command_;
00145 boost::scoped_ptr<tf::MessageFilter<geometry_msgs::PoseStamped> > command_filter_;
00146
00147 };
00148
00149 }
00150
00151
00152 #endif