srh_syntouch_controllers.hpp
Go to the documentation of this file.
00001 
00027 #ifndef SRH_SYNTOUCH_CONTROLLER_H
00028 #define SRH_SYNTOUCH_CONTROLLER_H
00029 
00030 #include <sr_mechanism_controllers/sr_controller.hpp>
00031 #include <sr_robot_msgs/JointControllerState.h>
00032 #include <sr_hardware_interface/tactile_sensors.hpp>
00033 #include <sr_hardware_interface/sr_actuator.hpp>
00034 
00035 namespace controller
00036 {
00037   class SrhSyntouchController : public SrController
00038   {
00039   public:
00040 
00041     SrhSyntouchController();
00042     ~SrhSyntouchController();
00043 
00044     bool init(ros_ethercat_model::RobotState *robot, ros::NodeHandle &n);
00045 
00046     virtual void starting(const ros::Time& time);
00047 
00051     virtual void update(const ros::Time& time, const ros::Duration& period);
00052 
00053   private:
00054     //publish our joint controller state
00055     boost::scoped_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::JointControllerState> > controller_state_publisher_;
00056 
00057     sr_actuator::SrMotorActuator* actuator_;
00058   };
00059 } // namespace
00060 
00061 /* For the emacs weenies in the crowd.
00062 Local Variables:
00063    c-basic-offset: 2
00064 End:
00065 */
00066 
00067 
00068 #endif


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:26:14