srh_syntouch_controllers.hpp
Go to the documentation of this file.
1 
27 #ifndef SRH_SYNTOUCH_CONTROLLER_H
28 #define SRH_SYNTOUCH_CONTROLLER_H
29 
31 #include <sr_robot_msgs/JointControllerState.h>
34 
35 namespace controller
36 {
38  public SrController
39 {
40 public:
42 
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 private:
55  // publish our joint controller state
56  boost::scoped_ptr<realtime_tools::RealtimePublisher
57  <sr_robot_msgs::JointControllerState> > controller_state_publisher_;
58 
60 };
61 } // namespace controller
62 
63 /* For the emacs weenies in the crowd.
64 Local Variables:
65  c-basic-offset: 2
66 End:
67 */
68 
69 
70 #endif
boost::scoped_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::JointControllerState > > controller_state_publisher_
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
sr_actuator::SrMotorActuator * actuator_
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
virtual void starting(const ros::Time &time)


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