00001
00028 #ifndef _UBI0_HPP_
00029 #define _UBI0_HPP_
00030
00031 #include <vector>
00032 #include <string>
00033 #include <sr_robot_msgs/UBI0All.h>
00034 #include <sr_robot_msgs/UBI0.h>
00035 #include <sr_robot_msgs/AuxSpiData.h>
00036 #include <sr_robot_msgs/MidProxDataAll.h>
00037 #include <sr_robot_msgs/MidProxData.h>
00038 #include <realtime_tools/realtime_publisher.h>
00039
00040 #include "sr_robot_lib/generic_tactiles.hpp"
00041 #include "sr_robot_lib/generic_updater.hpp"
00042
00043 namespace tactiles
00044 {
00045 template<class StatusType, class CommandType>
00046 class UBI0 :
00047 public GenericTactiles<StatusType, CommandType>
00048 {
00049 public:
00050 UBI0(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
00053 UBI0(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
00054 operation_mode::device_update_state::DeviceUpdateState update_state,
00055 boost::shared_ptr<std::vector<GenericTactileData> > init_tactiles_vector);
00056
00060 void init(std::vector<generic_updater::UpdateConfig> update_configs_vector,
00061 operation_mode::device_update_state::DeviceUpdateState update_state);
00062
00070 virtual void update(StatusType *status_data);
00071
00076 virtual void publish();
00077
00082 virtual void add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec,
00083 diagnostic_updater::DiagnosticStatusWrapper &d);
00084
00085
00086 virtual std::vector<AllTactileData> *get_tactile_data();
00087
00088 protected:
00090 boost::shared_ptr<std::vector<UBI0Data> > tactiles_vector;
00091
00093 boost::shared_ptr<UBI0PalmData> palm_tactiles;
00094
00095
00096 boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::AuxSpiData> > aux_spi_publisher;
00097 };
00098
00099
00100
00101
00107 template<>
00108 class UBI0<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND> :
00109 public GenericTactiles<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS,
00110 ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>
00111 {
00112 public:
00113 UBI0(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
00114 operation_mode::device_update_state::DeviceUpdateState update_state)
00115 : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS,
00116 ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
00117 {
00118 ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
00119 }
00120
00121 UBI0(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
00122 operation_mode::device_update_state::DeviceUpdateState update_state,
00123 boost::shared_ptr<std::vector<GenericTactileData> > init_tactiles_vector)
00124 : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS,
00125 ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
00126 {
00127 ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
00128 }
00129
00130 ~UBI0()
00131 {
00132 };
00133 };
00134
00135 template<>
00136 class UBI0<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND> :
00137 public GenericTactiles<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS,
00138 ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>
00139 {
00140 public:
00141 UBI0(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
00142 operation_mode::device_update_state::DeviceUpdateState update_state)
00143 : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS,
00144 ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
00145 {
00146 ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
00147 }
00148
00149 UBI0(ros::NodeHandle nh, std::string device_id, std::vector<generic_updater::UpdateConfig> update_configs_vector,
00150 operation_mode::device_update_state::DeviceUpdateState update_state,
00151 boost::shared_ptr<std::vector<GenericTactileData> > init_tactiles_vector)
00152 : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS,
00153 ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>(nh, device_id, update_configs_vector, update_state)
00154 {
00155 ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
00156 }
00157
00158 ~UBI0()
00159 {
00160 };
00161 };
00162 }
00163
00164
00165
00166
00167
00168
00169
00170 #endif