srh_joint_velocity_controller.hpp
Go to the documentation of this file.
1 
28 #ifndef _SRH_JOINT_VELOCITY_CONTROLLER_HPP_
29 #define _SRH_JOINT_VELOCITY_CONTROLLER_HPP_
30 
33 
34 
35 namespace controller
36 {
38  public SrController
39 {
40 public:
42 
43  bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n);
44 
45  virtual void starting(const ros::Time &time);
46 
50  virtual void update(const ros::Time &time, const ros::Duration &period);
51 
52  virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
53 
54  virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
55 
56  bool setGains(sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp);
57 
58 private:
60  boost::scoped_ptr<control_toolbox::Pid> pid_controller_velocity_;
61 
64 
67 
69  void read_parameters();
70 
72  double clamp_command(double cmd);
73 
75  void setCommandCB(const std_msgs::Float64ConstPtr &msg);
76 
77  void resetJointState();
78 };
79 } // namespace controller
80 
81 /* For the emacs weenies in the crowd.
82 Local Variables:
83  c-basic-offset: 2
84 End:
85 */
86 
87 
88 #endif
d
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&#39;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)
robot
Compensate the tendon friction by adding a given value depending on the sign of the force demand...
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&#39;re using an hysteresis deadband.


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:58