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( pr2_mechanism_model::RobotState *robot, const std::string &joint_name );
00045     bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00046 
00047     virtual void starting();
00048 
00052     virtual void update();
00053 
00054   private:
00055     //publish our joint controller state
00056     boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::JointControllerState> > controller_state_publisher_;
00057 
00058     sr_actuator::SrActuator* actuator_;
00059   };
00060 } // namespace
00061 
00062 /* For the emacs weenies in the crowd.
00063 Local Variables:
00064    c-basic-offset: 2
00065 End:
00066 */
00067 
00068 
00069 #endif


sr_mechanism_controllers
Author(s): Ugo Cupcic / ugo@shadowrobot.com , contact@shadowrobot.com
autogenerated on Mon Oct 6 2014 07:54:39