sr_board_mk2_gio.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Shadow Robot Company, All rights reserved.
00003  * 
00004  * This library is free software; you can redistribute it and/or
00005  * modify it under the terms of the GNU Lesser General Public
00006  * License as published by the Free Software Foundation; either
00007  * version 3.0 of the License, or (at your option) any later version.
00008  * 
00009  * This library is distributed in the hope that it will be useful,
00010  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00011  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
00012  * Lesser General Public License for more details.
00013  * 
00014  * You should have received a copy of the GNU Lesser General Public
00015  * License along with this library.
00016  */
00017 
00024 #include <sr_ronex_drivers/sr_board_mk2_gio.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(SrBoardMk2GIO, EthercatDevice);
00036 
00037 const std::string SrBoardMk2GIO::product_alias_ = "general_io";
00038 using boost::lexical_cast;
00039 
00040 
00041 SrBoardMk2GIO::SrBoardMk2GIO() :
00042   node_("~"), cycle_count_(0), has_stacker_(false)
00043 {}
00044 
00045 SrBoardMk2GIO::~SrBoardMk2GIO()
00046 {
00047   //remove parameters from server
00048   string device_id = "/ronex/devices/" + lexical_cast<string>(parameter_id_ );
00049   ros::param::del(device_id);
00050 
00051   string general_io_name = "/ronex/general_io/" + serial_number_;
00052   ros::param::del(general_io_name);
00053 
00054   string controller_name = "/ronex_" + serial_number_ + "_passthrough";
00055 }
00056 
00057 void SrBoardMk2GIO::construct(EtherCAT_SlaveHandler *sh, int &start_address)
00058 {
00059   sh_ = sh;
00060   serial_number_ = ronex::get_serial_number( sh );
00061 
00062   //get the alias from the parameter server if it exists
00063   std::string path_to_alias, alias;
00064   path_to_alias = "/ronex/mapping/" + serial_number_;
00065   if( ros::param::get(path_to_alias, alias))
00066   {
00067     ronex_id_ = alias;
00068   }
00069   else
00070   {
00071     //no alias found, using the serial number directly.
00072     ronex_id_ = serial_number_ ;
00073   }
00074 
00075   device_name_ = ronex::build_name( product_alias_, ronex_id_ );
00076 
00077   command_base_  = start_address;
00078   command_size_  = COMMAND_ARRAY_SIZE_BYTES;
00079 
00080   start_address += command_size_;
00081   status_base_   = start_address;
00082   status_size_   = STATUS_ARRAY_SIZE_BYTES;
00083 
00084   start_address += status_size_;
00085 
00086   // ETHERCAT_COMMAND_DATA
00087   //
00088   // This is for data going TO the board
00089   //
00090 
00091   if ( (PROTOCOL_TYPE) == (EC_BUFFERED) )
00092   {
00093     ROS_INFO("Using EC_BUFFERED");
00094   }
00095   else if ( (PROTOCOL_TYPE) == (EC_QUEUED) )
00096   {
00097     ROS_INFO("Using EC_QUEUED");
00098   }
00099 
00100   ROS_INFO("First FMMU (command) : Logical address: 0x%08X ; size: %3d bytes ; ET1200 address: 0x%08X", command_base_, command_size_,
00101            static_cast<int>(COMMAND_ADDRESS) );
00102   EC_FMMU *commandFMMU = new EC_FMMU( command_base_,            // Logical Start Address    (in ROS address space?)
00103                                       command_size_,
00104                                       0x00,                   // Logical Start Bit
00105                                       0x07,                   // Logical End Bit
00106                                       COMMAND_ADDRESS,        // Physical Start Address   (in ET1200 address space?)
00107                                       0x00,                   // Physical Start Bit
00108                                       false,                   // Read Enable
00109                                       true,                    // Write Enable
00110                                       true                     // Channel Enable
00111     );
00112 
00113 
00114   // WARNING!!!
00115   // We are leaving (command_size_ * 4) bytes in the physical memory of the device, but strictly we only need to
00116   // leave (command_size_ * 3). This change should be done in the firmware as well, otherwise it won't work.
00117   // This triple buffer is needed in the ethercat devices to work in EC_BUFFERED mode (in opposition to the other mode EC_QUEUED, the so called mailbox mode)
00118 
00119   // ETHERCAT_STATUS_DATA
00120   //
00121   // This is for data coming FROM the board
00122   //
00123   ROS_INFO("Second FMMU (status) : Logical address: 0x%08X ; size: %3d bytes ; ET1200 address: 0x%08X", status_base_, status_size_,
00124            static_cast<int>(STATUS_ADDRESS) );
00125   EC_FMMU *statusFMMU = new EC_FMMU(  status_base_,
00126                                       status_size_,
00127                                       0x00,
00128                                       0x07,
00129                                       STATUS_ADDRESS,
00130                                       0x00,
00131                                       true,
00132                                       false,
00133                                       true);
00134 
00135 
00136   EtherCAT_FMMU_Config *fmmu = new EtherCAT_FMMU_Config(2);
00137 
00138   (*fmmu)[0] = *commandFMMU;
00139   (*fmmu)[1] = *statusFMMU;
00140 
00141   sh->set_fmmu_config(fmmu);
00142 
00143   EtherCAT_PD_Config *pd = new EtherCAT_PD_Config(2);
00144 
00145 // SyncMan takes the physical address
00146   (*pd)[0] = EC_SyncMan(COMMAND_ADDRESS,              command_size_,    PROTOCOL_TYPE, EC_WRITTEN_FROM_MASTER);
00147   (*pd)[1] = EC_SyncMan(STATUS_ADDRESS,               status_size_,     PROTOCOL_TYPE);
00148 
00149 
00150   (*pd)[0].ChannelEnable = true;
00151   (*pd)[0].ALEventEnable = true;
00152   (*pd)[0].WriteEvent    = true;
00153 
00154   (*pd)[1].ChannelEnable = true;
00155 
00156   sh->set_pd_config(pd);
00157 
00158   ROS_INFO("Finished constructing the SrBoardMk2GIO driver");
00159 }
00160 
00161 int SrBoardMk2GIO::initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed)
00162 {
00163   digital_commands_ = 0;
00164   ROS_INFO("Device #%02d: Product code: %u (%#010X) , Serial #: %u (%#010X)",
00165             sh_->get_ring_position(),
00166             sh_->get_product_code(),
00167             sh_->get_product_code(),
00168             sh_->get_serial(),
00169             sh_->get_serial());
00170 
00171   device_offset_ = sh_->get_ring_position();
00172 
00173   //add the RoNeX to the hw interface
00174   ros_ethercat_model::RobotState *robot_state = static_cast<ros_ethercat_model::RobotState*>(hw);
00175   robot_state->custom_hws_.insert(device_name_, new ronex::GeneralIO());
00176   general_io_ = static_cast<ronex::GeneralIO*>(robot_state->getCustomHW(device_name_));
00177 
00178   build_topics_();
00179 
00180   ROS_INFO_STREAM("Adding a general_io RoNeX module to the hardware interface: " << device_name_);
00181   //Using the name of the ronex to prefix the state topic
00182 
00183   return 0;
00184 }
00185 
00186 void SrBoardMk2GIO::packCommand(unsigned char *buffer, bool halt, bool reset)
00187 {
00188   RONEX_COMMAND_02000001* command = (RONEX_COMMAND_02000001*)(buffer);
00189 
00190   command->command_type = RONEX_COMMAND_02000001_COMMAND_TYPE_NORMAL;
00191 
00192   //digital command
00193   for (size_t i = 0; i < general_io_->command_.digital_.size(); ++i)
00194   {
00195     if (input_mode_[i])
00196     {
00197       // Just set the pin to input mode, gets read in the status
00198       ronex::set_bit(digital_commands_, i*2, 1);
00199     }
00200     else
00201     { // Output
00202       ronex::set_bit(digital_commands_, i*2, 0);
00203       ronex::set_bit(digital_commands_, i*2+1, general_io_->command_.digital_[i]);
00204     }
00205   }
00206 
00207   command->digital_out = static_cast<int32u>(digital_commands_);
00208 
00209   //PWM command
00210   for (size_t i = 0; i < general_io_->command_.pwm_.size(); ++i)
00211   {
00212     command->pwm_module[i].pwm_period = general_io_->command_.pwm_[i].period;
00213     command->pwm_module[i].pwm_on_time_0 = general_io_->command_.pwm_[i].on_time_0;
00214     command->pwm_module[i].pwm_on_time_1 = general_io_->command_.pwm_[i].on_time_1;
00215   }
00216 
00217   command->pwm_clock_divider = general_io_->command_.pwm_clock_divider_;
00218 }
00219 
00220 bool SrBoardMk2GIO::unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
00221 {
00222   RONEX_STATUS_02000001* status_data = (RONEX_STATUS_02000001 *)(this_buffer+  command_size_);
00223 
00224   // Checking that the received command type matches RONEX_COMMAND_02000001_COMMAND_TYPE_NORMAL
00225   // (the one that was used in the command). The ronex firmware will answer with whatever command type we send.
00226   // The purpose of this is to filter those status_data structures that come filled with zeros due to the jitter
00227   // in the realtime loop. The jitter causes that the host tries to read the status when the microcontroller in the ronex
00228   // module has not finished writing it to memory yet.
00229   if( status_data->command_type == RONEX_COMMAND_02000001_COMMAND_TYPE_NORMAL)
00230   {
00231     if( general_io_->state_.analogue_.empty())
00232     {
00233       size_t nb_analogue_pub, nb_digital_io, nb_pwm_modules;
00234       //The publishers haven't been initialised yet.
00235       // Checking if the stacker board is plugged in or not
00236       // to determine the number of publishers.
00237       if (status_data->flags & RONEX_02000001_FLAGS_STACKER_0_PRESENT)
00238       {
00239         has_stacker_ = true;
00240         nb_analogue_pub = NUM_ANALOGUE_INPUTS;
00241         nb_digital_io = NUM_DIGITAL_IO;
00242         nb_pwm_modules = NUM_PWM_MODULES;
00243       }
00244       else
00245       {
00246         has_stacker_ = false;
00247         nb_analogue_pub = NUM_ANALOGUE_INPUTS / 2;
00248         nb_digital_io = NUM_DIGITAL_IO / 2;
00249         nb_pwm_modules = NUM_PWM_MODULES / 2;
00250       }
00251 
00252       //resizing the GeneralIO in the HardwareInterface
00253       general_io_->state_.analogue_.resize(nb_analogue_pub);
00254       general_io_->state_.digital_.resize(nb_digital_io);
00255       general_io_->command_.digital_.resize(nb_digital_io);
00256       general_io_->command_.pwm_.resize(nb_pwm_modules);
00257 
00258       input_mode_.assign(nb_digital_io, true);
00259 
00260       //init the state message
00261       state_msg_.analogue.resize(nb_analogue_pub);
00262       state_msg_.digital.resize(nb_digital_io);
00263       state_msg_.input_mode.resize(nb_digital_io);
00264 
00265       //dynamic reconfigure server is instantiated here
00266       // as we need the different vectors to be initialised
00267       // before running the first configuration.
00268       dynamic_reconfigure_server_.reset(new dynamic_reconfigure::Server<sr_ronex_drivers::GeneralIOConfig>(ros::NodeHandle(device_name_)));
00269       function_cb_ = boost::bind(&SrBoardMk2GIO::dynamic_reconfigure_cb, this, _1, _2);
00270       dynamic_reconfigure_server_->setCallback(function_cb_);
00271     } //end first time, the sizes are properly initialised, simply fill in the data
00272 
00273     for(size_t i = 0; i < general_io_->state_.analogue_.size(); ++i )
00274     {
00275       general_io_->state_.analogue_[i] = status_data->analogue_in[i];
00276     }
00277 
00278     for(size_t i = 0; i < general_io_->state_.digital_.size(); ++i )
00279     {
00280       general_io_->state_.digital_[i] = ronex::check_bit(status_data->digital_in, i);
00281     }
00282   }
00283 
00284   //publishing at 100Hz
00285   if(cycle_count_ > 9)
00286   {
00287     state_msg_.header.stamp = ros::Time::now();
00288 
00289     //update state message
00290     for(size_t i=0; i < general_io_->state_.analogue_.size(); ++i)
00291     {
00292       state_msg_.analogue[i] = general_io_->state_.analogue_[i];
00293     }
00294 
00295     for(size_t i=0; i < general_io_->state_.digital_.size(); ++i)
00296     {
00297       state_msg_.digital[i] = general_io_->state_.digital_[i];
00298       state_msg_.input_mode[i] = input_mode_[i];
00299     }
00300 
00301     state_msg_.pwm_clock_divider = general_io_->command_.pwm_clock_divider_;
00302 
00303     //publish
00304     if( state_publisher_->trylock() )
00305     {
00306       state_publisher_->msg_ = state_msg_;
00307       state_publisher_->unlockAndPublish();
00308     }
00309 
00310     cycle_count_ = 0;
00311   }
00312 
00313   cycle_count_++;
00314   return true;
00315 }
00316 
00317 void SrBoardMk2GIO::diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer)
00318 {
00319   d.name = device_name_;
00320   d.summary(d.OK, "OK");
00321   d.hardware_id = serial_number_;
00322 
00323   d.clear();
00324   if(has_stacker_)
00325     d.addf("Stacker Board", "True");
00326   else
00327     d.addf("Stacker Board", "False");
00328 }
00329 
00330 
00331 void SrBoardMk2GIO::dynamic_reconfigure_cb(sr_ronex_drivers::GeneralIOConfig &config, uint32_t level)
00332 {
00333   general_io_->command_.pwm_clock_divider_ = static_cast<int16u>(config.pwm_clock_divider);
00334 
00335   //not very pretty but I couldnt think of an easy way to set them up
00336   // (dynamic reconfigure doesn't seem to support arrays)
00337   if(general_io_->command_.digital_.size() > 0)
00338     input_mode_[0] = config.input_mode_0;
00339   if(general_io_->command_.digital_.size() > 1)
00340     input_mode_[1] = config.input_mode_1;
00341   if(general_io_->command_.digital_.size() > 2)
00342     input_mode_[2] = config.input_mode_2;
00343   if(general_io_->command_.digital_.size() > 3)
00344     input_mode_[3] = config.input_mode_3;
00345   if(general_io_->command_.digital_.size() > 4)
00346     input_mode_[4] = config.input_mode_4;
00347   if(general_io_->command_.digital_.size() > 5)
00348     input_mode_[5] = config.input_mode_5;
00349   if(general_io_->command_.digital_.size() > 6)
00350     input_mode_[6] = config.input_mode_6;
00351   if(general_io_->command_.digital_.size() > 7)
00352     input_mode_[7] = config.input_mode_7;
00353   if(general_io_->command_.digital_.size() > 8)
00354     input_mode_[8] = config.input_mode_8;
00355   if(general_io_->command_.digital_.size() > 9)
00356     input_mode_[9] = config.input_mode_9;
00357   if(general_io_->command_.digital_.size() > 10)
00358     input_mode_[10] = config.input_mode_10;
00359   if(general_io_->command_.digital_.size() > 11)
00360     input_mode_[11] = config.input_mode_11;
00361 
00362   if( general_io_->command_.pwm_.size() > 0 )
00363     general_io_->command_.pwm_[0].period = static_cast<int16u>(config.pwm_period_0);
00364   if( general_io_->command_.pwm_.size() > 1 )
00365     general_io_->command_.pwm_[1].period = static_cast<int16u>(config.pwm_period_1);
00366   if( general_io_->command_.pwm_.size() > 2 )
00367     general_io_->command_.pwm_[2].period = static_cast<int16u>(config.pwm_period_2);
00368   if( general_io_->command_.pwm_.size() > 3 )
00369     general_io_->command_.pwm_[3].period = static_cast<int16u>(config.pwm_period_3);
00370   if( general_io_->command_.pwm_.size() > 4 )
00371     general_io_->command_.pwm_[4].period = static_cast<int16u>(config.pwm_period_4);
00372   if( general_io_->command_.pwm_.size() > 5 )
00373     general_io_->command_.pwm_[5].period = static_cast<int16u>(config.pwm_period_5);
00374 }
00375 
00376 void SrBoardMk2GIO::build_topics_()
00377 {
00378   //loading everything into the parameter server
00379   parameter_id_ = ronex::get_ronex_param_id("");
00380   std::stringstream param_path, tmp_param;
00381   param_path << "/ronex/devices/" << parameter_id_ << "/";
00382   tmp_param << ronex::get_product_code(sh_);
00383   ros::param::set(param_path.str() + "product_id", tmp_param.str());
00384   ros::param::set(param_path.str() + "product_name", product_alias_);
00385   ros::param::set(param_path.str() + "ronex_id", ronex_id_);
00386 
00387   //the device is stored using path as the key in the CustomHW map
00388   ros::param::set(param_path.str() + "path", device_name_);
00389   ros::param::set(param_path.str() + "serial", serial_number_);
00390 
00391   //Advertising the realtime state publisher
00392   state_publisher_.reset(new realtime_tools::RealtimePublisher<sr_ronex_msgs::GeneralIOState>(node_, device_name_ + "/state", 1));
00393 }
00394 
00395 /* For the emacs weenies in the crowd.
00396    Local Variables:
00397    c-basic-offset: 2
00398    End:
00399 */


sr_ronex_drivers
Author(s): Ugo Cupcic, Toni Oliver, Mark Pitchless
autogenerated on Fri Aug 28 2015 13:12:23