intra_suite.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
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
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #include "perf_roscpp/intra.h"
00036 
00037 #include <ros/ros.h>
00038 
00039 #include <cstdio>
00040 #include <iostream>
00041 #include <fstream>
00042 #include <vector>
00043 
00044 using namespace perf_roscpp;
00045 using namespace std;
00046 
00047 typedef std::vector<intra::ThroughputResult> V_ThroughputResult;
00048 typedef std::vector<intra::LatencyResult> V_LatencyResult;
00049 typedef std::vector<intra::STLatencyResult> V_STLatencyResult;
00050 
00051 void printResult(std::ostream& out, uint32_t test_num, intra::ThroughputResult& r)
00052 {
00053 
00054   out << "----------------------------------------------------------\n";
00055   out << "Throughput Test " << test_num << ": receiver_threads [" << r.receiver_threads << "], sender_threads [" << r.sender_threads << "], streams [" << r.streams << "], test_duration [" << r.test_duration << "], message_size [" << r.message_size << "]\n";
00056   out << "\tMessages Sent: " << r.messages_sent << endl;
00057   out << "\tMessages Received: " << r.messages_received << " (" << (double)r.messages_received / (double)r.messages_sent * 100.0 << "%)" << endl;
00058   out << "\tBytes Sent: " << r.total_bytes_sent << endl;
00059   out << "\tBytes Received: " << r.total_bytes_received << endl;
00060   out << "\tBytes Per Second: " << r.bytes_per_second << " (" << r.bytes_per_second / (1024.0 * 1024.0) << " MB/s)" << endl;
00061 }
00062 
00063 void printResult(std::ostream& out, uint32_t test_num, intra::LatencyResult& r)
00064 {
00065   out << "----------------------------------------------------------\n";
00066   out << "Multi-Threaded Latency Test " << test_num << ": receiver_threads [" << r.receiver_threads << "], sender_threads [" << r.sender_threads << "], streams [" << r.streams << "], count_per_stream [" << r.count_per_stream << "], message_size [" << r.message_size << "]\n";
00067   out << "\tMessage Count: " << r.total_message_count << endl;
00068   out << "\tLatency Average: " << r.latency_avg << endl;
00069   out << "\tLatency Min: " << r.latency_min << endl;
00070   out << "\tLatency Max: " << r.latency_max << endl;
00071 }
00072 
00073 void printResult(std::ostream& out, uint32_t test_num, intra::STLatencyResult& r)
00074 {
00075   out << "----------------------------------------------------------\n";
00076   out << "Single-Threaded Latency Test " << test_num << endl;
00077   out << "\tMessage Count: " << r.total_message_count << endl;
00078   out << "\tLatency Average: " << r.latency_avg << endl;
00079   out << "\tLatency Min: " << r.latency_min << endl;
00080   out << "\tLatency Max: " << r.latency_max << endl;
00081 }
00082 
00083 void addResult(V_ThroughputResult& results, intra::ThroughputResult r, std::ostream& out, uint32_t i)
00084 {
00085   results.push_back(r);
00086   printResult(out, i, results.back());
00087 }
00088 
00089 void addResult(V_LatencyResult& results, intra::LatencyResult r, std::ostream& out, uint32_t i)
00090 {
00091   results.push_back(r);
00092   printResult(out, i, results.back());
00093 }
00094 
00095 void addResult(V_STLatencyResult& results, intra::STLatencyResult r, std::ostream& out, uint32_t i)
00096 {
00097   results.push_back(r);
00098   printResult(out, i, results.back());
00099 }
00100 
00101 void runThroughputTests(std::ostream& out, V_ThroughputResult& results)
00102 {
00103   uint32_t i = 0;
00104   //                                   test duration, streams, message size , send threads, receive threads
00105   addResult(results, intra::throughput(1            , 1      , 100          , 1           , 1              ), out, i++);
00106   addResult(results, intra::throughput(1            , 1      , 1024*1024*10 , 1           , 1              ), out, i++);
00107   addResult(results, intra::throughput(1            , 1      , 1024*1024*100, 1           , 1              ), out, i++);
00108 
00109   addResult(results, intra::throughput(10           , 1      , 100          , 1           , 1              ), out, i++);
00110   addResult(results, intra::throughput(10           , 1      , 1024*1024*10 , 1           , 1              ), out, i++);
00111   addResult(results, intra::throughput(10           , 1      , 1024*1024*100, 1           , 1              ), out, i++);
00112 
00113 #if 0
00114   addResult(results, intra::throughput(10           , 1      , 100          , 1           , 10             ), out, i++);
00115   addResult(results, intra::throughput(10           , 1      , 1024*1024*10 , 1           , 10             ), out, i++);
00116   addResult(results, intra::throughput(10           , 1      , 1024*1024*100, 1           , 10             ), out, i++);
00117 
00118   addResult(results, intra::throughput(1            , 10     , 100          , 1           , 1              ), out, i++);
00119   addResult(results, intra::throughput(1            , 10     , 1024*1024*1  , 1           , 1              ), out, i++);
00120   addResult(results, intra::throughput(1            , 10     , 1024*1024*10 , 1           , 1              ), out, i++);
00121 
00122   addResult(results, intra::throughput(10           , 10     , 100          , 1           , 10             ), out, i++);
00123   addResult(results, intra::throughput(10           , 10     , 1024*1024*1  , 1           , 10             ), out, i++);
00124   addResult(results, intra::throughput(10           , 10     , 1024*1024*10 , 1           , 10             ), out, i++);
00125 #endif
00126 }
00127 
00128 void runLatencyTests(std::ostream& out, V_LatencyResult& results)
00129 {
00130   uint32_t i = 0;
00131   //                                count per stream, streams, message size , receive threads
00132   addResult(results, intra::latency(100000          , 1      , 1            , 1           , 1              ), out, i++);
00133   addResult(results, intra::latency(10000           , 1      , 1024         , 1           , 1              ), out, i++);
00134   addResult(results, intra::latency(1000            , 1      , 1024*1024    , 1           , 1              ), out, i++);
00135   addResult(results, intra::latency(100             , 1      , 1024*1024*100, 1           , 1              ), out, i++);
00136 
00137 #if 0
00138   addResult(results, intra::latency(100000          , 1      , 1            , 1           , 10             ), out, i++);
00139   addResult(results, intra::latency(10000           , 1      , 1024         , 1           , 10             ), out, i++);
00140   addResult(results, intra::latency(1000            , 1      , 1024*1024    , 1           , 10             ), out, i++);
00141   addResult(results, intra::latency(100             , 1      , 1024*1024*100, 1           , 10             ), out, i++);
00142 
00143   addResult(results, intra::latency(100000          , 10     , 1            , 1           , 1              ), out, i++);
00144   addResult(results, intra::latency(10000           , 10     , 1024         , 1           , 1              ), out, i++);
00145   addResult(results, intra::latency(1000            , 10     , 1024*1024    , 1           , 1              ), out, i++);
00146   addResult(results, intra::latency(100             , 10     , 1024*1024*100, 1           , 1              ), out, i++);
00147 
00148   addResult(results, intra::latency(10000           , 10     , 1            , 10          , 1              ), out, i++);
00149   addResult(results, intra::latency(1000            , 10     , 1024         , 10          , 1              ), out, i++);
00150   addResult(results, intra::latency(100             , 10     , 1024*1024    , 10          , 1              ), out, i++);
00151   // 100mb test allocates too much memory
00152 #endif
00153 }
00154 
00155 void runSTLatencyTests(std::ostream& out, V_STLatencyResult& results)
00156 {
00157   uint32_t i = 0;
00158   addResult(results, intra::stlatency(10000), out, i++);
00159   addResult(results, intra::stlatency(100000), out, i++);
00160   addResult(results, intra::stlatency(1000000), out, i++);
00161 }
00162 
00163 int main(int argc, char** argv)
00164 {
00165   std::ofstream out("intra_suite_out.txt", std::ios::out);
00166   out << std::fixed;
00167   out.precision(10);
00168   cout << std::fixed;
00169   cout.precision(10);
00170 
00171   ROS_ASSERT(out.is_open());
00172 
00173   ros::init(argc, argv, "perf_roscpp_intra_suite", ros::init_options::NoSigintHandler|ros::init_options::NoRosout);
00174   ros::NodeHandle nh;
00175 
00176   V_ThroughputResult throughput_results;
00177   runThroughputTests(out, throughput_results);
00178 
00179   V_LatencyResult latency_results;
00180   runLatencyTests(out, latency_results);
00181 
00182   V_STLatencyResult stlatency_results;
00183   runSTLatencyTests(out, stlatency_results);
00184 
00185   printf("\n\n\n***************************** Results *****************************\n\n");
00186   uint32_t i = 0;
00187   {
00188     V_ThroughputResult::iterator it = throughput_results.begin();
00189     V_ThroughputResult::iterator end = throughput_results.end();
00190     for (; it != end; ++it, ++i)
00191     {
00192       intra::ThroughputResult& r = *it;
00193       printResult(cout, i, r);
00194     }
00195   }
00196 
00197   i = 0;
00198   {
00199     V_LatencyResult::iterator it = latency_results.begin();
00200     V_LatencyResult::iterator end = latency_results.end();
00201     for (; it != end; ++it, ++i)
00202     {
00203       intra::LatencyResult& r = *it;
00204       printResult(cout, i, r);
00205     }
00206   }
00207 
00208   i = 0;
00209   {
00210     V_STLatencyResult::iterator it = stlatency_results.begin();
00211     V_STLatencyResult::iterator end = stlatency_results.end();
00212     for (; it != end; ++it, ++i)
00213     {
00214       intra::STLatencyResult& r = *it;
00215       printResult(cout, i, r);
00216     }
00217   }
00218 }


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Tue Mar 7 2017 03:45:23