utest.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2011, Southwest Research Institute
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions are met:
00009  *
00010  *      * Redistributions of source code must retain the above copyright
00011  *      notice, this list of conditions and the following disclaimer.
00012  *      * Redistributions in binary form must reproduce the above copyright
00013  *      notice, this list of conditions and the following disclaimer in the
00014  *      documentation and/or other materials provided with the distribution.
00015  *      * Neither the name of the Southwest Research Institute, nor the names
00016  *      of its contributors may be used to endorse or promote products derived
00017  *      from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 
00032 #include "utils.h"
00033 #include "definitions.h"
00034 #include "trajectory_job.h"
00035 #include "simple_message/joint_traj.h"
00036 #include "simple_message/log_wrapper.h"
00037 
00038 #include <vector>
00039 #include <iostream>
00040 #include <fstream>
00041 #include <gtest/gtest.h>
00042 
00043 using namespace motoman::utils;
00044 using namespace motoman::trajectory_job;
00045 using namespace industrial::joint_traj;
00046 using namespace industrial::joint_traj_pt;
00047 using namespace industrial::joint_data;
00048 
00049 
00050 TEST(Utils, hasSuffix)
00051 {
00052   std::string test = "prefix_root_suffix";
00053   std::string suffix = "suffix";
00054   std::string root = "root";
00055   std::string prefix = "prefix";
00056   std::string empty = "";
00057   EXPECT_TRUE(hasSuffix(test, test));
00058   EXPECT_TRUE(hasSuffix(test, suffix));
00059   EXPECT_FALSE(hasSuffix(test, root));
00060   EXPECT_FALSE(hasSuffix(test, prefix));
00061   EXPECT_TRUE(hasSuffix(test, empty));
00062 
00063 }
00064 
00065 TEST(Utils, checkJointNames)
00066 {
00067   std::vector<std::string> names;
00068   EXPECT_TRUE(checkJointNames(names));
00069   names.push_back("joint_s");
00070   EXPECT_TRUE(checkJointNames(names));
00071   names.push_back("prefix_joint_l");
00072   EXPECT_TRUE(checkJointNames(names));
00073   names.push_back("bad_joint");
00074   EXPECT_FALSE(checkJointNames(names));
00075   names.clear();
00076   names.resize(motoman::parameters::Parameters::JOINT_SUFFIXES_SIZE + 1 );
00077   EXPECT_FALSE(checkJointNames(names));
00078 
00079   names.clear();
00080   for (int i = 0; i < motoman::parameters::Parameters::JOINT_SUFFIXES_SIZE; i++)
00081   {
00082     names.push_back(motoman::parameters::Parameters::JOINT_SUFFIXES[i]);
00083   }
00084   EXPECT_TRUE(checkJointNames(names));
00085 
00086 }
00087 
00088 TEST(Utils, toMotomanVelocity)
00089 {
00090   std::vector<double> vel;
00091   std::vector<double> lim;
00092 
00093   vel.push_back(1.0);
00094   lim.push_back(2.0);
00095 
00096   EXPECT_FLOAT_EQ(toMotomanVelocity(lim, vel), 1.0/2.0);
00097   EXPECT_FLOAT_EQ(toMotomanVelocity(vel, lim), 1.0);
00098 
00099   vel.push_back(2.0);
00100   lim.push_back(3.0);
00101 
00102   EXPECT_FLOAT_EQ(toMotomanVelocity(lim, vel), 2.0/3.0);
00103 
00104   vel.push_back(3.0);
00105   EXPECT_FLOAT_EQ(toMotomanVelocity(lim, vel), 0.0);
00106 
00107   lim.push_back(4.0);
00108   lim.push_back(5.0);
00109   EXPECT_FLOAT_EQ(toMotomanVelocity(lim, vel), 0.0);
00110 
00111 }
00112 
00113 TEST(TrajectoryJob, init)
00114 {
00115 
00116   using namespace std;
00117 
00118   TrajectoryJob job;
00119   JointTraj traj;
00120   JointTrajPt pt;
00121   JointData init;
00122   string job_name = "JOB_NAME";
00123   string job_ext = ".JBI";
00124 
00125   const int TRAJ_SIZE = 50;
00126   const int BIG_JOB_BUFFER_SIZE = 500000;
00127   char bigJobBuffer[BIG_JOB_BUFFER_SIZE];
00128   const int SMALL_JOB_BUFFER_SIZE = 10;
00129   char smallJobBuffer[SMALL_JOB_BUFFER_SIZE];
00130 
00131   for (int i = 1; i <= TRAJ_SIZE; i++)
00132   {
00133     //ROS_DEBUG("Initializing joint: %d", i);
00134     for (int j = 0; j < init.getMaxNumJoints(); j++)
00135     {
00136       //ROS_DEBUG("Initializing point: %d.%d", i, j);
00137       ASSERT_TRUE(init.setJoint(j, (i*(j+1))));
00138     }
00139     pt.init(i, init, 11.1111);
00140     ASSERT_TRUE(traj.addPoint(pt));
00141   }
00142 
00143   EXPECT_FALSE(job.init("this name is way too long to be the name of a file and this should fail", traj));
00144   ASSERT_TRUE(job.init((char*)job_name.c_str(), traj));
00145 
00146   EXPECT_FALSE(job.toJobString(&smallJobBuffer[0], SMALL_JOB_BUFFER_SIZE));
00147 
00148   EXPECT_TRUE(job.toJobString(&bigJobBuffer[0], BIG_JOB_BUFFER_SIZE));
00149   ofstream file;
00150   job_name.append(job_ext);
00151   file.open(job_name.c_str());
00152   ASSERT_TRUE(file.is_open());
00153   file << bigJobBuffer;
00154   file.close();
00155 
00156 
00157 }
00158 
00159 
00160 
00161 // Run all the tests that were declared with TEST()
00162 int main(int argc, char **argv)
00163 {
00164   testing::InitGoogleTest(&argc, argv);
00165   return RUN_ALL_TESTS();
00166 }
00167 


dx100
Author(s): Shaun Edwards (Southwest Research Institute)
autogenerated on Thu Jan 2 2014 11:29:36