srh_joint_effort_controller.hpp
Go to the documentation of this file.
1 /*
2 * Copyright 2011 Shadow Robot Company Ltd.
3 *
4 * This program is free software: you can redistribute it and/or modify it
5 * under the terms of the GNU General Public License as published by the Free
6 * Software Foundation version 2 of the License.
7 *
8 * This program is distributed in the hope that it will be useful, but WITHOUT
9 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
10 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
11 * more details.
12 *
13 * You should have received a copy of the GNU General Public License along
14 * with this program. If not, see <http://www.gnu.org/licenses/>.
15 */
16 
30 #ifndef _SRH_EFFORT_CONTROLLER_HPP_
31 #define _SRH_EFFORT_CONTROLLER_HPP_
32 
34 #include <sr_robot_msgs/SetEffortControllerGains.h>
35 
36 namespace controller
37 {
39  public SrController
40 {
41 public:
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::SetEffortControllerGains::Request &req,
56  sr_robot_msgs::SetEffortControllerGains::Response &resp);
57 
58 private:
60  void read_parameters();
61 
63  double clamp_command(double cmd);
64 
66  void setCommandCB(const std_msgs::Float64ConstPtr &msg);
67 };
68 } // namespace controller
69 
70 /* For the emacs weenies in the crowd.
71 Local Variables:
72  c-basic-offset: 2
73 End:
74 */
75 
76 
77 #endif
d
bool setGains(sr_robot_msgs::SetEffortControllerGains::Request &req, sr_robot_msgs::SetEffortControllerGains::Response &resp)
void read_parameters()
read all the controller settings from the parameter server
string cmd
A generic controller for the Shadow Robot EtherCAT hand&#39;s joints.
double clamp_command(double cmd)
clamp the command to effort limits
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
virtual void starting(const ros::Time &time)
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the effort target from a topic


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:30