28 #ifndef _SRH_JOINT_VELOCITY_CONTROLLER_HPP_ 29 #define _SRH_JOINT_VELOCITY_CONTROLLER_HPP_ 52 virtual void getGains(
double &p,
double &i,
double &
d,
double &i_max,
double &i_min);
54 virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
56 bool setGains(sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp);
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
bool setGains(sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp)
double clamp_command(double cmd)
clamp the command to velocity limits
A generic controller for the Shadow Robot EtherCAT hand's joints.
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
double velocity_deadband
the velocity deadband value used in the hysteresis_deadband
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the velocity target from a topic
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
Compensate the tendon friction by adding a given value depending on the sign of the force demand...
virtual void starting(const ros::Time &time)
void read_parameters()
read all the controller settings from the parameter server
boost::scoped_ptr< control_toolbox::Pid > pid_controller_velocity_
Internal PID controller for the velocity loop.
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
We're using an hysteresis deadband.
SrhJointVelocityController()