58 #ifndef CARTESIAN_TWIST_CONTROLLER_H 59 #define CARTESIAN_TWIST_CONTROLLER_H 62 #include <boost/scoped_ptr.hpp> 63 #include <boost/thread/condition.hpp> 66 #include <geometry_msgs/Twist.h> 69 #include <kdl/chainfksolver.hpp> 70 #include <kdl/chain.hpp> 71 #include <kdl/chainjnttojacsolver.hpp> 72 #include <kdl/frames.hpp> 98 void command(
const geometry_msgs::TwistConstPtr& twist_msg);
CartesianTwistController()
~CartesianTwistController()
geometry_msgs::Twist twist_msg_
ros::Subscriber sub_command_
KDL::JntArrayVel jnt_posvel_
std::vector< control_toolbox::Pid > fb_pid_controller_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
pr2_mechanism_model::Chain chain_
boost::scoped_ptr< KDL::ChainJntToJacSolver > jac_solver_
pr2_mechanism_model::RobotState * robot_state_
boost::scoped_ptr< KDL::ChainFkSolverVel > jnt_to_twist_solver_
void command(const geometry_msgs::TwistConstPtr &twist_msg)