Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
controller::CartesianPoseController Class Reference

#include <cartesian_pose_controller.h>

Inheritance diagram for controller::CartesianPoseController:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 CartesianPoseController ()
void command (const geometry_msgs::PoseStamped::ConstPtr &pose_msg)
bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
void starting ()
void update ()
 ~CartesianPoseController ()

Public Attributes

KDL::Frame pose_desi_
KDL::Frame pose_meas_
KDL::Twist twist_error_
KDL::Twist twist_ff_

Private Member Functions

KDL::Frame getPose ()

Private Attributes

pr2_mechanism_model::Chain chain_
boost::scoped_ptr
< tf::MessageFilter
< geometry_msgs::PoseStamped > > 
command_filter_
std::string controller_name_
boost::scoped_ptr
< KDL::ChainJntToJacSolver
jac_solver_
KDL::Jacobian jacobian_
KDL::JntArray jnt_eff_
KDL::JntArray jnt_pos_
boost::scoped_ptr
< KDL::ChainFkSolverPos
jnt_to_pose_solver_
KDL::Chain kdl_chain_
ros::Time last_time_
unsigned int loop_count_
ros::NodeHandle node_
std::vector< control_toolbox::Pidpid_controller_
pr2_mechanism_model::RobotStaterobot_state_
std::string root_name_
boost::scoped_ptr
< realtime_tools::RealtimePublisher
< geometry_msgs::Twist > > 
state_error_publisher_
boost::scoped_ptr
< realtime_tools::RealtimePublisher
< geometry_msgs::PoseStamped > > 
state_pose_publisher_
message_filters::Subscriber
< geometry_msgs::PoseStamped > 
sub_command_
tf::TransformListener tf_

Detailed Description

Definition at line 97 of file cartesian_pose_controller.h.


Constructor & Destructor Documentation

Definition at line 51 of file cartesian_pose_controller.cpp.

Definition at line 55 of file cartesian_pose_controller.cpp.


Member Function Documentation

void controller::CartesianPoseController::command ( const geometry_msgs::PoseStamped::ConstPtr &  pose_msg)

Definition at line 204 of file cartesian_pose_controller.cpp.

Definition at line 192 of file cartesian_pose_controller.cpp.

Reimplemented from pr2_controller_interface::Controller.

Definition at line 121 of file cartesian_pose_controller.cpp.


Member Data Documentation

Definition at line 125 of file cartesian_pose_controller.h.

boost::scoped_ptr<tf::MessageFilter<geometry_msgs::PoseStamped> > controller::CartesianPoseController::command_filter_ [private]

Definition at line 145 of file cartesian_pose_controller.h.

Definition at line 120 of file cartesian_pose_controller.h.

Definition at line 133 of file cartesian_pose_controller.h.

Definition at line 136 of file cartesian_pose_controller.h.

Definition at line 135 of file cartesian_pose_controller.h.

Definition at line 134 of file cartesian_pose_controller.h.

Definition at line 132 of file cartesian_pose_controller.h.

Definition at line 131 of file cartesian_pose_controller.h.

Definition at line 121 of file cartesian_pose_controller.h.

Definition at line 141 of file cartesian_pose_controller.h.

Definition at line 119 of file cartesian_pose_controller.h.

Definition at line 128 of file cartesian_pose_controller.h.

Definition at line 110 of file cartesian_pose_controller.h.

Definition at line 110 of file cartesian_pose_controller.h.

Definition at line 124 of file cartesian_pose_controller.h.

Definition at line 120 of file cartesian_pose_controller.h.

boost::scoped_ptr<realtime_tools::RealtimePublisher<geometry_msgs::Twist> > controller::CartesianPoseController::state_error_publisher_ [private]

Definition at line 139 of file cartesian_pose_controller.h.

boost::scoped_ptr<realtime_tools::RealtimePublisher<geometry_msgs::PoseStamped> > controller::CartesianPoseController::state_pose_publisher_ [private]

Definition at line 140 of file cartesian_pose_controller.h.

Definition at line 144 of file cartesian_pose_controller.h.

Definition at line 143 of file cartesian_pose_controller.h.

Definition at line 114 of file cartesian_pose_controller.h.

Definition at line 111 of file cartesian_pose_controller.h.


The documentation for this class was generated from the following files:


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Fri Jan 3 2014 11:41:37