#include <cartesian_controller.hpp>

Public Member Functions | |
| bool | init (hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &nh) | 
| void | starting (const ros::Time &time) | 
| void | stopping (const ros::Time &time) | 
| void | update (const ros::Time &time, const ros::Duration &period) | 
Private Member Functions | |
| void | velCmdCB (const geometry_msgs::TwistStampedConstPtr &msg) | 
Private Attributes | |
| boost::scoped_ptr < KDL::ChainFkSolverPos >  | chain_fk_solver_ | 
| boost::scoped_ptr < KDL::ChainIkSolverVel >  | chain_ik_solver_vel_ | 
| KDL::Twist | cmd_angular_twist_ | 
| KDL::Twist | cmd_linear_twist_ | 
| ros::Duration | dead_man_timeout_ | 
| bool | got_msg_ | 
| hardware_interface::JointHandle | joint_ | 
| std::vector < hardware_interface::JointHandle >  | joint_handles_ | 
| double | joint_vel_limit_ | 
| KDL::Chain | kdl_chain_ | 
| KDL::Tree | kdl_tree_ | 
| ros::Time | last_msg_ | 
| std::string | root_name_ | 
| std::string | tip_name_ | 
| ros::Subscriber | vel_cmd_sub_ | 
Definition at line 63 of file cartesian_controller.hpp.
| bool velocity_controllers::CartesianController::init | ( | hardware_interface::VelocityJointInterface * | hw, | 
| ros::NodeHandle & | nh | ||
| ) |  [virtual] | 
        
Reimplemented from controller_interface::Controller< hardware_interface::VelocityJointInterface >.
Definition at line 48 of file cartesian_controller.cpp.
| void velocity_controllers::CartesianController::starting | ( | const ros::Time & | time | ) |  [virtual] | 
        
Reimplemented from controller_interface::ControllerBase.
Definition at line 210 of file cartesian_controller.cpp.
| void velocity_controllers::CartesianController::stopping | ( | const ros::Time & | time | ) |  [virtual] | 
        
Reimplemented from controller_interface::ControllerBase.
Definition at line 230 of file cartesian_controller.cpp.
| void velocity_controllers::CartesianController::update | ( | const ros::Time & | time, | 
| const ros::Duration & | period | ||
| ) |  [virtual] | 
        
Implements controller_interface::ControllerBase.
Definition at line 103 of file cartesian_controller.cpp.
| void velocity_controllers::CartesianController::velCmdCB | ( | const geometry_msgs::TwistStampedConstPtr & | msg | ) |  [private] | 
        
Definition at line 235 of file cartesian_controller.cpp.
boost::scoped_ptr<KDL::ChainFkSolverPos> velocity_controllers::CartesianController::chain_fk_solver_ [private] | 
        
Definition at line 82 of file cartesian_controller.hpp.
boost::scoped_ptr<KDL::ChainIkSolverVel> velocity_controllers::CartesianController::chain_ik_solver_vel_ [private] | 
        
Definition at line 81 of file cartesian_controller.hpp.
Definition at line 85 of file cartesian_controller.hpp.
Definition at line 84 of file cartesian_controller.hpp.
Definition at line 92 of file cartesian_controller.hpp.
bool velocity_controllers::CartesianController::got_msg_ [private] | 
        
Definition at line 89 of file cartesian_controller.hpp.
Definition at line 74 of file cartesian_controller.hpp.
std::vector<hardware_interface::JointHandle> velocity_controllers::CartesianController::joint_handles_ [private] | 
        
Definition at line 79 of file cartesian_controller.hpp.
double velocity_controllers::CartesianController::joint_vel_limit_ [private] | 
        
Definition at line 94 of file cartesian_controller.hpp.
Definition at line 78 of file cartesian_controller.hpp.
Definition at line 77 of file cartesian_controller.hpp.
Definition at line 91 of file cartesian_controller.hpp.
std::string velocity_controllers::CartesianController::root_name_ [private] | 
        
Definition at line 87 of file cartesian_controller.hpp.
std::string velocity_controllers::CartesianController::tip_name_ [private] | 
        
Definition at line 87 of file cartesian_controller.hpp.
Definition at line 75 of file cartesian_controller.hpp.