analogue_to_position.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_transmissions/mapping/general_io/analogue_to_position.hpp"
00025 #include <ros_ethercat_model/robot_state.hpp>
00026 #include <boost/lexical_cast.hpp>
00027 
00028 namespace ronex
00029 {
00030   namespace mapping
00031   {
00032     namespace general_io
00033     {
00034       AnalogueToPosition::AnalogueToPosition(TiXmlElement* mapping_el, ros_ethercat_model::RobotState* robot)
00035         : pin_out_of_bound_(true)
00036       {
00037         const char *ronex_name = mapping_el ? mapping_el->Attribute("ronex") : NULL;
00038         if (!ronex_name)
00039         {
00040           ROS_ERROR("RonexTransmission transmission did not specify the ronex name");
00041           return;
00042         }
00043 
00044         init_timer_ = nh_.createTimer(ros::Duration(0.01),
00045                                       boost::bind(&AnalogueToPosition::try_init_cb_, this, _1, mapping_el, robot, ronex_name));
00046       }
00047 
00048       bool AnalogueToPosition::try_init_cb_(const ros::TimerEvent&, TiXmlElement* mapping_el, ros_ethercat_model::RobotState* robot, const char* ronex_name)
00049       {
00050         //has the ronex been added by the driver?
00051         if( robot->getCustomHW(ronex_name) == NULL )
00052         {
00053           return false;
00054         }
00055 
00056         //@todo: when we have multiple available module types check the module type when casting
00057         general_io_ = static_cast<ronex::GeneralIO*>( robot->getCustomHW(ronex_name) );
00058         if(!general_io_)
00059         {
00060           ROS_ERROR_STREAM("The RoNeX: " << ronex_name << " was not found on the system.");
00061           return false;
00062         }
00063 
00064         //read ronex pin from urdf
00065         const char *ronex_pin = mapping_el ? mapping_el->Attribute("analogue_pin") : NULL;
00066         if (!ronex_pin)
00067         {
00068           ROS_ERROR("RonexTransmission transmission did not specify the ronex pin.");
00069           return false;
00070         }
00071         //convert pin to size_t
00072         try
00073         {
00074           pin_index_ = boost::lexical_cast<size_t>( ronex_pin );
00075         }
00076         catch( boost::bad_lexical_cast const& )
00077         {
00078           ROS_ERROR("RonexTransmission: Couldn't parse pin to an int.");
00079           return false;
00080         }
00081 
00082         //read scale
00083         const char *scale = mapping_el ? mapping_el->Attribute("scale") : NULL;
00084         if (!scale)
00085         {
00086           ROS_WARN("RonexTransmission transmission did not specify the scale, using 1.0.");
00087           scale = "1.0";
00088         }
00089         //convert scale to double
00090         try
00091         {
00092           scale_ = boost::lexical_cast<double>( scale );
00093         }
00094         catch( boost::bad_lexical_cast const& )
00095         {
00096           ROS_WARN("RonexTransmission: Couldn't parse scale to a double, using 1.0.");
00097           scale_ = 1.0;
00098         }
00099 
00100         //read offset
00101         const char *offset = mapping_el ? mapping_el->Attribute("offset") : NULL;
00102         if (!offset)
00103         {
00104           ROS_WARN("RonexTransmission transmission did not specify the offset, using 0.0.");
00105           offset = "0.0";
00106         }
00107         //convert offset to double
00108         try
00109         {
00110           offset_ = boost::lexical_cast<double>( offset );
00111         }
00112         catch( boost::bad_lexical_cast const& )
00113         {
00114           ROS_WARN("RonexTransmission: Couldn't parse offset to a double, using 0.0.");
00115           offset_ = 0.0;
00116         }
00117 
00118         ROS_DEBUG_STREAM("RoNeX" << ronex_name << " is initialised now.");
00119         //stopping timer
00120         init_timer_.stop();
00121 
00122         is_initialized_ = true;
00123         return true;
00124       }
00125 
00126       void AnalogueToPosition::propagateFromRonex(ros_ethercat_model::JointState *js)
00127       {
00128         if( !is_initialized_ )
00129           return;
00130 
00131         if( check_pin_in_bound_() )
00132         {
00133           js->position_ = compute_scaled_data_();
00134         }
00135       }
00136 
00137       bool AnalogueToPosition::check_pin_in_bound_()
00138       {
00139         //we ignore the first iteration as the array is not yet initialised.
00140         if( first_iteration_ )
00141         {
00142           pin_out_of_bound_ = true;
00143           first_iteration_ = false;
00144           return false;
00145         }
00146 
00147         //we have to check here for the size otherwise the general io hasn't been updated.
00148         if( pin_out_of_bound_ )
00149         {
00150           if( pin_index_ >= general_io_->state_.analogue_.size() )
00151           {
00152             //size_t is always >= 0 so no need to check lower bound
00153             ROS_ERROR_STREAM("Specified pin is out of bound: " << pin_index_ << " / max = " << general_io_->state_.analogue_.size() << ", not propagating the RoNeX data to the joint position.");
00154 
00155             pin_out_of_bound_ = true;
00156             return false;
00157           }
00158         }
00159 
00160         pin_out_of_bound_ = false;
00161         return true;
00162       }
00163 
00164       double AnalogueToPosition::compute_scaled_data_()
00165       {
00166         return general_io_->state_.analogue_[pin_index_]*scale_ + offset_;
00167       }
00168     }
00169   }
00170 }
00171 /* For the emacs weenies in the crowd.
00172    Local Variables:
00173    c-basic-offset: 2
00174    End:
00175 */


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