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
00054 #ifndef CARTESIAN_WRENCH_CONTROLLER_H
00055 #define CARTESIAN_WRENCH_CONTROLLER_H
00056
00057 #include <vector>
00058 #include <kdl/chain.hpp>
00059 #include <kdl/frames.hpp>
00060 #include <kdl/chainjnttojacsolver.hpp>
00061 #include <ros/node_handle.h>
00062 #include <geometry_msgs/Wrench.h>
00063 #include <pr2_controller_interface/controller.h>
00064 #include <pr2_mechanism_model/chain.h>
00065 #include <tf/transform_datatypes.h>
00066 #include <realtime_tools/realtime_publisher.h>
00067 #include <boost/scoped_ptr.hpp>
00068 #include <boost/thread/condition.hpp>
00069
00070
00071 namespace controller {
00072
00073 class CartesianWrenchController : public pr2_controller_interface::Controller
00074 {
00075 public:
00076 CartesianWrenchController();
00077 ~CartesianWrenchController();
00078
00079 bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00080
00081 void starting();
00082 void update();
00083
00084
00085 KDL::Wrench wrench_desi_;
00086
00087 private:
00088 ros::NodeHandle node_;
00089 ros::Subscriber sub_command_;
00090 void command(const geometry_msgs::WrenchConstPtr& wrench_msg);
00091 pr2_mechanism_model::RobotState *robot_state_;
00092 pr2_mechanism_model::Chain chain_;
00093
00094 KDL::Chain kdl_chain_;
00095 boost::scoped_ptr<KDL::ChainJntToJacSolver> jnt_to_jac_solver_;
00096 KDL::JntArray jnt_pos_, jnt_eff_;
00097 KDL::Jacobian jacobian_;
00098
00099 };
00100
00101 }
00102
00103
00104 #endif