test_ronex_transmission.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/ronex_transmission.hpp"
00025 #include <sr_ronex_hardware_interface/mk2_gio_hardware_interface.hpp>
00026 #include <ros/ros.h>
00027 #include <ros_ethercat_model/robot_state.hpp>
00028 #include <gtest/gtest.h>
00029 #include <string>
00030 
00031 TEST(RonexTransmission, constructor)
00032 {
00033   // get urdf from param
00034   ros::NodeHandle nh;
00035   std::string xml_string;
00036   ASSERT_TRUE(nh.getParam("robot_description", xml_string));
00037   TiXmlDocument urdf_xml;
00038   urdf_xml.Parse(xml_string.c_str());
00039   ros_ethercat_model::RobotState state(0);
00040   TiXmlElement *root = urdf_xml.FirstChildElement("robot");
00041   ASSERT_TRUE(root != NULL);
00042 
00043   // add ronex
00044   std::string name("/ronex/general_io/0");
00045   state.custom_hws_.insert(name, new ronex::GeneralIO());
00046   state.initXml(root);
00047 
00048   ronex::GeneralIO* general_io = static_cast<ronex::GeneralIO*>(state.getCustomHW(name) );
00049   ASSERT_TRUE(general_io != NULL);
00050 }
00051 
00052 TEST(RonexTransmission, propagateCommand)
00053 {
00054   // get urdf from param
00055   ros::NodeHandle nh;
00056   std::string xml_string;
00057   ASSERT_TRUE(nh.getParam("robot_description", xml_string));
00058   TiXmlDocument urdf_xml;
00059   urdf_xml.Parse(xml_string.c_str());
00060   ros_ethercat_model::RobotState state(0);
00061   TiXmlElement *root = urdf_xml.FirstChildElement("robot");
00062   ASSERT_TRUE(root != NULL);
00063 
00064   // add ronex
00065   std::string name("/ronex/general_io/0");
00066   state.custom_hws_.insert(name, new ronex::GeneralIO());
00067   state.initXml(root);
00068 
00069   ronex::GeneralIO* general_io = static_cast<ronex::GeneralIO*>(state.getCustomHW(name));
00070   ASSERT_TRUE(general_io != NULL);
00071   general_io->command_.pwm_clock_divider_ = 20;
00072   general_io->command_.pwm_.resize(6);
00073   general_io->state_.analogue_.resize(6);
00074   general_io->state_.digital_.resize(6);
00075   general_io->command_.pwm_.resize(6);
00076   general_io->command_.digital_.resize(6);
00077 
00078   // setting effort for the joint
00079   state.joint_states_["joint1"].commanded_effort_ = 5.1;
00080 
00081   general_io->command_.pwm_[1].period =  64000;  // setting period too
00082 
00083   state.propagateJointEffortToActuatorEffort();
00084   state.propagateJointEffortToActuatorEffort();
00085 
00086   // reading the command from the RoNeX
00087   EXPECT_EQ(general_io->command_.pwm_[1].on_time_0, 3264);
00088   EXPECT_FALSE(general_io->command_.digital_[5]);  // Positive commanded effort should set direction pin to 0
00089 }
00090 
00091 
00092 TEST(RonexTransmission, propagateState)
00093 {
00094   // get urdf from param
00095   ros::NodeHandle nh;
00096   std::string xml_string;
00097   ASSERT_TRUE(nh.getParam("robot_description", xml_string));
00098   TiXmlDocument urdf_xml;
00099   urdf_xml.Parse(xml_string.c_str());
00100   ros_ethercat_model::RobotState state(0);
00101   TiXmlElement *root = urdf_xml.FirstChildElement("robot");
00102   ASSERT_TRUE(root != NULL);
00103 
00104   // add ronex
00105   std::string name("/ronex/general_io/0");
00106   state.custom_hws_.insert(name, new ronex::GeneralIO());
00107   state.initXml(root);
00108 
00109   ronex::GeneralIO* general_io = static_cast<ronex::GeneralIO*>(state.getCustomHW(name));
00110   ASSERT_TRUE(general_io != NULL);
00111   general_io->command_.pwm_.resize(6);
00112   general_io->state_.analogue_.resize(6);
00113   general_io->state_.digital_.resize(6);
00114   general_io->command_.pwm_.resize(6);
00115 
00116   // setting analogue data on the ronex for generating joint position / effort
00117   general_io->state_.analogue_[0] = 1.0;  // position according to urdf
00118   general_io->state_.analogue_[1] = 1.0;  // mapped to effort
00119   // propagating
00120   state.propagateActuatorPositionToJointPosition();
00121   state.propagateActuatorPositionToJointPosition();
00122   // reading the position and effort from the RoNeX
00123   EXPECT_DOUBLE_EQ(state.joint_states_["joint1"].position_, 1.0);  // scale is 1.0, offset 0.0
00124   EXPECT_DOUBLE_EQ(state.joint_states_["joint1"].effort_, 3.0);  // scale is 2.0, offset 1.0
00125 }
00126 
00127 int main(int argc, char **argv)
00128 {
00129     testing::InitGoogleTest(&argc, argv);
00130     ros::init(argc, argv, "test_ronex_transmissions");
00131     ros::NodeHandle nh;  // init the node
00132     return RUN_ALL_TESTS();
00133 }
00134 
00135 /* For the emacs weenies in the crowd.
00136    Local Variables:
00137    c-basic-offset: 2
00138    End:
00139 */
00140 


sr_ronex_transmissions
Author(s): Ugo Cupcic, Toni Oliver, Mark Pitchless
autogenerated on Thu Jun 6 2019 21:21:55