Public Member Functions | |
void | cancelCB (GoalHandle gh) |
ControlHead (const ros::NodeHandle &node) | |
void | controllerStateCB (const pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr &msg) |
void | goalCB (GoalHandle gh) |
void | watchdog (const ros::TimerEvent &e) |
Public Attributes | |
pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr | last_controller_state_ |
Private Types | |
typedef PHAS::GoalHandle | GoalHandle |
typedef actionlib::ActionServer< pr2_controllers_msgs::PointHeadAction > | PHAS |
Private Attributes | |
std::string | action_name_ |
PHAS | action_server_ |
GoalHandle | active_goal_ |
KDL::Chain | chain_ |
ros::ServiceClient | cli_query_traj_ |
ros::Subscriber | command_sub_ |
std::string | default_pointing_frame_ |
bool | has_active_goal_ |
boost::scoped_ptr< KDL::ChainJntToJacSolver > | jac_solver_ |
std::vector< std::string > | joint_names_ |
ros::NodeHandle | nh_ |
std::string | node_name_ |
std::string | pan_link_ |
std::string | pan_parent_ |
ros::NodeHandle | pnh_ |
tf::Vector3 | pointing_axis_ |
std::string | pointing_frame_ |
boost::scoped_ptr< KDL::ChainFkSolverPos > | pose_solver_ |
ros::Publisher | pub_controller_command_ |
std::string | root_ |
ros::Subscriber | sub_controller_state_ |
double | success_angle_threshold_ |
geometry_msgs::PointStamped | target_ |
tf::Stamped< tf::Point > | target_in_pan_ |
tf::Point | target_in_root_ |
tf::TransformListener | tfl_ |
std::string | tip_ |
KDL::Tree | tree_ |
urdf::Model | urdf_model_ |
ros::Timer | watchdog_timer_ |
Definition at line 77 of file pr2_point_frame.cpp.
|
private |
Definition at line 81 of file pr2_point_frame.cpp.
|
private |
Definition at line 80 of file pr2_point_frame.cpp.
|
inline |
Definition at line 120 of file pr2_point_frame.cpp.
|
inline |
Definition at line 469 of file pr2_point_frame.cpp.
|
inline |
Definition at line 485 of file pr2_point_frame.cpp.
|
inline |
Definition at line 168 of file pr2_point_frame.cpp.
|
inline |
Definition at line 434 of file pr2_point_frame.cpp.
|
private |
Definition at line 84 of file pr2_point_frame.cpp.
|
private |
Definition at line 100 of file pr2_point_frame.cpp.
|
private |
Definition at line 102 of file pr2_point_frame.cpp.
|
private |
Definition at line 109 of file pr2_point_frame.cpp.
|
private |
Definition at line 97 of file pr2_point_frame.cpp.
|
private |
Definition at line 96 of file pr2_point_frame.cpp.
|
private |
Definition at line 88 of file pr2_point_frame.cpp.
|
private |
Definition at line 101 of file pr2_point_frame.cpp.
|
private |
Definition at line 113 of file pr2_point_frame.cpp.
|
private |
Definition at line 91 of file pr2_point_frame.cpp.
pr2_controllers_msgs::JointTrajectoryControllerStateConstPtr ControlHead::last_controller_state_ |
Definition at line 484 of file pr2_point_frame.cpp.
|
private |
Definition at line 93 of file pr2_point_frame.cpp.
|
private |
Definition at line 83 of file pr2_point_frame.cpp.
|
private |
Definition at line 87 of file pr2_point_frame.cpp.
|
private |
Definition at line 104 of file pr2_point_frame.cpp.
|
private |
Definition at line 93 of file pr2_point_frame.cpp.
|
private |
Definition at line 90 of file pr2_point_frame.cpp.
|
private |
Definition at line 89 of file pr2_point_frame.cpp.
|
private |
Definition at line 112 of file pr2_point_frame.cpp.
|
private |
Definition at line 94 of file pr2_point_frame.cpp.
|
private |
Definition at line 85 of file pr2_point_frame.cpp.
|
private |
Definition at line 95 of file pr2_point_frame.cpp.
|
private |
Definition at line 105 of file pr2_point_frame.cpp.
|
private |
Definition at line 107 of file pr2_point_frame.cpp.
|
private |
Definition at line 103 of file pr2_point_frame.cpp.
|
private |
Definition at line 110 of file pr2_point_frame.cpp.
|
private |
Definition at line 115 of file pr2_point_frame.cpp.
|
private |
Definition at line 86 of file pr2_point_frame.cpp.
|
private |
Definition at line 108 of file pr2_point_frame.cpp.
|
private |
Definition at line 116 of file pr2_point_frame.cpp.
|
private |
Definition at line 98 of file pr2_point_frame.cpp.