#include <srh_joint_position_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, const std::string &joint_name, boost::shared_ptr< control_toolbox::Pid > pid_position) |
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::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp) |
SrhJointPositionController () | |
virtual void | starting () |
virtual void | update () |
Issues commands to the joint. Should be called at regular intervals. | |
virtual | ~SrhJointPositionController () |
Private Member Functions | |
void | read_parameters () |
read all the controller settings from the parameter server | |
Private Attributes | |
sr_deadband::HysteresisDeadband < double > | hysteresis_deadband |
We're using an hysteresis deadband. | |
std::string | joint_name_ |
double | max_force_demand |
clamps the force demand to this value | |
boost::shared_ptr < control_toolbox::Pid > | pid_controller_position_ |
double | position_deadband |
the position deadband value used in the hysteresis_deadband |
Definition at line 36 of file srh_joint_position_controller.hpp.
Definition at line 42 of file srh_joint_position_controller.cpp.
Definition at line 47 of file srh_joint_position_controller.cpp.
void controller::SrhJointPositionController::getGains | ( | double & | p, |
double & | i, | ||
double & | d, | ||
double & | i_max, | ||
double & | i_min | ||
) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 200 of file srh_joint_position_controller.cpp.
bool controller::SrhJointPositionController::init | ( | pr2_mechanism_model::RobotState * | robot, |
const std::string & | joint_name, | ||
boost::shared_ptr< control_toolbox::Pid > | pid_position | ||
) |
Definition at line 52 of file srh_joint_position_controller.cpp.
bool controller::SrhJointPositionController::init | ( | pr2_mechanism_model::RobotState * | robot, |
ros::NodeHandle & | n | ||
) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 123 of file srh_joint_position_controller.cpp.
void controller::SrhJointPositionController::read_parameters | ( | ) | [private] |
read all the controller settings from the parameter server
Definition at line 298 of file srh_joint_position_controller.cpp.
bool controller::SrhJointPositionController::resetGains | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | resp | ||
) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 180 of file srh_joint_position_controller.cpp.
bool controller::SrhJointPositionController::setGains | ( | sr_robot_msgs::SetPidGains::Request & | req, |
sr_robot_msgs::SetPidGains::Response & | resp | ||
) |
Definition at line 158 of file srh_joint_position_controller.cpp.
void controller::SrhJointPositionController::starting | ( | ) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 146 of file srh_joint_position_controller.cpp.
void controller::SrhJointPositionController::update | ( | void | ) | [virtual] |
Issues commands to the joint. Should be called at regular intervals.
Reimplemented from controller::SrController.
Definition at line 205 of file srh_joint_position_controller.cpp.
sr_deadband::HysteresisDeadband<double> controller::SrhJointPositionController::hysteresis_deadband [private] |
We're using an hysteresis deadband.
Reimplemented from controller::SrController.
Definition at line 67 of file srh_joint_position_controller.hpp.
std::string controller::SrhJointPositionController::joint_name_ [private] |
Definition at line 72 of file srh_joint_position_controller.hpp.
double controller::SrhJointPositionController::max_force_demand [private] |
clamps the force demand to this value
Reimplemented from controller::SrController.
Definition at line 61 of file srh_joint_position_controller.hpp.
boost::shared_ptr<control_toolbox::Pid> controller::SrhJointPositionController::pid_controller_position_ [private] |
Internal PID controller for the position loop.
Definition at line 58 of file srh_joint_position_controller.hpp.
double controller::SrhJointPositionController::position_deadband [private] |
the position deadband value used in the hysteresis_deadband
Definition at line 64 of file srh_joint_position_controller.hpp.