srh_muscle_joint_position_controller.hpp
Go to the documentation of this file.
1 
28 #ifndef _SRH_MUSCLE_JOINT_POSITION_CONTROLLER_HPP_
29 #define _SRH_MUSCLE_JOINT_POSITION_CONTROLLER_HPP_
30 
32 #include <sr_robot_msgs/JointMusclePositionControllerState.h>
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 
62  boost::scoped_ptr<realtime_tools::RealtimePublisher
63  <sr_robot_msgs::JointMusclePositionControllerState> > controller_state_publisher_;
64 
67 
70 
73 
75  void read_parameters();
76 
78  void setCommandCB(const std_msgs::Float64ConstPtr &msg);
79 
80  void resetJointState();
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
double position_deadband
the position deadband value used in the hysteresis_deadband
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
A generic controller for the Shadow Robot EtherCAT hand&#39;s joints.
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
We&#39;re using an hysteresis deadband.
boost::scoped_ptr< control_toolbox::Pid > pid_controller_position_
Internal PID controller for the position loop.
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
robot
bool setGains(sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp)
boost::scoped_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::JointMusclePositionControllerState > > controller_state_publisher_
publish our joint controller state
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
int command_acc_
Command accumulator, time to keep the valves open/shut, sign gives the direction. ...
void read_parameters()
read all the controller settings from the parameter server
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the position target from a topic


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