Go to the documentation of this file.00001
00028 #ifndef _UBI0_HPP_
00029 #define _UBI0_HPP_
00030
00031 #include <vector>
00032 #include <sr_robot_msgs/UBI0All.h>
00033 #include <sr_robot_msgs/UBI0.h>
00034 #include <sr_robot_msgs/AuxSpiData.h>
00035 #include <sr_robot_msgs/MidProxDataAll.h>
00036 #include <sr_robot_msgs/MidProxData.h>
00037 #include <realtime_tools/realtime_publisher.h>
00038
00039 #include "sr_robot_lib/generic_tactiles.hpp"
00040 #include "sr_robot_lib/generic_updater.hpp"
00041
00042 namespace tactiles
00043 {
00044 template <class StatusType, class CommandType>
00045 class UBI0 :
00046 public GenericTactiles<StatusType, CommandType>
00047 {
00048 public:
00049 UBI0(std::vector<generic_updater::UpdateConfig> update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state);
00050 UBI0(std::vector<generic_updater::UpdateConfig> update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state, boost::shared_ptr< std::vector<GenericTactileData> > init_tactiles_vector);
00051 ~UBI0() {};
00052
00056 void init(std::vector<generic_updater::UpdateConfig> update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state);
00057
00065 virtual void update(StatusType* status_data);
00066
00071 virtual void publish();
00072
00077 virtual void add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec,
00078 diagnostic_updater::DiagnosticStatusWrapper &d);
00079
00080
00081 virtual std::vector<AllTactileData>* get_tactile_data();
00082
00083 protected:
00085 boost::shared_ptr< std::vector<UBI0Data> > tactiles_vector;
00086
00088 boost::shared_ptr< UBI0PalmData > palm_tactiles;
00089
00090
00091 boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::UBI0All> > tactile_publisher;
00092
00093 boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::MidProxDataAll> > mid_prox_publisher;
00094
00095 boost::shared_ptr<realtime_tools::RealtimePublisher<sr_robot_msgs::AuxSpiData> > aux_spi_publisher;
00096 };
00097
00098
00099
00100
00106 template <>
00107 class UBI0<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND> :
00108 public GenericTactiles<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>
00109 {
00110 public:
00111 UBI0(std::vector<generic_updater::UpdateConfig> update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
00112 : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>(update_configs_vector, update_state)
00113 {
00114 ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
00115 }
00116 UBI0(std::vector<generic_updater::UpdateConfig> update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state, boost::shared_ptr< std::vector<GenericTactileData> > init_tactiles_vector)
00117 : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>(update_configs_vector, update_state)
00118 {
00119 ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
00120 }
00121 ~UBI0() {};
00122 };
00123
00124 template <>
00125 class UBI0<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND> :
00126 public GenericTactiles<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>
00127 {
00128 public:
00129 UBI0(std::vector<generic_updater::UpdateConfig> update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state)
00130 : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>(update_configs_vector, update_state)
00131 {
00132 ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
00133 }
00134 UBI0(std::vector<generic_updater::UpdateConfig> update_configs_vector, operation_mode::device_update_state::DeviceUpdateState update_state, boost::shared_ptr< std::vector<GenericTactileData> > init_tactiles_vector)
00135 : GenericTactiles<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>(update_configs_vector, update_state)
00136 {
00137 ROS_ERROR("This UBI0 tactile object should not have been instantiated for this type of ETHERCAT_DATA_STRUCTURE");
00138 }
00139 ~UBI0() {};
00140 };
00141 }
00142
00143
00144
00145
00146
00147
00148
00149 #endif