$search
#include <srh_joint_effort_controller.hpp>

| Public Member Functions | |
| virtual void | getGains (double &p, double &i, double &d, double &i_max, double &i_min) | 
| bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) | 
| bool | init (pr2_mechanism_model::RobotState *robot, const std::string &joint_name) | 
| virtual bool | resetGains (std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp) | 
| bool | setGains (sr_robot_msgs::SetEffortControllerGains::Request &req, sr_robot_msgs::SetEffortControllerGains::Response &resp) | 
| SrhEffortJointController () | |
| virtual void | starting () | 
| virtual void | update () | 
| Issues commands to the joint. Should be called at regular intervals. | |
| ~SrhEffortJointController () | |
| Private Member Functions | |
| void | read_parameters () | 
| read all the controller settings from the parameter server | |
Definition at line 38 of file srh_joint_effort_controller.hpp.
| controller::SrhEffortJointController::SrhEffortJointController | ( | ) | 
Definition at line 44 of file srh_joint_effort_controller.cpp.
| controller::SrhEffortJointController::~SrhEffortJointController | ( | ) | 
Definition at line 49 of file srh_joint_effort_controller.cpp.
| void controller::SrhEffortJointController::getGains | ( | double & | p, | |
| double & | i, | |||
| double & | d, | |||
| double & | i_max, | |||
| double & | i_min | |||
| ) |  [virtual] | 
Reimplemented from controller::SrController.
Definition at line 164 of file srh_joint_effort_controller.cpp.
| bool controller::SrhEffortJointController::init | ( | pr2_mechanism_model::RobotState * | robot, | |
| ros::NodeHandle & | n | |||
| ) |  [virtual] | 
Reimplemented from controller::SrController.
Definition at line 112 of file srh_joint_effort_controller.cpp.
| bool controller::SrhEffortJointController::init | ( | pr2_mechanism_model::RobotState * | robot, | |
| const std::string & | joint_name | |||
| ) | 
Definition at line 54 of file srh_joint_effort_controller.cpp.
| void controller::SrhEffortJointController::read_parameters | ( | ) |  [private] | 
read all the controller settings from the parameter server
Definition at line 234 of file srh_joint_effort_controller.cpp.
| bool controller::SrhEffortJointController::resetGains | ( | std_srvs::Empty::Request & | req, | |
| std_srvs::Empty::Response & | resp | |||
| ) |  [virtual] | 
Reimplemented from controller::SrController.
Definition at line 150 of file srh_joint_effort_controller.cpp.
| bool controller::SrhEffortJointController::setGains | ( | sr_robot_msgs::SetEffortControllerGains::Request & | req, | |
| sr_robot_msgs::SetEffortControllerGains::Response & | resp | |||
| ) | 
Definition at line 137 of file srh_joint_effort_controller.cpp.
| void controller::SrhEffortJointController::starting | ( | ) |  [virtual] | 
Reimplemented from controller::SrController.
Definition at line 131 of file srh_joint_effort_controller.cpp.
| void controller::SrhEffortJointController::update | ( | void | ) |  [virtual] | 
Issues commands to the joint. Should be called at regular intervals.
Reimplemented from controller::SrController.
Definition at line 168 of file srh_joint_effort_controller.cpp.