#include <srh_joint_velocity_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_velocity) |
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) |
SrhJointVelocityController () | |
virtual void | starting () |
virtual void | update () |
Issues commands to the joint. Should be called at regular intervals. | |
virtual | ~SrhJointVelocityController () |
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. | |
boost::shared_ptr < control_toolbox::Pid > | pid_controller_velocity_ |
double | velocity_deadband |
the velocity deadband value used in the hysteresis_deadband |
Definition at line 37 of file srh_joint_velocity_controller.hpp.
Definition at line 42 of file srh_joint_velocity_controller.cpp.
Definition at line 47 of file srh_joint_velocity_controller.cpp.
void controller::SrhJointVelocityController::getGains | ( | double & | p, |
double & | i, | ||
double & | d, | ||
double & | i_max, | ||
double & | i_min | ||
) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 195 of file srh_joint_velocity_controller.cpp.
bool controller::SrhJointVelocityController::init | ( | pr2_mechanism_model::RobotState * | robot, |
const std::string & | joint_name, | ||
boost::shared_ptr< control_toolbox::Pid > | pid_velocity | ||
) |
Definition at line 52 of file srh_joint_velocity_controller.cpp.
bool controller::SrhJointVelocityController::init | ( | pr2_mechanism_model::RobotState * | robot, |
ros::NodeHandle & | n | ||
) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 118 of file srh_joint_velocity_controller.cpp.
void controller::SrhJointVelocityController::read_parameters | ( | ) | [private] |
read all the controller settings from the parameter server
Definition at line 278 of file srh_joint_velocity_controller.cpp.
bool controller::SrhJointVelocityController::resetGains | ( | std_srvs::Empty::Request & | req, |
std_srvs::Empty::Response & | resp | ||
) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 175 of file srh_joint_velocity_controller.cpp.
bool controller::SrhJointVelocityController::setGains | ( | sr_robot_msgs::SetPidGains::Request & | req, |
sr_robot_msgs::SetPidGains::Response & | resp | ||
) |
Definition at line 154 of file srh_joint_velocity_controller.cpp.
void controller::SrhJointVelocityController::starting | ( | ) | [virtual] |
Reimplemented from controller::SrController.
Definition at line 142 of file srh_joint_velocity_controller.cpp.
void controller::SrhJointVelocityController::update | ( | void | ) | [virtual] |
Issues commands to the joint. Should be called at regular intervals.
Reimplemented from controller::SrController.
Definition at line 200 of file srh_joint_velocity_controller.cpp.
sr_deadband::HysteresisDeadband<double> controller::SrhJointVelocityController::hysteresis_deadband [private] |
We're using an hysteresis deadband.
Reimplemented from controller::SrController.
Definition at line 66 of file srh_joint_velocity_controller.hpp.
boost::shared_ptr<control_toolbox::Pid> controller::SrhJointVelocityController::pid_controller_velocity_ [private] |
Internal PID controller for the velocity loop.
Definition at line 60 of file srh_joint_velocity_controller.hpp.
double controller::SrhJointVelocityController::velocity_deadband [private] |
the velocity deadband value used in the hysteresis_deadband
Definition at line 63 of file srh_joint_velocity_controller.hpp.