$search
#include <cartesian_twist_controller.h>
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_ |
Definition at line 81 of file cartesian_twist_controller.h.
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.
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] |
Implements pr2_controller_interface::Controller.
Definition at line 59 of file cartesian_twist_controller.cpp.
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] |
Implements pr2_controller_interface::Controller.
Definition at line 134 of file cartesian_twist_controller.cpp.
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.
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.
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.
Definition at line 110 of file cartesian_twist_controller.h.
Definition at line 100 of file cartesian_twist_controller.h.
Definition at line 96 of file cartesian_twist_controller.h.
Definition at line 106 of file cartesian_twist_controller.h.
Definition at line 97 of file cartesian_twist_controller.h.
Definition at line 93 of file cartesian_twist_controller.h.
Definition at line 93 of file cartesian_twist_controller.h.
Definition at line 118 of file cartesian_twist_controller.h.
Definition at line 116 of file cartesian_twist_controller.h.