69 #ifndef CARTESIAN_POSE_CONTROLLER_H 70 #define CARTESIAN_POSE_CONTROLLER_H 73 #include <boost/scoped_ptr.hpp> 74 #include <boost/thread/condition.hpp> 78 #include <geometry_msgs/PoseStamped.h> 79 #include <geometry_msgs/Twist.h> 82 #include <kdl/chainfksolver.hpp> 83 #include <kdl/chain.hpp> 84 #include <kdl/chainjnttojacsolver.hpp> 85 #include <kdl/frames.hpp> 107 void command(
const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
std::vector< control_toolbox::Pid > pid_controller_
void command(const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
boost::scoped_ptr< tf::MessageFilter< geometry_msgs::PoseStamped > > command_filter_
message_filters::Subscriber< geometry_msgs::PoseStamped > sub_command_
boost::scoped_ptr< KDL::ChainJntToJacSolver > jac_solver_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
~CartesianPoseController()
tf::TransformListener tf_
std::string controller_name_
boost::scoped_ptr< realtime_tools::RealtimePublisher< geometry_msgs::PoseStamped > > state_pose_publisher_
pr2_mechanism_model::Chain chain_
pr2_mechanism_model::RobotState * robot_state_
CartesianPoseController()
boost::scoped_ptr< realtime_tools::RealtimePublisher< geometry_msgs::Twist > > state_error_publisher_
boost::scoped_ptr< KDL::ChainFkSolverPos > jnt_to_pose_solver_