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

#include <cartesian_pose_controller.h>

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

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 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::Frame pose_desi_
 
KDL::Frame pose_meas_
 
KDL::Twist twist_error_
 
KDL::Twist twist_ff_
 
- 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

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::ChainJntToJacSolverjac_solver_
 
KDL::Jacobian jacobian_
 
KDL::JntArray jnt_eff_
 
KDL::JntArray jnt_pos_
 
boost::scoped_ptr< KDL::ChainFkSolverPosjnt_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

controller::CartesianPoseController::CartesianPoseController ( )

Definition at line 51 of file cartesian_pose_controller.cpp.

controller::CartesianPoseController::~CartesianPoseController ( )

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.

Frame controller::CartesianPoseController::getPose ( )
private

Definition at line 192 of file cartesian_pose_controller.cpp.

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

Reimplemented from pr2_controller_interface::Controller.

Definition at line 121 of file cartesian_pose_controller.cpp.

void controller::CartesianPoseController::update ( void  )
virtual

Member Data Documentation

pr2_mechanism_model::Chain controller::CartesianPoseController::chain_
private

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.

std::string controller::CartesianPoseController::controller_name_
private

Definition at line 120 of file cartesian_pose_controller.h.

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

Definition at line 133 of file cartesian_pose_controller.h.

KDL::Jacobian controller::CartesianPoseController::jacobian_
private

Definition at line 136 of file cartesian_pose_controller.h.

KDL::JntArray controller::CartesianPoseController::jnt_eff_
private

Definition at line 135 of file cartesian_pose_controller.h.

KDL::JntArray controller::CartesianPoseController::jnt_pos_
private

Definition at line 134 of file cartesian_pose_controller.h.

boost::scoped_ptr<KDL::ChainFkSolverPos> controller::CartesianPoseController::jnt_to_pose_solver_
private

Definition at line 132 of file cartesian_pose_controller.h.

KDL::Chain controller::CartesianPoseController::kdl_chain_
private

Definition at line 131 of file cartesian_pose_controller.h.

ros::Time controller::CartesianPoseController::last_time_
private

Definition at line 121 of file cartesian_pose_controller.h.

unsigned int controller::CartesianPoseController::loop_count_
private

Definition at line 141 of file cartesian_pose_controller.h.

ros::NodeHandle controller::CartesianPoseController::node_
private

Definition at line 119 of file cartesian_pose_controller.h.

std::vector<control_toolbox::Pid> controller::CartesianPoseController::pid_controller_
private

Definition at line 128 of file cartesian_pose_controller.h.

KDL::Frame controller::CartesianPoseController::pose_desi_

Definition at line 110 of file cartesian_pose_controller.h.

KDL::Frame controller::CartesianPoseController::pose_meas_

Definition at line 110 of file cartesian_pose_controller.h.

pr2_mechanism_model::RobotState* controller::CartesianPoseController::robot_state_
private

Definition at line 124 of file cartesian_pose_controller.h.

std::string controller::CartesianPoseController::root_name_
private

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.

message_filters::Subscriber<geometry_msgs::PoseStamped> controller::CartesianPoseController::sub_command_
private

Definition at line 144 of file cartesian_pose_controller.h.

tf::TransformListener controller::CartesianPoseController::tf_
private

Definition at line 143 of file cartesian_pose_controller.h.

KDL::Twist controller::CartesianPoseController::twist_error_

Definition at line 114 of file cartesian_pose_controller.h.

KDL::Twist controller::CartesianPoseController::twist_ff_

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 Wed Jun 5 2019 19:34:03