Public Member Functions | Private Member Functions
controller::SrhEffortJointController Class Reference

#include <srh_joint_effort_controller.hpp>

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

List of all members.

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, const std::string &joint_name)
bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
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.
virtual ~SrhEffortJointController ()

Private Member Functions

void read_parameters ()
 read all the controller settings from the parameter server

Detailed Description

Definition at line 38 of file srh_joint_effort_controller.hpp.


Constructor & Destructor Documentation

Definition at line 44 of file srh_joint_effort_controller.cpp.

Definition at line 49 of file srh_joint_effort_controller.cpp.


Member Function Documentation

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,
const std::string &  joint_name 
)

Definition at line 54 of file srh_joint_effort_controller.cpp.

Reimplemented from controller::SrController.

Definition at line 112 of file srh_joint_effort_controller.cpp.

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.

Reimplemented from controller::SrController.

Definition at line 131 of file srh_joint_effort_controller.cpp.

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.


The documentation for this class was generated from the following files:


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Fri Aug 28 2015 13:09:56