Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00026 #include <sr_ronex_transmissions/ronex_transmission.hpp>
00027 #include "pluginlib/class_list_macros.h"
00028 #include <cstring>
00029 #include <string>
00030
00031 #include "sr_ronex_transmissions/mapping/general_io/analogue_to_position.hpp"
00032 #include "sr_ronex_transmissions/mapping/general_io/analogue_to_effort.hpp"
00033 #include "sr_ronex_transmissions/mapping/general_io/command_to_pwm.hpp"
00034 #include "sr_ronex_transmissions/mapping/general_io/command_to_pwm_2_dir_pin.hpp"
00035
00036 PLUGINLIB_EXPORT_CLASS(ronex::RonexTransmission, ros_ethercat_model::Transmission)
00037
00038 namespace ronex
00039 {
00040 bool RonexTransmission::initXml(TiXmlElement *elt, ros_ethercat_model::RobotState *robot)
00041 {
00042 if (!ros_ethercat_model::Transmission::initXml(elt, robot))
00043 return false;
00044
00045
00046 TiXmlElement *jel = elt->FirstChildElement("joint");
00047 if (!jel || !jel->Attribute("name"))
00048 {
00049 ROS_ERROR_STREAM("Joint name not specified in transmission " << name_);
00050 return false;
00051 }
00052
00053 joint_ = robot->getJointState(jel->Attribute("name"));
00054
00055
00056
00057 actuator_ = new ros_ethercat_model::Actuator();
00058 actuator_->name_ = "Dummy_actuator_" + std::string(jel->Attribute("name"));
00059
00060
00061 for ( TiXmlElement *mapping_el = elt->FirstChildElement("mapping"); mapping_el;
00062 mapping_el = mapping_el->NextSiblingElement("mapping") )
00063 {
00064 const char *property = mapping_el ? mapping_el->Attribute("property") : NULL;
00065 if (!property)
00066 {
00067 ROS_ERROR("RonexTransmission: no property defined for the mapping. Skipping the mapping.");
00068 }
00069 else
00070 {
00071
00072 if ( std::strcmp("position", property) == 0 )
00073 {
00074 ronex_mappings_.push_back( new mapping::general_io::AnalogueToPosition(mapping_el, robot) );
00075 }
00076 else if ( std::strcmp("effort", property) == 0 )
00077 {
00078 ronex_mappings_.push_back( new mapping::general_io::AnalogueToEffort(mapping_el, robot) );
00079 }
00080 else if ( std::strcmp("command", property) == 0 )
00081 {
00082 ronex_mappings_.push_back( new mapping::general_io::CommandToPWM(mapping_el, robot) );
00083 }
00084 else if ( std::strcmp("command_2_dir", property) == 0 )
00085 {
00086 ronex_mappings_.push_back( new mapping::general_io::CommandToPWM2PinDir(mapping_el, robot) );
00087 }
00088 else
00089 ROS_WARN_STREAM("Property not recognized: " << property);
00090 }
00091 }
00092
00093 return true;
00094 }
00095
00096 void RonexTransmission::propagatePosition()
00097 {
00098 for (ronex_iter_ = ronex_mappings_.begin(); ronex_iter_ != ronex_mappings_.end(); ++ronex_iter_)
00099 {
00100 ronex_iter_->propagateFromRonex(joint_);
00101 }
00102 }
00103
00104 void RonexTransmission::propagateEffort()
00105 {
00106 for (ronex_iter_ = ronex_mappings_.begin(); ronex_iter_ != ronex_mappings_.end(); ++ronex_iter_)
00107 {
00108 ronex_iter_->propagateToRonex(joint_);
00109 }
00110 }
00111 }
00112
00113
00114
00115
00116
00117