srh_joint_position_controller.hpp
Go to the documentation of this file.
1 
28 #ifndef _SRH_JOINT_POSITION_CONTROLLER_HPP_
29 #define _SRH_JOINT_POSITION_CONTROLLER_HPP_
30 
32 
33 
34 namespace controller
35 {
37  public SrController
38 {
39 public:
41 
42  bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n);
43 
44  virtual void starting(const ros::Time &time);
45 
49  virtual void update(const ros::Time &time, const ros::Duration &period);
50 
51  virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
52 
53  virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
54 
55  bool setGains(sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp);
56 
57 private:
59  boost::scoped_ptr<control_toolbox::Pid> pid_controller_position_;
60 
63 
66 
68  void read_parameters();
69 
71  void setCommandCB(const std_msgs::Float64ConstPtr &msg);
72 
73  void resetJointState();
74 };
75 } // namespace controller
76 
77 /* For the emacs weenies in the crowd.
78 Local Variables:
79  c-basic-offset: 2
80 End:
81 */
82 
83 
84 #endif
d
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
We&#39;re using an hysteresis deadband.
double position_deadband
the position deadband value used in the hysteresis_deadband
void read_parameters()
read all the controller settings from the parameter server
A generic controller for the Shadow Robot EtherCAT hand&#39;s joints.
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
robot
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the position target from a topic
boost::scoped_ptr< control_toolbox::Pid > pid_controller_position_
Internal PID controller for the position loop.
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
bool setGains(sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp)
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)


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