srh_joint_muscle_valve_controller.hpp
Go to the documentation of this file.
1 
30 #ifndef _SRH_MUSCLE_VALVE_CONTROLLER_HPP_
31 #define _SRH_MUSCLE_VALVE_CONTROLLER_HPP_
32 
34 #include <sr_robot_msgs/JointMuscleValveControllerState.h>
35 #include <sr_robot_msgs/JointMuscleValveControllerCommand.h>
36 
37 namespace controller
38 {
40  public SrController
41 {
42 public:
44 
45  bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n);
46 
47  virtual void starting(const ros::Time &time);
48 
52  virtual void update(const ros::Time &time, const ros::Duration &period);
53 
54  virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
55 
56  virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
57 
58  int8_t cmd_valve_muscle_[2];
60  unsigned int cmd_duration_ms_[2];
62  unsigned int current_duration_ms_[2];
63 
66 
67 private:
68  // publish our joint controller state
70  <sr_robot_msgs::JointMuscleValveControllerState> > controller_state_publisher_;
71 
73 
74  void setCommandCB(const sr_robot_msgs::JointMuscleValveControllerCommandConstPtr &msg);
75 
77  void read_parameters();
78 
80  int8_t clamp_command(int8_t cmd);
81 };
82 } // namespace controller
83 
84 /* For the emacs weenies in the crowd.
85 Local Variables:
86  c-basic-offset: 2
87 End:
88 */
89 
90 
91 #endif
d
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
A generic controller for the Shadow Robot EtherCAT hand&#39;s joints.
int8_t clamp_command(int8_t cmd)
enforce that the value of the received command is in the allowed range
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
void read_parameters()
read all the controller settings from the parameter server
robot
boost::shared_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::JointMuscleValveControllerState > > controller_state_publisher_
void setCommandCB(const sr_robot_msgs::JointMuscleValveControllerCommandConstPtr &msg)
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.


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