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

#include <cartesian_wrench_controller.h>

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

Public Member Functions

 CartesianWrenchController ()
 
bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 
void starting ()
 
void update ()
 
 ~CartesianWrenchController ()
 
- 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::Wrench wrench_desi_
 
- 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::WrenchConstPtr &wrench_msg)
 

Private Attributes

pr2_mechanism_model::Chain chain_
 
KDL::Jacobian jacobian_
 
KDL::JntArray jnt_eff_
 
KDL::JntArray jnt_pos_
 
boost::scoped_ptr< KDL::ChainJntToJacSolverjnt_to_jac_solver_
 
KDL::Chain kdl_chain_
 
ros::NodeHandle node_
 
pr2_mechanism_model::RobotStaterobot_state_
 
ros::Subscriber sub_command_
 

Detailed Description

Definition at line 73 of file cartesian_wrench_controller.h.

Constructor & Destructor Documentation

controller::CartesianWrenchController::CartesianWrenchController ( )

Definition at line 45 of file cartesian_wrench_controller.cpp.

controller::CartesianWrenchController::~CartesianWrenchController ( )

Definition at line 52 of file cartesian_wrench_controller.cpp.

Member Function Documentation

void controller::CartesianWrenchController::command ( const geometry_msgs::WrenchConstPtr &  wrench_msg)
private

Definition at line 139 of file cartesian_wrench_controller.cpp.

bool controller::CartesianWrenchController::init ( pr2_mechanism_model::RobotState robot,
ros::NodeHandle n 
)
virtual
void controller::CartesianWrenchController::starting ( )
virtual

Reimplemented from pr2_controller_interface::Controller.

Definition at line 105 of file cartesian_wrench_controller.cpp.

void controller::CartesianWrenchController::update ( void  )
virtual

Member Data Documentation

pr2_mechanism_model::Chain controller::CartesianWrenchController::chain_
private

Definition at line 92 of file cartesian_wrench_controller.h.

KDL::Jacobian controller::CartesianWrenchController::jacobian_
private

Definition at line 97 of file cartesian_wrench_controller.h.

KDL::JntArray controller::CartesianWrenchController::jnt_eff_
private

Definition at line 96 of file cartesian_wrench_controller.h.

KDL::JntArray controller::CartesianWrenchController::jnt_pos_
private

Definition at line 96 of file cartesian_wrench_controller.h.

boost::scoped_ptr<KDL::ChainJntToJacSolver> controller::CartesianWrenchController::jnt_to_jac_solver_
private

Definition at line 95 of file cartesian_wrench_controller.h.

KDL::Chain controller::CartesianWrenchController::kdl_chain_
private

Definition at line 94 of file cartesian_wrench_controller.h.

ros::NodeHandle controller::CartesianWrenchController::node_
private

Definition at line 88 of file cartesian_wrench_controller.h.

pr2_mechanism_model::RobotState* controller::CartesianWrenchController::robot_state_
private

Definition at line 91 of file cartesian_wrench_controller.h.

ros::Subscriber controller::CartesianWrenchController::sub_command_
private

Definition at line 89 of file cartesian_wrench_controller.h.

KDL::Wrench controller::CartesianWrenchController::wrench_desi_

Definition at line 85 of file cartesian_wrench_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 Wed Jun 5 2019 19:34:03