controller::CartesianTwistController Class Reference

#include <cartesian_twist_controller.h>

List of all members.

Public Member Functions

 CartesianTwistController ()
bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
void starting ()
void update ()
 ~CartesianTwistController ()

Public Attributes

KDL::Twist twist_desi_
KDL::Twist twist_meas_

Private Member Functions

void command (const geometry_msgs::TwistConstPtr &twist_msg)

Private Attributes

pr2_mechanism_model::Chain chain_
std::vector< control_toolbox::Pid > fb_pid_controller_
double ff_rot_
double ff_trans_
boost::scoped_ptr
< KDL::ChainJntToJacSolver > 
jac_solver_
KDL::Jacobian jacobian_
KDL::JntArray jnt_eff_
KDL::JntArrayVel jnt_posvel_
boost::scoped_ptr
< KDL::ChainFkSolverVel > 
jnt_to_twist_solver_
KDL::Chain kdl_chain_
ros::Time last_time_
ros::NodeHandle node_
pr2_mechanism_model::RobotState * robot_state_
ros::Subscriber sub_command_
geometry_msgs::Twist twist_msg_
KDL::Wrench wrench_out_

Detailed Description

Definition at line 77 of file cartesian_twist_controller.h.


Constructor & Destructor Documentation

controller::CartesianTwistController::CartesianTwistController (  ) 

Definition at line 46 of file cartesian_twist_controller.cpp.

controller::CartesianTwistController::~CartesianTwistController (  ) 

Definition at line 53 of file cartesian_twist_controller.cpp.


Member Function Documentation

void controller::CartesianTwistController::command ( const geometry_msgs::TwistConstPtr &  twist_msg  )  [private]

Definition at line 176 of file cartesian_twist_controller.cpp.

bool controller::CartesianTwistController::init ( pr2_mechanism_model::RobotState *  robot,
ros::NodeHandle &  n 
)

Definition at line 59 of file cartesian_twist_controller.cpp.

void controller::CartesianTwistController::starting (  ) 

Definition at line 119 of file cartesian_twist_controller.cpp.

void controller::CartesianTwistController::update (  ) 

Definition at line 134 of file cartesian_twist_controller.cpp.


Member Data Documentation

pr2_mechanism_model::Chain controller::CartesianTwistController::chain_ [private]

Definition at line 100 of file cartesian_twist_controller.h.

std::vector<control_toolbox::Pid> controller::CartesianTwistController::fb_pid_controller_ [private]

Definition at line 96 of file cartesian_twist_controller.h.

Definition at line 92 of file cartesian_twist_controller.h.

Definition at line 92 of file cartesian_twist_controller.h.

boost::scoped_ptr<KDL::ChainJntToJacSolver> controller::CartesianTwistController::jac_solver_ [private]

Definition at line 105 of file cartesian_twist_controller.h.

Definition at line 108 of file cartesian_twist_controller.h.

Definition at line 107 of file cartesian_twist_controller.h.

Definition at line 106 of file cartesian_twist_controller.h.

boost::scoped_ptr<KDL::ChainFkSolverVel> controller::CartesianTwistController::jnt_to_twist_solver_ [private]

Definition at line 104 of file cartesian_twist_controller.h.

Definition at line 103 of file cartesian_twist_controller.h.

Definition at line 93 of file cartesian_twist_controller.h.

Definition at line 89 of file cartesian_twist_controller.h.

pr2_mechanism_model::RobotState* controller::CartesianTwistController::robot_state_ [private]

Definition at line 99 of file cartesian_twist_controller.h.

Definition at line 90 of file cartesian_twist_controller.h.

Definition at line 86 of file cartesian_twist_controller.h.

Definition at line 86 of file cartesian_twist_controller.h.

geometry_msgs::Twist controller::CartesianTwistController::twist_msg_ [private]

Definition at line 111 of file cartesian_twist_controller.h.

Definition at line 109 of file cartesian_twist_controller.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Friends


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Fri Jan 11 10:01:07 2013