Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00024 #include <stdint.h>
00025 #include "sr_ronex_external_protocol/Ronex_Protocol_0x02000001_GIO_00.h"
00026 #include <ros_ethercat_hardware/ethercat_hardware.h>
00027 #include "sr_ronex_drivers/ronex_utils.hpp"
00028 #include "sr_ronex_drivers/sr_board_mk2_gio.hpp"
00029 #include "sr_ronex_hardware_interface/mk2_gio_hardware_interface.hpp"
00030 #include <ros_ethercat_model/robot_state.hpp>
00031 #include <ros/ros.h>
00032 #include <gtest/gtest.h>
00033 #include <tinyxml.h>
00034 #include <string>
00035
00036 using ronex::build_name;
00037
00038 TEST(RonexEthercatDrivers, build_name)
00039 {
00040 string expected = "/ronex/general_io/beautiful_ronex";
00041 string result = build_name("general_io", "beautiful_ronex");
00042 int res = expected.compare(result);
00043 ASSERT_EQ(0, res);
00044 }
00045
00046 TEST(RonexEthercatDrivers, constructor)
00047 {
00048 const uint32_t serial = 55662211;
00049
00050 EtherCAT_FMMU_Config fmmu(0);
00051 EtherCAT_PD_Config pdcfg(0);
00052 EtherCAT_MbxConfig mbxcfg;
00053 EtherCAT_DataLinkLayer dll;
00054 EC_Logic logic;
00055 EtherCAT_PD_Buffer pdbuf(&logic, &dll);
00056
00057 EtherCAT_SlaveHandler sh(0, 0, 0, serial, EC_FixedStationAddress((uint16_t) 0), &fmmu, &pdcfg, &mbxcfg, &dll, &logic,
00058 &pdbuf);
00059
00060 SrBoardMk2GIO sbm;
00061
00062 int add = 0;
00063 sbm.construct(&sh, add);
00064
00065 ros::NodeHandle nh;
00066 string xml_string;
00067 nh.getParam("robot_description", xml_string);
00068 TiXmlDocument urdf_xml;
00069 urdf_xml.Parse(xml_string.c_str());
00070 TiXmlElement *root = urdf_xml.FirstChildElement("robot");
00071 ros_ethercat_model::RobotState hw(root);
00072
00073 int retsbm = sbm.initialize(static_cast<hardware_interface::HardwareInterface*>(&hw));
00074 ASSERT_EQ(0, retsbm);
00075 }
00076
00077 int main(int argc, char **argv)
00078 {
00079 ros::init(argc, argv, "test_ethercat_drivers_test");
00080 testing::InitGoogleTest(&argc, argv);
00081 return RUN_ALL_TESTS();
00082 }
00083
00084
00085
00086
00087
00088