cod_decod_std_io.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 
00029 #include "sr_ronex_drivers/cod_decod/cod_decod_std_io.hpp"
00030 #include <sstream>
00031 
00032 PLUGINLIB_EXPORT_CLASS(sr_cod_decod::CodDecodStdIo, sr_cod_decod::CodDecod);
00033 
00034 namespace sr_cod_decod
00035 {
00036   CodDecodStdIo::CodDecodStdIo()
00037     :CodDecod(),
00038      n_digital_outputs_(0),
00039      n_analog_outputs_(0),
00040      n_digital_inputs_(0),
00041      n_analog_inputs_(0),
00042      n_PWM_outputs_(0),
00043      command_size_(0),
00044      status_size_(0),
00045      digital_input_state_publisher_(NULL),
00046      analog_input_state_publisher_(NULL)
00047   {
00048   }
00049 
00050   void CodDecodStdIo::construct(hardware_interface::HardwareInterface *hw, EtherCAT_SlaveHandler *sh, int n_digital_outputs, int n_analog_outputs, int n_digital_inputs, int n_analog_inputs, int n_PWM_outputs)
00051   {
00052     CodDecod::construct(hw, sh, n_digital_outputs, n_analog_outputs, n_digital_inputs, n_analog_inputs, n_PWM_outputs);
00053     n_digital_outputs_ = n_digital_outputs;
00054     n_analog_outputs_ = n_analog_outputs;
00055     n_digital_inputs_ = n_digital_inputs;
00056     n_analog_inputs_ = n_analog_inputs;
00057     n_PWM_outputs_ = n_PWM_outputs;
00058 
00059     int dig_out_size = 0;
00060     if (n_digital_outputs_ > 0 )
00061       dig_out_size = ((n_digital_outputs_/16 + 1) * 2);
00062 
00063     command_size_ = dig_out_size + (n_PWM_outputs_ * 4) + (n_analog_outputs_ * 2);
00064 
00065     int dig_in_size = 0;
00066     if (n_digital_inputs_ > 0 )
00067       dig_in_size = ((n_digital_inputs_/16 + 1) * 2);
00068 
00069     status_size_ = dig_in_size + (n_analog_inputs_ * 2);
00070 
00071     node_ = ros::NodeHandle();
00072 
00073     //Initialise digital outputs to 0
00074     boost::shared_ptr<sr_ronex_msgs::BoolArray> d_out_ptr(new sr_ronex_msgs::BoolArray());
00075     d_out_ptr->data.clear();
00076     for (unsigned i = 0; i < n_digital_outputs_; ++i)
00077     {
00078       d_out_ptr->data.push_back(false);
00079     }
00080     digital_output_.set(d_out_ptr);
00081 
00082     //Initialise analog outputs to 0
00083     boost::shared_ptr<std_msgs::UInt16MultiArray> a_out_ptr(new std_msgs::UInt16MultiArray());
00084     a_out_ptr->data.clear();
00085     for (unsigned i = 0; i < n_analog_outputs_; ++i)
00086     {
00087       a_out_ptr->data.push_back(0x0000);
00088     }
00089     analog_output_.set(a_out_ptr);
00090 
00091     //Initialise PWM outputs to 0
00092     boost::shared_ptr<std_msgs::UInt16MultiArray> PWM_out_ptr(new std_msgs::UInt16MultiArray());
00093     PWM_out_ptr->data.clear();
00094     for (unsigned i = 0; i < (n_PWM_outputs_ * 2); ++i)
00095     {
00096       PWM_out_ptr->data.push_back(0x0000);
00097     }
00098     PWM_output_.set(PWM_out_ptr);
00099 
00100 
00101     char buff[200];
00102     string topic;
00103 
00104     sprintf(buff, "device_0x%08X_0x%08X_digital_outputs_command",
00105             sh_->get_product_code(),
00106             sh_->get_serial());
00107     topic = buff;
00108     sub_digital_output_command_ = node_.subscribe<sr_ronex_msgs::BoolArray>(topic, 1, &CodDecodStdIo::digitalOutputCommandCB, this);
00109 
00110 
00111     sprintf(buff, "device_0x%08X_0x%08X_analog_outputs_command",
00112             sh_->get_product_code(),
00113             sh_->get_serial());
00114     topic = buff;
00115     sub_analog_output_command_ = node_.subscribe<std_msgs::UInt16MultiArray>(topic, 1, &CodDecodStdIo::analogOutputCommandCB, this);
00116 
00117     sprintf(buff, "device_0x%08X_0x%08X_PWM_outputs_command",
00118             sh_->get_product_code(),
00119             sh_->get_serial());
00120         topic = buff;
00121     sub_PWM_output_command_ = node_.subscribe<std_msgs::UInt16MultiArray>(topic, 1, &CodDecodStdIo::PWMOutputCommandCB, this);
00122 
00123 
00124     sprintf(buff, "device_0x%08X_0x%08X_digital_inputs_state",
00125             sh_->get_product_code(),
00126             sh_->get_serial());
00127     topic = buff;
00128     digital_input_state_publisher_.reset(new realtime_tools::RealtimePublisher<sr_ronex_msgs::BoolArray>(node_, topic, 1));
00129 
00130 
00131     sprintf(buff, "device_0x%08X_0x%08X_analog_inputs_state",
00132             sh_->get_product_code(),
00133             sh_->get_serial());
00134     topic = buff;
00135     analog_input_state_publisher_.reset(new realtime_tools::RealtimePublisher<std_msgs::UInt16MultiArray>(node_, topic, 1));
00136 
00137 
00138   }
00139 
00140   void CodDecodStdIo::update(unsigned char *status_buffer)
00141   {
00142     unsigned char *buff_ptr;
00143 
00144     //The first byte(s) in the buffer contain the digital inputs values
00145     buff_ptr = status_buffer;
00146 
00147     d_in_.data.clear();
00148 
00149     //Read the digital inputs from the incoming buffer
00150     for (unsigned i = 0; i < n_digital_inputs_; i++)
00151     {
00152       if(buff_ptr[0] & (0x01 << (i % 8)))         d_in_.data.push_back(true);
00153       else                                        d_in_.data.push_back(false);
00154 
00155       if((i + 1) % 8 == 0) buff_ptr++;
00156     }
00157 
00158     //Publish to the digital inputs state topic using the Realtime publisher
00159     if (digital_input_state_publisher_ && digital_input_state_publisher_->trylock())
00160     {
00161       digital_input_state_publisher_->msg_= d_in_;
00162       digital_input_state_publisher_->unlockAndPublish();
00163     }
00164 
00165 
00166     //point to the beginning of the analog inputs in the buffer
00167     buff_ptr = status_buffer + ((n_digital_inputs_/16 + 1) * 2);
00168 
00169     a_in_.data.clear();
00170 
00171     //Read the analog inputs from the incoming buffer
00172     for (unsigned i = 0; i < n_analog_inputs_; i++)
00173     {
00174       a_in_.data.push_back(*((uint16_t *)buff_ptr));
00175 
00176       buff_ptr += 2;
00177     }
00178 
00179     //Publish to the analog inputs state topic using the Realtime publisher
00180     if (analog_input_state_publisher_ && analog_input_state_publisher_->trylock())
00181     {
00182       analog_input_state_publisher_->msg_= a_in_;
00183       analog_input_state_publisher_->unlockAndPublish();
00184     }
00185 
00186     //for debugging only
00187     char buff[300];
00188     char aux[3];
00189     strcpy(buff, "");
00190     for (unsigned int i = 0; i<status_size_; i++)
00191     {
00192       sprintf(aux, "%02x", static_cast<uint16_t>(status_buffer[i]));
00193       strcat(buff, aux);
00194     }
00195     if(status_size_ > 0)
00196     {
00197       ROS_DEBUG("Stat buffer %02d: %s", sh_->get_ring_position(), buff);
00198     }
00199   }
00200 
00201   void CodDecodStdIo::build_command(unsigned char *command_buffer)
00202   {
00203     unsigned char *buff_ptr;
00204     buff_ptr = command_buffer;
00205 
00206     //Read the digital outputs from the digital_output_ realtime box and write them on the output buffer
00207     boost::shared_ptr<sr_ronex_msgs::BoolArray> d_out_ptr;
00208     digital_output_.get(d_out_ptr);
00209 
00210     //first we set all the digital output bytes in the buffer to zero
00211     for (size_t i = 0; i < ((n_digital_outputs_/16 + 1) * 2); i++)
00212     {
00213       buff_ptr[i] = 0;
00214     }
00215 
00216     //then we write the actual values (only the digital ones now) to the buffer
00217     for (size_t i = 0; i < d_out_ptr->data.size(); i++)
00218     {
00219       if (d_out_ptr->data.at(i))
00220         (*((uint8_t *)buff_ptr)) |= (0x01 << (i % 8));
00221       if((i + 1) % 8 == 0)
00222         ++buff_ptr;
00223     }
00224 
00225 
00226     //point to the beginning of the PWM outputs in the buffer
00227     buff_ptr = command_buffer + ((n_digital_outputs_/16 + 1) * 2);
00228 
00229     //Read the PWM outputs from the PWM_output_ realtime box and write them on the output buffer
00230     boost::shared_ptr<std_msgs::UInt16MultiArray> PWM_out_ptr;
00231     PWM_output_.get(PWM_out_ptr);
00232 
00233     //we write the actual values to the buffer
00234     for (size_t i = 0; i < PWM_out_ptr->data.size(); i++)
00235     {
00236       *((uint16_t *)buff_ptr) = PWM_out_ptr->data.at(i);
00237       buff_ptr += 2;
00238     }
00239 
00240 
00241     //point to the beginning of the analog outputs in the buffer
00242     buff_ptr = command_buffer + ((n_digital_outputs_/16 + 1) * 2) + (n_PWM_outputs_ * 4);
00243 
00244     //Read the analog outputs from the analog_output_ realtime box and write them on the output buffer
00245     boost::shared_ptr<std_msgs::UInt16MultiArray> a_out_ptr;
00246     analog_output_.get(a_out_ptr);
00247 
00248     //we write the actual values to the buffer
00249     for (size_t i = 0; i < a_out_ptr->data.size(); i++)
00250     {
00251       *((uint16_t *)buff_ptr) = a_out_ptr->data.at(i);
00252       buff_ptr += 2;
00253     }
00254 
00255     //for debugging only
00256     char buff[300];
00257     char aux[3];
00258     strcpy(buff, "");
00259     for (unsigned int i = 0; i<command_size_; i++)
00260     {
00261       sprintf(aux, "%02x", static_cast<uint16_t>(command_buffer[i]));
00262       strcat(buff, aux);
00263     }
00264     if(command_size_ > 0)
00265     {
00266       ROS_DEBUG("Cmd buffer %02d: %s", sh_->get_ring_position(), buff);
00267     }
00268     //ROS_INFO("Buffer: 0x%02x", static_cast<uint16_t>(buffer[0]));
00269     //ROS_INFO("State: %02d", sh_->get_state());
00270 
00271   }
00272 
00273   void CodDecodStdIo::digitalOutputCommandCB(const sr_ronex_msgs::BoolArrayConstPtr& msg)
00274   {
00275     if(msg->data.size() == n_digital_outputs_)
00276     {
00277       boost::shared_ptr<sr_ronex_msgs::BoolArray> d_out_ptr(new sr_ronex_msgs::BoolArray());
00278       d_out_ptr->data.clear();
00279       for (unsigned int i = 0; i < n_digital_outputs_; ++i)
00280       {
00281         d_out_ptr->data.push_back(msg->data.at(i));
00282       }
00283       digital_output_.set(d_out_ptr);
00284     }
00285     else
00286     {
00287       ROS_ERROR("Wrong number of digital outputs. Must be: %d", n_digital_outputs_);
00288     }
00289   }
00290 
00291   void CodDecodStdIo::analogOutputCommandCB(const std_msgs::UInt16MultiArrayConstPtr& msg)
00292   {
00293     if(msg->data.size() == n_analog_outputs_)
00294     {
00295       boost::shared_ptr<std_msgs::UInt16MultiArray> a_out_ptr(new std_msgs::UInt16MultiArray());
00296       a_out_ptr->data.clear();
00297       for (unsigned int i = 0; i < n_analog_outputs_; ++i)
00298       {
00299         a_out_ptr->data.push_back(msg->data.at(i));
00300       }
00301       analog_output_.set(a_out_ptr);
00302     }
00303     else
00304     {
00305       ROS_ERROR("Wrong number of analog outputs. Must be: %d", n_analog_outputs_);
00306     }
00307   }
00308 
00309   void CodDecodStdIo::PWMOutputCommandCB(const std_msgs::UInt16MultiArrayConstPtr& msg)
00310   {
00311     if(msg->data.size() == n_PWM_outputs_ * 2)
00312     {
00313       boost::shared_ptr<std_msgs::UInt16MultiArray> PWM_out_ptr(new std_msgs::UInt16MultiArray());
00314       PWM_out_ptr->data.clear();
00315       for (unsigned int i = 0; i < (n_PWM_outputs_ * 2); ++i)
00316       {
00317         //The even index values correspond to the PWM channel period
00318         //65535 value (0xFFFF)is disallowed for the period to allow the ON-time to be able to be period+1 in any case
00319         if(!(i & 0x0001) )
00320         {
00321           if(msg->data.at(i) == 0xFFFF)
00322           {
00323             PWM_out_ptr->data.push_back(0xFFFE);
00324           }
00325           else
00326           {
00327             PWM_out_ptr->data.push_back(msg->data.at(i));
00328           }
00329         }
00330         //The odd index values correspond to the PWM channel ON-time
00331         //Allowed values are from 0 to (Period+1)
00332         else
00333         {
00334           if(msg->data.at(i) > (PWM_out_ptr->data.at(i - 1) + 1))
00335           {
00336             PWM_out_ptr->data.push_back(PWM_out_ptr->data.at(i - 1) + 1);
00337           }
00338           else
00339           {
00340             PWM_out_ptr->data.push_back(msg->data.at(i));
00341           }
00342         }
00343       }
00344       PWM_output_.set(PWM_out_ptr);
00345     }
00346     else
00347     {
00348       ROS_ERROR("Wrong number of PWM outputs. Must be: %d. Remember that you need 2 UINT values for every output (Period, ON-time)", n_PWM_outputs_);
00349     }
00350   }
00351 
00352   void CodDecodStdIo::add_diagnostics(std::vector<diagnostic_msgs::DiagnosticStatus> &vec,
00353                                  diagnostic_updater::DiagnosticStatusWrapper &d)
00354   {
00355 
00356   }
00357 
00358   void CodDecodStdIo::setPinAsDigitalInput(sr_cod_decod_std_io::DigitalIo pin)
00359   {
00360     //Read the digital outputs from the digital_output_ realtime box and set the right values to the digital_output_ realtime box again
00361     boost::shared_ptr<sr_ronex_msgs::BoolArray> d_out_ptr(new sr_ronex_msgs::BoolArray());
00362     boost::shared_ptr<sr_ronex_msgs::BoolArray> current_d_out_ptr;
00363     digital_output_.get(current_d_out_ptr);
00364     d_out_ptr->data = current_d_out_ptr->data;
00365     //set the pin as digital input
00366     d_out_ptr->data.at(pin * 2) = true;
00367     digital_output_.set(d_out_ptr);
00368   }
00369 
00370   bool CodDecodStdIo::digitalInputToBool(sr_cod_decod_std_io::DigitalIo input_pin)
00371   {
00372     //The following line gets the digital input input_pin value
00373     return static_cast<bool>(d_in_.data.at(input_pin));
00374   }
00375 
00376   void CodDecodStdIo::digitalInputToBool(sr_cod_decod_std_io::DigitalIo input_pin, bool *where_to_store_it)
00377   {
00378     //The following line connects the digital input input_pin to the variable pointed by where_to_store_it (it should point to a field in the HW interface)
00379     *where_to_store_it = static_cast<bool>(d_in_.data.at(input_pin));
00380   }
00381 
00382   double CodDecodStdIo::analogInputToDouble(sr_cod_decod_std_io::AnalogInput input_pin)
00383   {
00384     //The following line gets the analog input input_pin value
00385     return static_cast<double>(a_in_.data.at(input_pin));
00386   }
00387 
00388   void CodDecodStdIo::analogInputToDouble(sr_cod_decod_std_io::AnalogInput input_pin, double *where_to_store_it)
00389   {
00390     //The following line connects the analog input input_pin to the variable pointed by where_to_store_it (it should point to a field in the HW interface)
00391     *where_to_store_it = static_cast<double>(a_in_.data.at(input_pin));
00392   }
00393 
00394   uint16_t CodDecodStdIo::analogInputToUint16(sr_cod_decod_std_io::AnalogInput input_pin)
00395   {
00396     //The following line gets the analog input input_pin value
00397     return a_in_.data.at(input_pin);
00398   }
00399 
00400   void CodDecodStdIo::analogInputToUint16(sr_cod_decod_std_io::AnalogInput input_pin, uint16_t *where_to_store_it)
00401   {
00402     //The following line connects the analog input input_pin to the variable pointed by where_to_store_it (it should point to a field in the HW interface)
00403     *where_to_store_it = a_in_.data.at(input_pin);
00404   }
00405 
00406   int CodDecodStdIo::analogInputToInt(sr_cod_decod_std_io::AnalogInput input_pin)
00407   {
00408     //The following line gets the analog input input_pin value
00409     return static_cast<int>(a_in_.data.at(input_pin));
00410   }
00411 
00412   void CodDecodStdIo::analogInputToInt(sr_cod_decod_std_io::AnalogInput input_pin, int *where_to_store_it)
00413   {
00414     //The following line connects the analog input input_pin to the variable pointed by where_to_store_it (it should point to a field in the HW interface)
00415     *where_to_store_it = static_cast<int>(a_in_.data.at(input_pin));
00416   }
00417 
00418   void CodDecodStdIo::signToDigitalOutput(sr_cod_decod_std_io::DigitalIo output_pin, double value)
00419   {
00420     boolToDigitalOutput(output_pin, (value < 0.0));
00421   }
00422 
00423   void CodDecodStdIo::boolToDigitalOutput(sr_cod_decod_std_io::DigitalIo output_pin, bool value)
00424   {
00425     //Read the digital outputs from the digital_output_ realtime box and set the right values to the digital_output_ realtime box again
00426     boost::shared_ptr<sr_ronex_msgs::BoolArray> d_out_ptr(new sr_ronex_msgs::BoolArray());
00427     boost::shared_ptr<sr_ronex_msgs::BoolArray> current_d_out_ptr;
00428     digital_output_.get(current_d_out_ptr);
00429     d_out_ptr->data = current_d_out_ptr->data;
00430     //set the pin as digital output
00431     d_out_ptr->data.at(output_pin * 2) = false;
00432     //Set the dig. out. to the corresponding state
00433     d_out_ptr->data.at(output_pin * 2 + 1) = value;
00434     digital_output_.set(d_out_ptr);
00435   }
00436 
00437   void CodDecodStdIo::doubleToAnalogOutput(sr_cod_decod_std_io::AnalogOutput output_pin, double value)
00438   {
00439     uint16ToAnalogOutput(output_pin, static_cast<uint16_t>(abs(value)));
00440   }
00441 
00442   void CodDecodStdIo::uint16ToAnalogOutput(sr_cod_decod_std_io::AnalogOutput output_pin, uint16_t value)
00443   {
00444     //Read the PWM outputs from the PWM_output_ realtime box and set the right values to the PWM_output_ realtime box again
00445     boost::shared_ptr<std_msgs::UInt16MultiArray> analog_out_ptr(new std_msgs::UInt16MultiArray());
00446     boost::shared_ptr<std_msgs::UInt16MultiArray> current_analog_out_ptr;
00447     analog_output_.get(current_analog_out_ptr);
00448     analog_out_ptr->data = current_analog_out_ptr->data;
00449     //set the value of the output
00450     analog_out_ptr->data.at(output_pin) = value;
00451     analog_output_.set(analog_out_ptr);
00452   }
00453 
00454   void CodDecodStdIo::doubleToPWMOutput(sr_cod_decod_std_io::DigitalIo output_pin, uint16_t PWM_period, double PWM_ON_time)
00455   {
00456     uint16ToPWMOutput(output_pin, PWM_period, static_cast<uint16_t>(abs(PWM_ON_time) > static_cast<double>(PWM_period + 1) ? static_cast<double>(PWM_period + 1) : abs(PWM_ON_time) + 0.5));
00457   }
00458 
00459   void CodDecodStdIo::uint16ToPWMOutput(sr_cod_decod_std_io::DigitalIo output_pin, uint16_t PWM_period, uint16_t PWM_ON_time)
00460   {
00461     //Read the PWM outputs from the PWM_output_ realtime box and set the right values to the PWM_output_ realtime box again
00462     boost::shared_ptr<std_msgs::UInt16MultiArray> PWM_out_ptr(new std_msgs::UInt16MultiArray());
00463     boost::shared_ptr<std_msgs::UInt16MultiArray> current_PWM_out_ptr;
00464     PWM_output_.get(current_PWM_out_ptr);
00465     PWM_out_ptr->data = current_PWM_out_ptr->data;
00466     //set the period to PWM_period
00467     PWM_out_ptr->data.at(output_pin * 2) = PWM_period;
00468     //set the ON-time (maximum is period + 1)
00469     PWM_out_ptr->data.at(output_pin * 2 + 1) = static_cast<uint16_t>(PWM_ON_time > (PWM_period + 1) ? (PWM_period + 1) : PWM_ON_time);
00470     PWM_output_.set(PWM_out_ptr);
00471   }
00472 
00473 }


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