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


sr_ronex_drivers
Author(s): Ugo Cupcic, Toni Oliver, Mark Pitchless
autogenerated on Thu Jun 6 2019 21:22:00