00001 00028 #ifndef GENERIC_TACTILES_HPP_ 00029 #define GENERIC_TACTILES_HPP_ 00030 00031 #include <boost/smart_ptr.hpp> 00032 #include <sr_external_dependencies/types_for_external.h> 00033 extern "C" 00034 { 00035 #include <sr_external_dependencies/external/0220_palm_edc/0220_palm_edc_ethercat_protocol.h> 00036 } 00037 00038 #include <ros/ros.h> 00039 #include <vector> 00040 #include <std_srvs/Empty.h> 00041 00042 #include <boost/smart_ptr.hpp> 00043 00044 #include <diagnostic_msgs/DiagnosticStatus.h> 00045 #include <diagnostic_updater/DiagnosticStatusWrapper.h> 00046 00047 #include <sr_hardware_interface/tactile_sensors.hpp> 00048 #include "sr_robot_lib/generic_updater.hpp" 00049 #include "sr_robot_lib/sensor_updater.hpp" 00050 00051 namespace tactiles 00052 { 00053 class GenericTactiles 00054 { 00055 public: 00056 GenericTactiles(std::vector<generic_updater::UpdateConfig> update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state); 00057 ~GenericTactiles() {}; 00058 00066 virtual void update(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS* status_data); 00067 00072 virtual void publish(); 00073 00078 virtual void add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec, 00079 diagnostic_updater::DiagnosticStatusWrapper &d); 00080 00089 bool reset(std_srvs::Empty::Request& request, 00090 std_srvs::Empty::Response& response); 00091 00093 static const unsigned int nb_tactiles; 00094 00095 boost::shared_ptr<generic_updater::SensorUpdater> sensor_updater; 00097 boost::shared_ptr< std::vector<GenericTactileData> > tactiles_vector; 00098 00099 virtual std::vector<AllTactileData>* get_tactile_data(); 00100 00101 protected: 00102 00103 void process_received_data_type(int32u data); 00104 00105 ros::NodeHandle nodehandle_; 00106 00107 ros::ServiceServer reset_service_client_; 00108 00110 std::vector<int32u> initialization_received_data_vector; 00111 00122 std::string sanitise_string( const char* raw_string, const unsigned int str_size ); 00123 00124 boost::shared_ptr<std::vector<AllTactileData> > all_tactile_data; 00125 };//end class 00126 }//end namespace 00127 00128 /* For the emacs weenies in the crowd. 00129 Local Variables: 00130 c-basic-offset: 2 00131 End: 00132 */ 00133 00134 #endif /* GENERIC_TACTILES_HPP_ */