Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
controller::CartesianTwistController Class Reference

#include <cartesian_twist_controller.h>

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

Public Member Functions

 CartesianTwistController ()
 
bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 
void starting ()
 
void update ()
 
 ~CartesianTwistController ()
 
- Public Member Functions inherited from pr2_controller_interface::Controller
 Controller ()
 
bool getController (const std::string &name, int sched, ControllerType *&c)
 
bool initRequest (ControllerProvider *cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 
bool isRunning ()
 
void starting (const ros::Time &time)
 
bool startRequest ()
 
void stopping (const ros::Time &time)
 
virtual void stopping ()
 
bool stopRequest ()
 
void update (const ros::Time &time, const ros::Duration &period)
 
void updateRequest ()
 
virtual ~Controller ()
 

Public Attributes

KDL::Twist twist_desi_
 
KDL::Twist twist_meas_
 
- Public Attributes inherited from pr2_controller_interface::Controller
std::vector< std::string > after_list_
 
 AFTER_ME
 
std::vector< std::string > before_list_
 
 BEFORE_ME
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum pr2_controller_interface::Controller:: { ... }  state_
 

Private Member Functions

void command (const geometry_msgs::TwistConstPtr &twist_msg)
 

Private Attributes

pr2_mechanism_model::Chain chain_
 
std::vector< control_toolbox::Pidfb_pid_controller_
 
double ff_rot_
 
double ff_trans_
 
boost::scoped_ptr< KDL::ChainJntToJacSolverjac_solver_
 
KDL::Jacobian jacobian_
 
KDL::JntArray jnt_eff_
 
KDL::JntArrayVel jnt_posvel_
 
boost::scoped_ptr< KDL::ChainFkSolverVeljnt_to_twist_solver_
 
KDL::Chain kdl_chain_
 
ros::Time last_time_
 
ros::NodeHandle node_
 
pr2_mechanism_model::RobotStaterobot_state_
 
ros::Subscriber sub_command_
 
geometry_msgs::Twist twist_msg_
 
KDL::Wrench wrench_out_
 

Detailed Description

Definition at line 81 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 
)
virtual
void controller::CartesianTwistController::starting ( )
virtual

Reimplemented from pr2_controller_interface::Controller.

Definition at line 119 of file cartesian_twist_controller.cpp.

void controller::CartesianTwistController::update ( void  )
virtual

Member Data Documentation

pr2_mechanism_model::Chain controller::CartesianTwistController::chain_
private

Definition at line 107 of file cartesian_twist_controller.h.

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

Definition at line 103 of file cartesian_twist_controller.h.

double controller::CartesianTwistController::ff_rot_
private

Definition at line 99 of file cartesian_twist_controller.h.

double controller::CartesianTwistController::ff_trans_
private

Definition at line 99 of file cartesian_twist_controller.h.

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

Definition at line 112 of file cartesian_twist_controller.h.

KDL::Jacobian controller::CartesianTwistController::jacobian_
private

Definition at line 115 of file cartesian_twist_controller.h.

KDL::JntArray controller::CartesianTwistController::jnt_eff_
private

Definition at line 114 of file cartesian_twist_controller.h.

KDL::JntArrayVel controller::CartesianTwistController::jnt_posvel_
private

Definition at line 113 of file cartesian_twist_controller.h.

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

Definition at line 111 of file cartesian_twist_controller.h.

KDL::Chain controller::CartesianTwistController::kdl_chain_
private

Definition at line 110 of file cartesian_twist_controller.h.

ros::Time controller::CartesianTwistController::last_time_
private

Definition at line 100 of file cartesian_twist_controller.h.

ros::NodeHandle controller::CartesianTwistController::node_
private

Definition at line 96 of file cartesian_twist_controller.h.

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

Definition at line 106 of file cartesian_twist_controller.h.

ros::Subscriber controller::CartesianTwistController::sub_command_
private

Definition at line 97 of file cartesian_twist_controller.h.

KDL::Twist controller::CartesianTwistController::twist_desi_

Definition at line 93 of file cartesian_twist_controller.h.

KDL::Twist controller::CartesianTwistController::twist_meas_

Definition at line 93 of file cartesian_twist_controller.h.

geometry_msgs::Twist controller::CartesianTwistController::twist_msg_
private

Definition at line 118 of file cartesian_twist_controller.h.

KDL::Wrench controller::CartesianTwistController::wrench_out_
private

Definition at line 116 of file cartesian_twist_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 Mon Jun 10 2019 14:26:26