intra_suite.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #include "perf_roscpp/intra.h"
36 
37 #include <ros/ros.h>
38 
39 #include <cstdio>
40 #include <iostream>
41 #include <fstream>
42 #include <vector>
43 
44 using namespace perf_roscpp;
45 using namespace std;
46 
47 typedef std::vector<intra::ThroughputResult> V_ThroughputResult;
48 typedef std::vector<intra::LatencyResult> V_LatencyResult;
49 typedef std::vector<intra::STLatencyResult> V_STLatencyResult;
50 
51 void printResult(std::ostream& out, uint32_t test_num, intra::ThroughputResult& r)
52 {
53 
54  out << "----------------------------------------------------------\n";
55  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";
56  out << "\tMessages Sent: " << r.messages_sent << endl;
57  out << "\tMessages Received: " << r.messages_received << " (" << (double)r.messages_received / (double)r.messages_sent * 100.0 << "%)" << endl;
58  out << "\tBytes Sent: " << r.total_bytes_sent << endl;
59  out << "\tBytes Received: " << r.total_bytes_received << endl;
60  out << "\tBytes Per Second: " << r.bytes_per_second << " (" << r.bytes_per_second / (1024.0 * 1024.0) << " MB/s)" << endl;
61 }
62 
63 void printResult(std::ostream& out, uint32_t test_num, intra::LatencyResult& r)
64 {
65  out << "----------------------------------------------------------\n";
66  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";
67  out << "\tMessage Count: " << r.total_message_count << endl;
68  out << "\tLatency Average: " << r.latency_avg << endl;
69  out << "\tLatency Min: " << r.latency_min << endl;
70  out << "\tLatency Max: " << r.latency_max << endl;
71 }
72 
73 void printResult(std::ostream& out, uint32_t test_num, intra::STLatencyResult& r)
74 {
75  out << "----------------------------------------------------------\n";
76  out << "Single-Threaded Latency Test " << test_num << endl;
77  out << "\tMessage Count: " << r.total_message_count << endl;
78  out << "\tLatency Average: " << r.latency_avg << endl;
79  out << "\tLatency Min: " << r.latency_min << endl;
80  out << "\tLatency Max: " << r.latency_max << endl;
81 }
82 
83 void addResult(V_ThroughputResult& results, intra::ThroughputResult r, std::ostream& out, uint32_t i)
84 {
85  results.push_back(r);
86  printResult(out, i, results.back());
87 }
88 
89 void addResult(V_LatencyResult& results, intra::LatencyResult r, std::ostream& out, uint32_t i)
90 {
91  results.push_back(r);
92  printResult(out, i, results.back());
93 }
94 
95 void addResult(V_STLatencyResult& results, intra::STLatencyResult r, std::ostream& out, uint32_t i)
96 {
97  results.push_back(r);
98  printResult(out, i, results.back());
99 }
100 
101 void runThroughputTests(std::ostream& out, V_ThroughputResult& results)
102 {
103  uint32_t i = 0;
104  // test duration, streams, message size , send threads, receive threads
105  addResult(results, intra::throughput(1 , 1 , 100 , 1 , 1 ), out, i++);
106  addResult(results, intra::throughput(1 , 1 , 1024*1024*10 , 1 , 1 ), out, i++);
107  addResult(results, intra::throughput(1 , 1 , 1024*1024*100, 1 , 1 ), out, i++);
108 
109  addResult(results, intra::throughput(10 , 1 , 100 , 1 , 1 ), out, i++);
110  addResult(results, intra::throughput(10 , 1 , 1024*1024*10 , 1 , 1 ), out, i++);
111  addResult(results, intra::throughput(10 , 1 , 1024*1024*100, 1 , 1 ), out, i++);
112 
113 #if 0
114  addResult(results, intra::throughput(10 , 1 , 100 , 1 , 10 ), out, i++);
115  addResult(results, intra::throughput(10 , 1 , 1024*1024*10 , 1 , 10 ), out, i++);
116  addResult(results, intra::throughput(10 , 1 , 1024*1024*100, 1 , 10 ), out, i++);
117 
118  addResult(results, intra::throughput(1 , 10 , 100 , 1 , 1 ), out, i++);
119  addResult(results, intra::throughput(1 , 10 , 1024*1024*1 , 1 , 1 ), out, i++);
120  addResult(results, intra::throughput(1 , 10 , 1024*1024*10 , 1 , 1 ), out, i++);
121 
122  addResult(results, intra::throughput(10 , 10 , 100 , 1 , 10 ), out, i++);
123  addResult(results, intra::throughput(10 , 10 , 1024*1024*1 , 1 , 10 ), out, i++);
124  addResult(results, intra::throughput(10 , 10 , 1024*1024*10 , 1 , 10 ), out, i++);
125 #endif
126 }
127 
128 void runLatencyTests(std::ostream& out, V_LatencyResult& results)
129 {
130  uint32_t i = 0;
131  // count per stream, streams, message size , receive threads
132  addResult(results, intra::latency(100000 , 1 , 1 , 1 , 1 ), out, i++);
133  addResult(results, intra::latency(10000 , 1 , 1024 , 1 , 1 ), out, i++);
134  addResult(results, intra::latency(1000 , 1 , 1024*1024 , 1 , 1 ), out, i++);
135  addResult(results, intra::latency(100 , 1 , 1024*1024*100, 1 , 1 ), out, i++);
136 
137 #if 0
138  addResult(results, intra::latency(100000 , 1 , 1 , 1 , 10 ), out, i++);
139  addResult(results, intra::latency(10000 , 1 , 1024 , 1 , 10 ), out, i++);
140  addResult(results, intra::latency(1000 , 1 , 1024*1024 , 1 , 10 ), out, i++);
141  addResult(results, intra::latency(100 , 1 , 1024*1024*100, 1 , 10 ), out, i++);
142 
143  addResult(results, intra::latency(100000 , 10 , 1 , 1 , 1 ), out, i++);
144  addResult(results, intra::latency(10000 , 10 , 1024 , 1 , 1 ), out, i++);
145  addResult(results, intra::latency(1000 , 10 , 1024*1024 , 1 , 1 ), out, i++);
146  addResult(results, intra::latency(100 , 10 , 1024*1024*100, 1 , 1 ), out, i++);
147 
148  addResult(results, intra::latency(10000 , 10 , 1 , 10 , 1 ), out, i++);
149  addResult(results, intra::latency(1000 , 10 , 1024 , 10 , 1 ), out, i++);
150  addResult(results, intra::latency(100 , 10 , 1024*1024 , 10 , 1 ), out, i++);
151  // 100mb test allocates too much memory
152 #endif
153 }
154 
155 void runSTLatencyTests(std::ostream& out, V_STLatencyResult& results)
156 {
157  uint32_t i = 0;
158  addResult(results, intra::stlatency(10000), out, i++);
159  addResult(results, intra::stlatency(100000), out, i++);
160  addResult(results, intra::stlatency(1000000), out, i++);
161 }
162 
163 int main(int argc, char** argv)
164 {
165  std::ofstream out("intra_suite_out.txt", std::ios::out);
166  out << std::fixed;
167  out.precision(10);
168  cout << std::fixed;
169  cout.precision(10);
170 
171  ROS_ASSERT(out.is_open());
172 
173  ros::init(argc, argv, "perf_roscpp_intra_suite", ros::init_options::NoSigintHandler|ros::init_options::NoRosout);
174  ros::NodeHandle nh;
175 
176  V_ThroughputResult throughput_results;
177  runThroughputTests(out, throughput_results);
178 
179  V_LatencyResult latency_results;
180  runLatencyTests(out, latency_results);
181 
182  V_STLatencyResult stlatency_results;
183  runSTLatencyTests(out, stlatency_results);
184 
185  printf("\n\n\n***************************** Results *****************************\n\n");
186  uint32_t i = 0;
187  {
188  V_ThroughputResult::iterator it = throughput_results.begin();
189  V_ThroughputResult::iterator end = throughput_results.end();
190  for (; it != end; ++it, ++i)
191  {
192  intra::ThroughputResult& r = *it;
193  printResult(cout, i, r);
194  }
195  }
196 
197  i = 0;
198  {
199  V_LatencyResult::iterator it = latency_results.begin();
200  V_LatencyResult::iterator end = latency_results.end();
201  for (; it != end; ++it, ++i)
202  {
203  intra::LatencyResult& r = *it;
204  printResult(cout, i, r);
205  }
206  }
207 
208  i = 0;
209  {
210  V_STLatencyResult::iterator it = stlatency_results.begin();
211  V_STLatencyResult::iterator end = stlatency_results.end();
212  for (; it != end; ++it, ++i)
213  {
214  intra::STLatencyResult& r = *it;
215  printResult(cout, i, r);
216  }
217  }
218 }
void printResult(std::ostream &out, uint32_t test_num, intra::ThroughputResult &r)
Definition: intra_suite.cpp:51
STLatencyResult stlatency(uint32_t message_count)
Definition: intra.cpp:710
std::vector< intra::STLatencyResult > V_STLatencyResult
Definition: intra_suite.cpp:49
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void addResult(V_ThroughputResult &results, intra::ThroughputResult r, std::ostream &out, uint32_t i)
Definition: intra_suite.cpp:83
void runLatencyTests(std::ostream &out, V_LatencyResult &results)
void runThroughputTests(std::ostream &out, V_ThroughputResult &results)
ThroughputResult throughput(double duration, uint32_t streams, uint32_t message_size, uint32_t sender_threads, uint32_t receiver_threads)
Definition: intra.cpp:314
std::vector< intra::ThroughputResult > V_ThroughputResult
Definition: intra_suite.cpp:47
std::vector< intra::LatencyResult > V_LatencyResult
Definition: intra_suite.cpp:48
LatencyResult latency(uint32_t count_per_stream, uint32_t streams, uint32_t message_size, uint32_t sender_threads, uint32_t receiver_threads)
Definition: intra.cpp:576
int main(int argc, char **argv)
#define ROS_ASSERT(cond)
void runSTLatencyTests(std::ostream &out, V_STLatencyResult &results)


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:46