Go to the documentation of this file.00001
00028 #ifndef _BIOTAC_HPP_
00029 #define _BIOTAC_HPP_
00030
00031 #include <vector>
00032 #include <string>
00033 #include <sr_robot_msgs/BiotacAll.h>
00034 #include <sr_robot_msgs/Biotac.h>
00035 #include <realtime_tools/realtime_publisher.h>
00036
00037 #include "sr_robot_lib/generic_tactiles.hpp"
00038 #include "sr_robot_lib/generic_updater.hpp"
00039
00040 namespace tactiles
00041 {
00042 template<class StatusType, class CommandType>
00043 class Biotac :
00044 public GenericTactiles<StatusType, CommandType>
00045 {
00046 public:
00047 Biotac(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
00048 operation_mode::device_update_state::DeviceUpdateState update_state);
00049
00050 Biotac(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
00051 operation_mode::device_update_state::DeviceUpdateState update_state,
00052 boost::shared_ptr<std::vector<GenericTactileData> > init_tactiles_vector);
00053
00057 void init(std::vector<generic_updater::UpdateConfig> update_configs_vector,
00058 operation_mode::device_update_state::DeviceUpdateState update_state);
00059
00067 virtual void update(StatusType *status_data);
00068
00073 virtual void publish();
00074
00079 virtual void add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec,
00080 diagnostic_updater::DiagnosticStatusWrapper &d);
00081
00082
00083 virtual std::vector<AllTactileData> *get_tactile_data();
00084
00085 void set_version_specific_details();
00086
00087 protected:
00089 boost::shared_ptr<std::vector<BiotacData> > tactiles_vector;
00090
00091 size_t nb_electrodes_;
00092
00093 static const size_t nb_electrodes_v1_;
00094 static const size_t nb_electrodes_v2_;
00095 };
00096 }
00097
00098
00099
00100
00101
00102
00103
00104 #endif