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
00033 #include "sr_ronex_drivers/ronex_utils.hpp"
00034
00035 PLUGINLIB_EXPORT_CLASS(SrSPI, EthercatDevice);
00036
00037 using namespace std;
00038 using boost::lexical_cast;
00039
00040 const string 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_, command_size_,
00103 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 ROS_INFO("Second FMMU (status) : Logical address: 0x%08X ; size: %3d bytes ; ET1200 address: 0x%08X", status_base_, status_size_,
00126 static_cast<int>(STATUS_ADDRESS) );
00127 EC_FMMU *statusFMMU = new EC_FMMU( status_base_,
00128 status_size_,
00129 0x00,
00130 0x07,
00131 STATUS_ADDRESS,
00132 0x00,
00133 true,
00134 false,
00135 true);
00136
00137
00138 EtherCAT_FMMU_Config *fmmu = new EtherCAT_FMMU_Config(2);
00139
00140 (*fmmu)[0] = *commandFMMU;
00141 (*fmmu)[1] = *statusFMMU;
00142
00143 sh->set_fmmu_config(fmmu);
00144
00145 EtherCAT_PD_Config *pd = new EtherCAT_PD_Config(2);
00146
00147
00148 (*pd)[0] = EC_SyncMan(COMMAND_ADDRESS, command_size_, PROTOCOL_TYPE, EC_WRITTEN_FROM_MASTER);
00149 (*pd)[1] = EC_SyncMan(STATUS_ADDRESS, status_size_, PROTOCOL_TYPE);
00150
00151
00152 (*pd)[0].ChannelEnable = true;
00153 (*pd)[0].ALEventEnable = true;
00154 (*pd)[0].WriteEvent = true;
00155
00156 (*pd)[1].ChannelEnable = true;
00157
00158 sh->set_pd_config(pd);
00159
00160 ROS_INFO("Finished constructing the SrSPI driver");
00161 }
00162
00163 int SrSPI::initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed)
00164 {
00165 digital_commands_ = 0;
00166 ROS_INFO("Device #%02d: Product code: %u (%#010X) , Serial #: %u (%#010X)",
00167 sh_->get_ring_position(),
00168 sh_->get_product_code(),
00169 sh_->get_product_code(),
00170 sh_->get_serial(),
00171 sh_->get_serial());
00172
00173 device_offset_ = sh_->get_ring_position();
00174
00175
00176 ros_ethercat_model::RobotState *robot_state = static_cast<ros_ethercat_model::RobotState*>(hw);
00177 robot_state->custom_hws_.insert(device_name_, new ronex::SPI());
00178 spi_ = static_cast<ronex::SPI*>(robot_state->getCustomHW(device_name_));
00179
00180 build_topics_();
00181
00182 ROS_INFO_STREAM("Adding a SPI RoNeX module to the hardware interface: " << device_name_);
00183
00184
00185 return 0;
00186 }
00187
00188 void SrSPI::packCommand(unsigned char *buffer, bool halt, bool reset)
00189 {
00190 RONEX_COMMAND_02000002* command = (RONEX_COMMAND_02000002*)(buffer);
00191
00192
00193 command->command_type = spi_->command_->command_type;
00194 command->pin_output_states_pre = spi_->command_->pin_output_states_pre;
00195 command->pin_output_states_post = spi_->command_->pin_output_states_post;
00196
00197 for(size_t spi_index = 0; spi_index < NUM_SPI_OUTPUTS; ++spi_index)
00198 {
00199 command->spi_out[spi_index].clock_divider = spi_->command_->spi_out[spi_index].clock_divider;
00200 command->spi_out[spi_index].SPI_config = spi_->command_->spi_out[spi_index].SPI_config;
00201 command->spi_out[spi_index].inter_byte_gap = spi_->command_->spi_out[spi_index].inter_byte_gap;
00202 command->spi_out[spi_index].num_bytes = spi_->command_->spi_out[spi_index].num_bytes;
00203
00204 for( size_t i = 0; i < SPI_TRANSACTION_MAX_SIZE; ++i )
00205 command->spi_out[spi_index].data_bytes[i] = spi_->command_->spi_out[spi_index].data_bytes[i];
00206
00207 if( command->spi_out[spi_index].num_bytes != 0)
00208 {
00209 ostringstream ss;
00210 ss << "SPI out ["<<spi_index<<"]: Sending non null command("<<static_cast<unsigned int>(command->spi_out[spi_index].num_bytes)<<"): -> ";
00211
00212 for(unsigned int i =0; i < static_cast<unsigned int>(command->spi_out[spi_index].num_bytes); ++i)
00213 ss << static_cast<int>(command->spi_out[spi_index].data_bytes[i]) << ",";
00214
00215 ROS_DEBUG_STREAM("" << ss.str());
00216 }
00217 }
00218 }
00219
00220 bool SrSPI::unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
00221 {
00222 RONEX_STATUS_02000002* status_data = (RONEX_STATUS_02000002 *)(this_buffer+ command_size_);
00223
00224
00225 spi_->state_->command_type = status_data->command_type;
00226
00227 for(size_t sampling = 0; sampling < NUM_DIO_SAMPLES; ++sampling)
00228 {
00229 spi_->state_->info_type.status_data.pin_input_states_DIO[sampling] = status_data->info_type.status_data.pin_input_states_DIO[sampling];
00230 spi_->state_->info_type.status_data.pin_input_states_SOMI[sampling] = status_data->info_type.status_data.pin_input_states_SOMI[sampling];
00231 }
00232
00233 for (size_t spi_index=0; spi_index < NUM_SPI_OUTPUTS; ++spi_index)
00234 {
00235 for(size_t i = 0; i < SPI_TRANSACTION_MAX_SIZE; ++i)
00236 {
00237 spi_->state_->info_type.status_data.spi_in[spi_index].data_bytes[i] = status_data->info_type.status_data.spi_in[spi_index].data_bytes[i];
00238
00239
00240
00241
00242
00243 }
00244 }
00245
00246 for(size_t analogue_index = 0 ; analogue_index < NUM_ANALOGUE_INPUTS ; ++analogue_index)
00247 {
00248 spi_->state_->info_type.status_data.analogue_in[analogue_index] = status_data->info_type.status_data.analogue_in[analogue_index];
00249 }
00250
00251
00252 if(cycle_count_ > 9)
00253 {
00254 state_msg_.header.stamp = ros::Time::now();
00255
00256 state_msg_.command_type = spi_->state_->command_type;
00257
00258 for(size_t sampling = 0; sampling < NUM_DIO_SAMPLES; ++sampling)
00259 {
00260 state_msg_.pin_input_states_DIO[sampling] = spi_->state_->info_type.status_data.pin_input_states_DIO[sampling];
00261 state_msg_.pin_input_states_SOMI[sampling] = spi_->state_->info_type.status_data.pin_input_states_SOMI[sampling];
00262 }
00263
00264 for (size_t spi_index=0; spi_index < NUM_SPI_OUTPUTS; ++spi_index)
00265 {
00266 for(size_t i = 0; i < SPI_TRANSACTION_MAX_SIZE; ++i)
00267 state_msg_.spi_in[spi_index].data[i] = spi_->state_->info_type.status_data.spi_in[spi_index].data_bytes[i];
00268 }
00269
00270 for(size_t analogue_index = 0 ; analogue_index < NUM_ANALOGUE_INPUTS ; ++analogue_index)
00271 {
00272 state_msg_.analogue_in[analogue_index] = spi_->state_->info_type.status_data.analogue_in[analogue_index];
00273 }
00274
00275
00276 if( state_publisher_->trylock() )
00277 {
00278 state_publisher_->msg_ = state_msg_;
00279 state_publisher_->unlockAndPublish();
00280 }
00281
00282 cycle_count_ = 0;
00283 }
00284
00285 cycle_count_++;
00286 return true;
00287 }
00288
00289 void SrSPI::diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer)
00290 {
00291 d.name = device_name_;
00292 d.summary(d.OK, "OK");
00293 d.hardware_id = serial_number_;
00294
00295 d.clear();
00296
00297
00298 }
00299
00300 void SrSPI::build_topics_()
00301 {
00302
00303 parameter_id_ = ronex::get_ronex_param_id("");
00304 ostringstream param_path, tmp_param;
00305 param_path << "/ronex/devices/" << parameter_id_ << "/";
00306 tmp_param << ronex::get_product_code(sh_);
00307 ros::param::set(param_path.str() + "product_id", tmp_param.str());
00308 ros::param::set(param_path.str() + "product_name", product_alias_);
00309 ros::param::set(param_path.str() + "ronex_id", ronex_id_);
00310
00311
00312 ros::param::set(param_path.str() + "path", device_name_);
00313 ros::param::set(param_path.str() + "serial", serial_number_);
00314
00315
00316 state_publisher_.reset(new realtime_tools::RealtimePublisher<sr_ronex_msgs::SPIState>(node_, device_name_ + "/state", 1));
00317 }
00318
00319
00320
00321
00322
00323