Go to the documentation of this file.00001
00028 #ifndef _SHADOW_PSTS_HPP_
00029 #define _SHADOW_PSTS_HPP_
00030
00031 #include <vector>
00032 #include <string>
00033 #include <sr_robot_msgs/ShadowPST.h>
00034 #include <realtime_tools/realtime_publisher.h>
00035
00036 #include <sr_hardware_interface/tactile_sensors.hpp>
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 ShadowPSTs :
00044 public GenericTactiles<StatusType, CommandType>
00045 {
00046 public:
00047 ShadowPSTs(ros::NodeHandle nh, std::string device_id,
00048 std::vector<generic_updater::UpdateConfig> update_configs_vector,
00049 operation_mode::device_update_state::DeviceUpdateState update_state);
00050
00051 ShadowPSTs(ros::NodeHandle nh, std::string device_id,
00052 std::vector<generic_updater::UpdateConfig> update_configs_vector,
00053 operation_mode::device_update_state::DeviceUpdateState update_state,
00054 boost::shared_ptr<std::vector<GenericTactileData> > init_tactiles_vector);
00055
00056 void init(std::vector<generic_updater::UpdateConfig> update_configs_vector,
00057 operation_mode::device_update_state::DeviceUpdateState update_state);
00058
00066 virtual void update(StatusType *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
00082 boost::shared_ptr<std::vector<PST3Data> > tactiles_vector;
00083
00084 virtual std::vector<AllTactileData> *get_tactile_data();
00085
00086 protected:
00087 };
00088 }
00089
00090
00091
00092
00093
00094
00095
00096 #endif