38 #include "kdl/chainfksolverpos_recursive.hpp" 51 CartesianPoseController::CartesianPoseController()
68 ROS_ERROR(
"CartesianPoseController: No root name found on parameter server (namespace: %s)",
73 ROS_ERROR(
"CartesianPoseController: No tip name found on parameter server (namespace: %s)",
102 for (
unsigned int i = 0; i < 3; i++)
105 for (
unsigned int i = 0; i < 3; i++)
124 for (
unsigned int i=0; i<6; i++)
150 for (
unsigned int i=0; i<6; i++)
159 for (
unsigned int j=0; j<6; j++)
208 poseStampedMsgToTF(*pose_msg, pose_stamped);
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
void resize(unsigned int newNrOfColumns)
std::vector< control_toolbox::Pid > pid_controller_
void command(const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
void getPositions(std::vector< double > &)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
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)
void poseTFToKDL(const tf::Pose &t, KDL::Frame &k)
~CartesianPoseController()
void poseKDLToTF(const KDL::Frame &k, tf::Pose &t)
const std::string & getNamespace() const
tf::TransformListener tf_
unsigned int getNrOfJoints() const
void resize(unsigned int newSize)
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
bool getParam(const std::string &key, std::string &s) const
boost::scoped_ptr< realtime_tools::RealtimePublisher< geometry_msgs::PoseStamped > > state_pose_publisher_
pr2_mechanism_model::Chain chain_
pr2_mechanism_model::RobotState * robot_state_
bool init(RobotState *robot_state, const std::string &root, const std::string &tip)
void toKDL(KDL::Chain &chain)
boost::scoped_ptr< realtime_tools::RealtimePublisher< geometry_msgs::Twist > > state_error_publisher_
void addEfforts(KDL::JntArray &)
boost::scoped_ptr< KDL::ChainFkSolverPos > jnt_to_pose_solver_