Go to the documentation of this file.00001
00028 #include "sr_robot_lib/generic_tactiles.hpp"
00029 #include <sr_utilities/sr_math_utils.hpp>
00030 #include <cctype>
00031 #include <string>
00032 #include <vector>
00033
00034
00035
00036
00037
00038 #define TACTILE_DATA_LENGTH_BYTES TACTILE_DATA_LENGTH_BYTES_v1
00039
00040 namespace tactiles
00041 {
00042 template<class StatusType, class CommandType>
00043 const unsigned int GenericTactiles<StatusType, CommandType>::nb_tactiles = 5;
00044
00045 template<class StatusType, class CommandType>
00046 GenericTactiles<StatusType,
00047 CommandType>::GenericTactiles(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 : nodehandle_(nh),
00051 device_id_(device_id)
00052 {
00053 sensor_updater = boost::shared_ptr<generic_updater::SensorUpdater<CommandType> >(
00054 new generic_updater::SensorUpdater<CommandType>(update_configs_vector, update_state));
00055 if (update_state != operation_mode::device_update_state::INITIALIZATION)
00056 {
00057 reset_service_client_ = nodehandle_.advertiseService("tactiles/reset", &GenericTactiles::reset, this);
00058 }
00059
00060
00061 tactiles_vector = boost::shared_ptr<std::vector<GenericTactileData> >(
00062 new std::vector<GenericTactileData>(nb_tactiles));
00063 all_tactile_data = boost::shared_ptr<std::vector<AllTactileData> >(new std::vector<AllTactileData>(nb_tactiles));
00064
00065 for (unsigned int i = 0; i < nb_tactiles; i++)
00066 {
00067 GenericTactileData tmp_pst;
00068 tactiles_vector->push_back(tmp_pst);
00069 }
00070 }
00071
00072 template<class StatusType, class CommandType>
00073 void GenericTactiles<StatusType, CommandType>::update(StatusType *status_data)
00074 {
00075 int tactile_mask = static_cast<int16u>(status_data->tactile_data_valid);
00076
00077 for (unsigned int id_sensor = 0; id_sensor < nb_tactiles; ++id_sensor)
00078 {
00079 ROS_DEBUG_STREAM(" received: " << static_cast<int32u>(status_data->tactile_data_type));
00080
00081 switch (static_cast<int32u>(status_data->tactile_data_type))
00082 {
00083
00084 case TACTILE_SENSOR_TYPE_WHICH_SENSORS:
00085 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
00086 {
00087 if (tactiles_vector != NULL)
00088 {
00089 tactiles_vector->at(id_sensor).which_sensor =
00090 static_cast<unsigned int>(static_cast<int16u>(status_data->tactile[id_sensor].word[0]));
00091 }
00092 ROS_DEBUG_STREAM(" tact[" << id_sensor << "] = " << tactiles_vector->at(id_sensor).which_sensor);
00093 }
00094 break;
00095
00096 case TACTILE_SENSOR_TYPE_SAMPLE_FREQUENCY_HZ:
00097 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
00098 {
00099 if (tactiles_vector != NULL)
00100 {
00101 tactiles_vector->at(id_sensor).sample_frequency =
00102 static_cast<unsigned int>(static_cast<int16u>(status_data->tactile[id_sensor].word[0]));
00103 }
00104 }
00105 break;
00106
00107 case TACTILE_SENSOR_TYPE_MANUFACTURER:
00108 {
00109 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
00110 {
00111 tactiles_vector->at(id_sensor).manufacturer = sanitise_string(status_data->tactile[id_sensor].string,
00112 TACTILE_DATA_LENGTH_BYTES);
00113 }
00114 }
00115 break;
00116
00117 case TACTILE_SENSOR_TYPE_SERIAL_NUMBER:
00118 {
00119 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
00120 {
00121 tactiles_vector->at(id_sensor).serial_number = sanitise_string(status_data->tactile[id_sensor].string,
00122 TACTILE_DATA_LENGTH_BYTES);
00123 }
00124 }
00125 break;
00126
00127 case TACTILE_SENSOR_TYPE_SOFTWARE_VERSION:
00128 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
00129 {
00130 if (tactiles_vector != NULL)
00131 {
00132 tactiles_vector->at(id_sensor).set_software_version(status_data->tactile[id_sensor].string);
00133 }
00134 }
00135 break;
00136
00137 case TACTILE_SENSOR_TYPE_PCB_VERSION:
00138 if (sr_math_utils::is_bit_mask_index_true(tactile_mask, id_sensor))
00139 {
00140 if (tactiles_vector != NULL)
00141 {
00142 tactiles_vector->at(id_sensor).pcb_version = sanitise_string(status_data->tactile[id_sensor].string,
00143 TACTILE_DATA_LENGTH_BYTES);
00144 }
00145 }
00146 break;
00147
00148 default:
00149 break;
00150 }
00151 }
00152
00153 if (sensor_updater->update_state == operation_mode::device_update_state::INITIALIZATION)
00154 {
00155 process_received_data_type(static_cast<int32u>(status_data->tactile_data_type));
00156 if (sensor_updater->initialization_configs_vector.size() == 0)
00157 {
00158 sensor_updater->update_state = operation_mode::device_update_state::OPERATION;
00159 }
00160 }
00161 }
00162
00163 template<class StatusType, class CommandType>
00164 void GenericTactiles<StatusType, CommandType>::process_received_data_type(int32u data)
00165 {
00166 unsigned int i;
00167 for (i = 0; i < sensor_updater->initialization_configs_vector.size(); i++)
00168 {
00169 if (sensor_updater->initialization_configs_vector[i].what_to_update == data)
00170 {
00171 break;
00172 }
00173 }
00174 if (i < sensor_updater->initialization_configs_vector.size())
00175 {
00176 sensor_updater->initialization_configs_vector.erase(sensor_updater->initialization_configs_vector.begin() + i);
00177 }
00178 }
00179
00180 template<class StatusType, class CommandType>
00181 void GenericTactiles<StatusType, CommandType>::publish()
00182 {
00183
00184 }
00185
00186 template<class StatusType, class CommandType>
00187 void GenericTactiles<StatusType, CommandType>::add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec,
00188 diagnostic_updater::DiagnosticStatusWrapper &d)
00189 {
00190
00191 }
00192
00201 template<class StatusType, class CommandType>
00202 bool GenericTactiles<StatusType, CommandType>::reset(std_srvs::Empty::Request &request,
00203 std_srvs::Empty::Response &response)
00204 {
00205 ROS_INFO_STREAM("Resetting tactiles");
00206
00207 return sensor_updater->reset();
00208 }
00209
00210 template<class StatusType, class CommandType>
00211 std::string GenericTactiles<StatusType, CommandType>::sanitise_string(const char *raw_string,
00212 const unsigned int str_size)
00213 {
00214 std::string sanitised_string = "";
00215 for (unsigned int i = 0; i < str_size; ++i)
00216 {
00217 char tmp = static_cast<char>(raw_string[i]);
00218 if (tmp != 0)
00219 {
00220 if (tmp >= '\x20' && tmp <= '\x7E')
00221 {
00222 sanitised_string += static_cast<char>(raw_string[i]);
00223 }
00224 else
00225 {
00226 sanitised_string += '?';
00227 }
00228 }
00229 else
00230 {
00231 break;
00232 }
00233 }
00234 return sanitised_string;
00235 }
00236
00237 template<class StatusType, class CommandType>
00238 std::vector<AllTactileData> *GenericTactiles<StatusType, CommandType>::get_tactile_data()
00239 {
00240 return all_tactile_data.get();
00241 }
00242
00243
00244 template
00245 class GenericTactiles<ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND>;
00246
00247 template
00248 class GenericTactiles<ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0230_PALM_EDC_COMMAND>;
00249
00250 template
00251 class GenericTactiles<ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS, ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND>;
00252 }
00253
00254
00255
00256
00257
00258
00259
00260