device_interface.h
Go to the documentation of this file.
00001 /* -*- mode: C++ -*-
00002  *
00003  *  Copyright (C) 2011 Austin Robot Technology
00004  *  License: Modified BSD Software License Agreement
00005  * 
00006  *  $Id: device_interface.h 1539 2011-05-09 04:09:20Z jack.oquin $
00007  */
00008 
00020 #ifndef __DEVICE_INTERFACE_H_
00021 #define __DEVICE_INTERFACE_H_
00022 
00023 #include <ros/ros.h>
00024 #include <art_msgs/DriverState.h>
00025 
00026 namespace device_interface
00027 {
00028 
00030 class DeviceBase
00031 {
00032  public:
00033 
00038   DeviceBase(ros::NodeHandle node):
00039     node_(node)
00040   {}
00041 
00042   typedef art_msgs::DriverState::_state_type DeviceState;
00043   virtual DeviceState state(ros::Time recently) = 0;
00044 
00045 protected:
00046   ros::NodeHandle node_;                // node handle for topic
00047   ros::Subscriber sub_;                 // state message subscriber
00048 };
00049 
00051 class ServoDeviceBase: public DeviceBase
00052 {
00053  public:
00054 
00059   ServoDeviceBase(ros::NodeHandle node):
00060     DeviceBase(node)
00061   {}
00062 
00063   virtual float last_request() = 0;
00064   virtual float value() = 0;
00065 
00071   virtual void publish(float new_position, ros::Time cycle_time) = 0;
00072 
00073 protected:
00074   ros::Publisher pub_;                  // command message publisher
00075 };
00076 
00077 }; // end device_interface namespace
00078 
00079 #endif // __DEVICE_INTERFACE_H_


art_pilot
Author(s): Austin Robot Technology, Jack O'Quin
autogenerated on Fri Jan 3 2014 11:09:32