00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00024 #include <sr_ronex_drivers/sr_spi.hpp>
00025 #include <ros_ethercat_model/robot_state.hpp>
00026 #include <ros_ethercat_hardware/ethercat_hardware.h>
00027
00028 #include <sstream>
00029 #include <iomanip>
00030 #include <boost/lexical_cast.hpp>
00031 #include <math.h>
00032 #include <string>
00033
00034 #include "sr_ronex_drivers/ronex_utils.hpp"
00035
00036 PLUGINLIB_EXPORT_CLASS(SrSPI, EthercatDevice);
00037
00038 using boost::lexical_cast;
00039
00040 const char SrSPI::product_alias_[] = PRODUCT_NAME;
00041
00042 SrSPI::SrSPI() :
00043 node_("~"), cycle_count_(0)
00044 {}
00045
00046 SrSPI::~SrSPI()
00047 {
00048
00049 string device_id = "/ronex/devices/" + lexical_cast<string>(parameter_id_);
00050 ros::param::del(device_id);
00051
00052 string controller_name = "/ronex_" + serial_number_ + "_passthrough";
00053 ros::param::del(controller_name);
00054
00055 string spi_device_name = "/ronex/spi/" + serial_number_;
00056 ros::param::del(spi_device_name);
00057 }
00058
00059 void SrSPI::construct(EtherCAT_SlaveHandler *sh, int &start_address)
00060 {
00061 sh_ = sh;
00062 serial_number_ = ronex::get_serial_number(sh);
00063
00064
00065 string path_to_alias, alias;
00066 path_to_alias = "/ronex/mapping/" + serial_number_;
00067 if ( ros::param::get(path_to_alias, alias))
00068 {
00069 ronex_id_ = alias;
00070 }
00071 else
00072 {
00073
00074 ronex_id_ = serial_number_;
00075 }
00076
00077 device_name_ = ronex::build_name(product_alias_, ronex_id_);
00078
00079 command_base_ = start_address;
00080 command_size_ = COMMAND_ARRAY_SIZE_BYTES;
00081
00082 start_address += command_size_;
00083 status_base_ = start_address;
00084 status_size_ = STATUS_ARRAY_SIZE_BYTES;
00085
00086 start_address += status_size_;
00087
00088
00089
00090
00091
00092
00093 if ( (PROTOCOL_TYPE) == (EC_BUFFERED) )
00094 {
00095 ROS_INFO("Using EC_BUFFERED");
00096 }
00097 else if ( (PROTOCOL_TYPE) == (EC_QUEUED) )
00098 {
00099 ROS_INFO("Using EC_QUEUED");
00100 }
00101
00102 ROS_INFO("First FMMU (command) : Logical address: 0x%08X ; size: %3d bytes ; ET1200 address: 0x%08X", command_base_,
00103 command_size_, static_cast<int>(COMMAND_ADDRESS) );
00104 EC_FMMU *commandFMMU = new EC_FMMU( command_base_,
00105 command_size_,
00106 0x00,
00107 0x07,
00108 COMMAND_ADDRESS,
00109 0x00,
00110 false,
00111 true,
00112 true);
00113
00114
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126 ROS_INFO("Second FMMU (status) : Logical address: 0x%08X ; size: %3d bytes ; ET1200 address: 0x%08X", status_base_,
00127 status_size_, static_cast<int>(STATUS_ADDRESS) );
00128 EC_FMMU *statusFMMU = new EC_FMMU( status_base_,
00129 status_size_,
00130 0x00,
00131 0x07,
00132 STATUS_ADDRESS,
00133 0x00,
00134 true,
00135 false,
00136 true);
00137
00138
00139 EtherCAT_FMMU_Config *fmmu = new EtherCAT_FMMU_Config(2);
00140
00141 (*fmmu)[0] = *commandFMMU;
00142 (*fmmu)[1] = *statusFMMU;
00143
00144 sh->set_fmmu_config(fmmu);
00145
00146 EtherCAT_PD_Config *pd = new EtherCAT_PD_Config(2);
00147
00148
00149 (*pd)[0] = EC_SyncMan(COMMAND_ADDRESS, command_size_, PROTOCOL_TYPE, EC_WRITTEN_FROM_MASTER);
00150 (*pd)[1] = EC_SyncMan(STATUS_ADDRESS, status_size_, PROTOCOL_TYPE);
00151
00152
00153 (*pd)[0].ChannelEnable = true;
00154 (*pd)[0].ALEventEnable = true;
00155 (*pd)[0].WriteEvent = true;
00156
00157 (*pd)[1].ChannelEnable = true;
00158
00159 sh->set_pd_config(pd);
00160
00161 ROS_INFO("Finished constructing the SrSPI driver");
00162 }
00163
00164 int SrSPI::initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed)
00165 {
00166 digital_commands_ = 0;
00167 ROS_INFO("Device #%02d: Product code: %u (%#010X) , Serial #: %u (%#010X)",
00168 sh_->get_ring_position(),
00169 sh_->get_product_code(),
00170 sh_->get_product_code(),
00171 sh_->get_serial(),
00172 sh_->get_serial());
00173
00174 device_offset_ = sh_->get_ring_position();
00175
00176
00177 ros_ethercat_model::RobotState *robot_state = static_cast<ros_ethercat_model::RobotState*>(hw);
00178 robot_state->custom_hws_.insert(device_name_, new ronex::SPI());
00179 spi_ = static_cast<ronex::SPI*>(robot_state->getCustomHW(device_name_));
00180
00181 build_topics_();
00182
00183 ROS_INFO_STREAM("Adding a SPI RoNeX module to the hardware interface: " << device_name_);
00184
00185
00186 return 0;
00187 }
00188
00189 void SrSPI::packCommand(unsigned char *buffer, bool halt, bool reset)
00190 {
00191 RONEX_COMMAND_02000002* command = reinterpret_cast<RONEX_COMMAND_02000002*>(buffer);
00192
00193
00194 command->command_type = spi_->command_->command_type;
00195 command->pin_output_states_pre = spi_->command_->pin_output_states_pre;
00196 command->pin_output_states_post = spi_->command_->pin_output_states_post;
00197
00198 for (size_t spi_index = 0; spi_index < NUM_SPI_OUTPUTS; ++spi_index)
00199 {
00200 command->spi_out[spi_index].clock_divider = spi_->command_->spi_out[spi_index].clock_divider;
00201 command->spi_out[spi_index].SPI_config = spi_->command_->spi_out[spi_index].SPI_config;
00202 command->spi_out[spi_index].inter_byte_gap = spi_->command_->spi_out[spi_index].inter_byte_gap;
00203 command->spi_out[spi_index].num_bytes = spi_->command_->spi_out[spi_index].num_bytes;
00204
00205 for ( size_t i = 0; i < SPI_TRANSACTION_MAX_SIZE; ++i )
00206 command->spi_out[spi_index].data_bytes[i] = spi_->command_->spi_out[spi_index].data_bytes[i];
00207
00208 if ( command->spi_out[spi_index].num_bytes != 0)
00209 {
00210 ostringstream ss;
00211 ss << "SPI out [" << spi_index << "]: Sending non null command("
00212 <<static_cast<unsigned int>(command->spi_out[spi_index].num_bytes) << "): -> ";
00213
00214 for (unsigned int i = 0; i < static_cast<unsigned int>(command->spi_out[spi_index].num_bytes); ++i)
00215 ss << static_cast<int>(command->spi_out[spi_index].data_bytes[i]) << ",";
00216
00217 ROS_DEBUG_STREAM("" << ss.str());
00218 }
00219 }
00220 }
00221
00222 bool SrSPI::unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
00223 {
00224 RONEX_STATUS_02000002* status_data = reinterpret_cast<RONEX_STATUS_02000002 *>(this_buffer+ command_size_);
00225
00226
00227
00228
00229
00230
00231
00232 if ( status_data->command_type == RONEX_COMMAND_02000002_COMMAND_TYPE_NORMAL)
00233 {
00234
00235 spi_->state_->command_type = status_data->command_type;
00236
00237 for (size_t sampling = 0; sampling < NUM_DIO_SAMPLES; ++sampling)
00238 {
00239 spi_->state_->info_type.status_data.pin_input_states_DIO[sampling] =
00240 status_data->info_type.status_data.pin_input_states_DIO[sampling];
00241 spi_->state_->info_type.status_data.pin_input_states_SOMI[sampling] =
00242 status_data->info_type.status_data.pin_input_states_SOMI[sampling];
00243 }
00244
00245 for (size_t spi_index=0; spi_index < NUM_SPI_OUTPUTS; ++spi_index)
00246 {
00247 for (size_t i = 0; i < SPI_TRANSACTION_MAX_SIZE; ++i)
00248 {
00249 spi_->state_->info_type.status_data.spi_in[spi_index].data_bytes[i] =
00250 status_data->info_type.status_data.spi_in[spi_index].data_bytes[i];
00251
00252
00253
00254
00255
00256
00257 }
00258 }
00259
00260 for (size_t analogue_index = 0 ; analogue_index < NUM_ANALOGUE_INPUTS ; ++analogue_index)
00261 {
00262 spi_->state_->info_type.status_data.analogue_in[analogue_index] =
00263 status_data->info_type.status_data.analogue_in[analogue_index];
00264 }
00265 }
00266 else if ( status_data->command_type == RONEX_COMMAND_02000002_COMMAND_TYPE_CONFIG_INFO)
00267 {
00268
00269 }
00270
00271
00272 if (cycle_count_ > 9)
00273 {
00274 state_msg_.header.stamp = ros::Time::now();
00275
00276 state_msg_.command_type = spi_->state_->command_type;
00277
00278 for (size_t sampling = 0; sampling < NUM_DIO_SAMPLES; ++sampling)
00279 {
00280 state_msg_.pin_input_states_DIO[sampling] = spi_->state_->info_type.status_data.pin_input_states_DIO[sampling];
00281 state_msg_.pin_input_states_SOMI[sampling] = spi_->state_->info_type.status_data.pin_input_states_SOMI[sampling];
00282 }
00283
00284 for (size_t spi_index=0; spi_index < NUM_SPI_OUTPUTS; ++spi_index)
00285 {
00286 for (size_t i = 0; i < SPI_TRANSACTION_MAX_SIZE; ++i)
00287 state_msg_.spi_in[spi_index].data[i] = spi_->state_->info_type.status_data.spi_in[spi_index].data_bytes[i];
00288 }
00289
00290 for (size_t analogue_index = 0 ; analogue_index < NUM_ANALOGUE_INPUTS ; ++analogue_index)
00291 {
00292 state_msg_.analogue_in[analogue_index] = spi_->state_->info_type.status_data.analogue_in[analogue_index];
00293 }
00294
00295
00296 if ( state_publisher_->trylock() )
00297 {
00298 state_publisher_->msg_ = state_msg_;
00299 state_publisher_->unlockAndPublish();
00300 }
00301
00302 cycle_count_ = 0;
00303 }
00304
00305 cycle_count_++;
00306 return true;
00307 }
00308
00309 void SrSPI::diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer)
00310 {
00311 d.name = device_name_;
00312 d.summary(d.OK, "OK");
00313 d.hardware_id = serial_number_;
00314
00315 d.clear();
00316
00317
00318 }
00319
00320 void SrSPI::build_topics_()
00321 {
00322
00323 parameter_id_ = ronex::get_ronex_param_id("");
00324 ostringstream param_path, tmp_param;
00325 param_path << "/ronex/devices/" << parameter_id_ << "/";
00326 tmp_param << ronex::get_product_code(sh_);
00327 ros::param::set(param_path.str() + "product_id", tmp_param.str());
00328 ros::param::set(param_path.str() + "product_name", product_alias_);
00329 ros::param::set(param_path.str() + "ronex_id", ronex_id_);
00330
00331
00332 ros::param::set(param_path.str() + "path", device_name_);
00333 ros::param::set(param_path.str() + "serial", serial_number_);
00334
00335
00336 state_publisher_.reset(
00337 new realtime_tools::RealtimePublisher<sr_ronex_msgs::SPIState>(node_, device_name_ + "/state", 1));
00338 }
00339
00340
00341
00342
00343
00344