srh_mixed_position_velocity_controller.hpp
Go to the documentation of this file.
1 
30 #ifndef SRH_MIXED_POSITION_VELOCITY_CONTROLLER_H
31 #define SRH_MIXED_POSITION_VELOCITY_CONTROLLER_H
32 
34 #include <sr_robot_msgs/SetMixedPositionVelocityPidGains.h>
35 #include <sr_robot_msgs/JointControllerState.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 void getGains_velocity(double &p, double &i, double &d, double &i_max, double &i_min);
57 
58  virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp);
59 
60  bool setGains(sr_robot_msgs::SetMixedPositionVelocityPidGains::Request &req,
61  sr_robot_msgs::SetMixedPositionVelocityPidGains::Response &resp);
62 
63 private:
65  boost::scoped_ptr<control_toolbox::Pid> pid_controller_position_;
67  boost::scoped_ptr<control_toolbox::Pid> pid_controller_velocity_;
68 
69  // publish our joint controller state
70  boost::scoped_ptr<realtime_tools::RealtimePublisher
71  <sr_robot_msgs::JointControllerState> > controller_state_publisher_;
72 
75 
81 
82 #ifdef DEBUG_PUBLISHER
83  ros::Publisher debug_pub;
84 #endif
86 
89 
92 
94  void read_parameters();
95 
98 
100  void setCommandCB(const std_msgs::Float64ConstPtr &msg);
101 
102  void resetJointState();
103 };
104 } // namespace controller
105 
106 /* For the emacs weenies in the crowd.
107 Local Variables:
108  c-basic-offset: 2
109 End:
110 */
111 
112 
113 #endif
d
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
A generic controller for the Shadow Robot EtherCAT hand&#39;s joints.
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the position target from a topic
void read_parameters()
read all the controller settings from the parameter server
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
boost::scoped_ptr< control_toolbox::Pid > pid_controller_velocity_
Internal PID controller for the velocity loop.
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
virtual void getGains_velocity(double &p, double &i, double &d, double &i_max, double &i_min)
robot
bool override_to_current_effort_
Override commanded_effort to current effort when in deadband.
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.
int motor_min_force_threshold
smallest demand we can send to the motors
bool setGains(sr_robot_msgs::SetMixedPositionVelocityPidGains::Request &req, sr_robot_msgs::SetMixedPositionVelocityPidGains::Response &resp)
double max_velocity_
The values for the velocity demand saturation.
boost::scoped_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::JointControllerState > > controller_state_publisher_


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