params.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /* Author: Josh Faust */
00031 
00032 /*
00033  * Test parameters
00034  */
00035 
00036 #include <string>
00037 #include <sstream>
00038 #include <fstream>
00039 
00040 #include <gtest/gtest.h>
00041 
00042 #include <time.h>
00043 #include <stdlib.h>
00044 
00045 #include "ros/ros.h"
00046 #include <ros/param.h>
00047 
00048 using namespace ros;
00049 
00050 TEST(Params, allParamTypes)
00051 {
00052   std::string string_param;
00053   EXPECT_TRUE( param::get( "string", string_param ) );
00054   EXPECT_TRUE( string_param == "test" );
00055 
00056   int int_param = 0;
00057   EXPECT_TRUE( param::get( "int", int_param ) );
00058   EXPECT_TRUE( int_param == 10 );
00059 
00060   double double_param = 0.0;
00061   EXPECT_TRUE( param::get( "double", double_param ) );
00062   EXPECT_DOUBLE_EQ( double_param, 10.5 );
00063 
00064   bool bool_param = true;
00065   EXPECT_TRUE( param::get( "bool", bool_param ) );
00066   EXPECT_FALSE( bool_param );
00067 }
00068 
00069 TEST(Params, setThenGetString)
00070 {
00071   param::set( "test_set_param", std::string("asdf") );
00072   std::string param;
00073   ASSERT_TRUE( param::get( "test_set_param", param ) );
00074   ASSERT_STREQ( "asdf", param.c_str() );
00075   
00076   XmlRpc::XmlRpcValue v;
00077   param::get("test_set_param", v);
00078   ASSERT_EQ(v.getType(), XmlRpc::XmlRpcValue::TypeString);
00079 }
00080 
00081 TEST(Params, setThenGetStringCached)
00082 {
00083   std::string param;
00084   ASSERT_FALSE( param::getCached( "test_set_param_setThenGetStringCached", param) );
00085 
00086   param::set( "test_set_param_setThenGetStringCached", std::string("asdf") );
00087 
00088   ASSERT_TRUE( param::getCached( "test_set_param_setThenGetStringCached", param) );
00089   ASSERT_STREQ( "asdf", param.c_str() );
00090 }
00091 
00092 TEST(Params, setThenGetStringCachedNodeHandle)
00093 {
00094         NodeHandle nh;
00095   std::string param;
00096   ASSERT_FALSE( nh.getParamCached( "test_set_param_setThenGetStringCachedNodeHandle", param) );
00097 
00098   nh.setParam( "test_set_param_setThenGetStringCachedNodeHandle", std::string("asdf") );
00099 
00100   ASSERT_TRUE( nh.getParamCached( "test_set_param_setThenGetStringCachedNodeHandle", param) );
00101   ASSERT_STREQ( "asdf", param.c_str() );
00102 }
00103 
00104 TEST(Params, setThenGetNamespaceCached)
00105 {
00106   std::string stringParam;
00107   XmlRpc::XmlRpcValue structParam;
00108   const std::string ns = "test_set_param_setThenGetStringCached2";
00109   ASSERT_FALSE(param::getCached(ns, stringParam));
00110 
00111   param::set(ns, std::string("a"));
00112   ASSERT_TRUE(param::getCached(ns, stringParam));
00113   ASSERT_STREQ("a", stringParam.c_str());
00114 
00115   param::set(ns + "/foo", std::string("b"));
00116   ASSERT_TRUE(param::getCached(ns + "/foo", stringParam));
00117   ASSERT_STREQ("b", stringParam.c_str());
00118   ASSERT_TRUE(param::getCached(ns, structParam));
00119   ASSERT_TRUE(structParam.hasMember("foo"));
00120   ASSERT_STREQ("b", static_cast<std::string>(structParam["foo"]).c_str());
00121 }
00122 
00123 TEST(Params, setThenGetCString)
00124 {
00125   param::set( "test_set_param", "asdf" );
00126   std::string param;
00127   ASSERT_TRUE( param::get( "test_set_param", param ) );
00128   ASSERT_STREQ( "asdf", param.c_str() );
00129 }
00130 
00131 TEST(Params, setThenGetInt)
00132 {
00133   param::set( "test_set_param", 42);
00134   int param;
00135   ASSERT_TRUE( param::get( "test_set_param", param ) );
00136   ASSERT_EQ( 42, param );
00137   XmlRpc::XmlRpcValue v;
00138   param::get("test_set_param", v);
00139   ASSERT_EQ(v.getType(), XmlRpc::XmlRpcValue::TypeInt);
00140 }
00141 
00142 TEST(Params, unknownParam)
00143 {
00144   std::string param;
00145   ASSERT_FALSE( param::get( "this_param_really_should_not_exist", param ) );
00146 }
00147 
00148 TEST(Params, deleteParam)
00149 {
00150   param::set( "test_delete_param", "asdf" );
00151   param::del( "test_delete_param" );
00152   std::string param;
00153   ASSERT_FALSE( param::get( "test_delete_param", param ) );
00154 }
00155 
00156 TEST(Params, hasParam)
00157 {
00158   ASSERT_TRUE( param::has( "string" ) );
00159 }
00160 
00161 TEST(Params, setIntDoubleGetInt)
00162 {
00163   param::set("test_set_int_as_double", 1);
00164   param::set("test_set_int_as_double", 3.0f);
00165 
00166   int i = -1;
00167   ASSERT_TRUE(param::get("test_set_int_as_double", i));
00168   ASSERT_EQ(3, i);
00169   double d = 0.0f;
00170   ASSERT_TRUE(param::get("test_set_int_as_double", d));
00171   ASSERT_EQ(3.0, d);
00172 }
00173 
00174 TEST(Params, getIntAsDouble)
00175 {
00176   param::set("int_param", 1);
00177   double d = 0.0;
00178   ASSERT_TRUE(param::get("int_param", d));
00179   ASSERT_EQ(1.0, d);
00180 }
00181 
00182 TEST(Params, getDoubleAsInt)
00183 {
00184   param::set("double_param", 2.3);
00185   int i = -1;
00186   ASSERT_TRUE(param::get("double_param", i));
00187   ASSERT_EQ(2, i);
00188 
00189   param::set("double_param", 3.8);
00190   i = -1;
00191   ASSERT_TRUE(param::get("double_param", i));
00192   ASSERT_EQ(4, i);
00193 }
00194 
00195 TEST(Params, searchParam)
00196 {
00197   std::string ns = "/a/b/c/d/e/f";
00198   std::string result;
00199 
00200   param::set("/s_i", 1);
00201   ASSERT_TRUE(param::search(ns, "s_i", result));
00202   ASSERT_STREQ(result.c_str(), "/s_i");
00203   param::del("/s_i");
00204 
00205   param::set("/a/b/s_i", 1);
00206   ASSERT_TRUE(param::search(ns, "s_i", result));
00207   ASSERT_STREQ(result.c_str(), "/a/b/s_i");
00208   param::del("/a/b/s_i");
00209 
00210   param::set("/a/b/c/d/e/f/s_i", 1);
00211   ASSERT_TRUE(param::search(ns, "s_i", result));
00212   ASSERT_STREQ(result.c_str(), "/a/b/c/d/e/f/s_i");
00213   param::del("/a/b/c/d/e/f/s_i");
00214 
00215   bool cont = true;
00216   while (!cont)
00217   {
00218         ros::WallDuration(0.1).sleep();
00219   }
00220 
00221   ASSERT_FALSE(param::search(ns, "s_j", result));
00222 }
00223 
00224 TEST(Params, searchParamNodeHandle)
00225 {
00226   NodeHandle n("/a/b/c/d/e/f");
00227   std::string result;
00228 
00229   n.setParam("/s_i", 1);
00230   ASSERT_TRUE(n.searchParam("s_i", result));
00231   ASSERT_STREQ(result.c_str(), "/s_i");
00232   n.deleteParam("/s_i");
00233 
00234   n.setParam("/a/b/s_i", 1);
00235   ASSERT_TRUE(n.searchParam("s_i", result));
00236   ASSERT_STREQ(result.c_str(), "/a/b/s_i");
00237   n.deleteParam("/a/b/s_i");
00238 
00239   n.setParam("/a/b/c/d/e/f/s_i", 1);
00240   ASSERT_TRUE(n.searchParam("s_i", result));
00241   ASSERT_STREQ(result.c_str(), "/a/b/c/d/e/f/s_i");
00242   n.deleteParam("/a/b/c/d/e/f/s_i");
00243 
00244   ASSERT_FALSE(n.searchParam("s_j", result));
00245 }
00246 
00247 TEST(Params, searchParamNodeHandleWithRemapping)
00248 {
00249   M_string remappings;
00250   remappings["s_c"] = "s_b";
00251   NodeHandle n("/a/b/c/d/e/f", remappings);
00252   std::string result;
00253 
00254   n.setParam("/s_c", 1);
00255   ASSERT_FALSE(n.searchParam("s_c", result));
00256   n.setParam("/s_b", 1);
00257   ASSERT_TRUE(n.searchParam("s_c", result));
00258 }
00259 
00260 // See ROS ticket #2381
00261 TEST(Params, getMissingXmlRpcValueParameterCachedTwice)
00262 {
00263   XmlRpc::XmlRpcValue v;
00264   ASSERT_FALSE(ros::param::getCached("invalid_xmlrpcvalue_param", v));
00265   ASSERT_FALSE(ros::param::getCached("invalid_xmlrpcvalue_param", v));
00266 }
00267 
00268 // See ROS ticket #2353
00269 TEST(Params, doublePrecision)
00270 {
00271   ros::param::set("bar", 0.123456789123456789);
00272   double d;
00273   ASSERT_TRUE(ros::param::get("bar", d));
00274   EXPECT_DOUBLE_EQ(d, 0.12345678912345678);
00275 }
00276 
00277 std::vector<std::string> vec_s, vec_s2;
00278 std::vector<double> vec_d, vec_d2;
00279 std::vector<float> vec_f, vec_f2;
00280 std::vector<int> vec_i, vec_i2;
00281 std::vector<bool> vec_b, vec_b2;
00282 
00283 TEST(Params, vectorStringParam)
00284 {
00285   const std::string param_name = "vec_str_param";
00286 
00287   vec_s.clear();
00288   vec_s.push_back("foo");
00289   vec_s.push_back("bar");
00290   vec_s.push_back("baz");
00291 
00292   ros::param::set(param_name, vec_s);
00293 
00294   ASSERT_FALSE(ros::param::get(param_name, vec_d));
00295   ASSERT_FALSE(ros::param::get(param_name, vec_f));
00296   ASSERT_FALSE(ros::param::get(param_name, vec_i));
00297   ASSERT_FALSE(ros::param::get(param_name, vec_b));
00298 
00299   ASSERT_TRUE(ros::param::get(param_name, vec_s2));
00300 
00301   ASSERT_EQ(vec_s.size(), vec_s2.size());
00302   ASSERT_TRUE(std::equal(vec_s.begin(), vec_s.end(), vec_s2.begin()));
00303 
00304   // Test empty vector
00305   vec_s.clear();
00306   ros::param::set(param_name, vec_s);
00307   ASSERT_TRUE(ros::param::get(param_name, vec_s2));
00308   ASSERT_EQ(vec_s.size(), vec_s2.size());
00309 }
00310 
00311 TEST(Params, vectorDoubleParam)
00312 {
00313   const std::string param_name = "vec_double_param";
00314 
00315   vec_d.clear();
00316   vec_d.push_back(-0.123456789);
00317   vec_d.push_back(3);
00318   vec_d.push_back(3.01);
00319   vec_d.push_back(7.01);
00320 
00321   ros::param::set(param_name, vec_d);
00322 
00323   ASSERT_FALSE(ros::param::get(param_name, vec_s));
00324   ASSERT_TRUE(ros::param::get(param_name, vec_i));
00325   ASSERT_TRUE(ros::param::get(param_name, vec_b));
00326   ASSERT_TRUE(ros::param::get(param_name, vec_f));
00327 
00328   ASSERT_TRUE(ros::param::get(param_name, vec_d2));
00329 
00330   ASSERT_EQ(vec_d.size(), vec_d2.size());
00331   ASSERT_TRUE(std::equal(vec_d.begin(), vec_d.end(), vec_d2.begin()));
00332 }
00333 
00334 TEST(Params, vectorFloatParam)
00335 {
00336   const std::string param_name = "vec_float_param";
00337 
00338   vec_f.clear();
00339   vec_f.push_back(-0.123456789);
00340   vec_f.push_back(0.0);
00341   vec_f.push_back(3);
00342   vec_f.push_back(3.01);
00343 
00344   ros::param::set(param_name, vec_f);
00345 
00346   ASSERT_FALSE(ros::param::get(param_name, vec_s));
00347   ASSERT_TRUE(ros::param::get(param_name, vec_i));
00348   ASSERT_TRUE(ros::param::get(param_name, vec_b));
00349   ASSERT_TRUE(ros::param::get(param_name, vec_d));
00350 
00351   ASSERT_EQ(vec_b[0],true);
00352   ASSERT_EQ(vec_b[1],false);
00353 
00354   ASSERT_TRUE(ros::param::get(param_name, vec_f2));
00355 
00356   ASSERT_EQ(vec_f.size(), vec_f2.size());
00357   ASSERT_TRUE(std::equal(vec_f.begin(), vec_f.end(), vec_f2.begin()));
00358 }
00359 
00360 TEST(Params, vectorIntParam)
00361 {
00362   const std::string param_name = "vec_int_param";
00363 
00364   vec_i.clear();
00365   vec_i.push_back(-1);
00366   vec_i.push_back(0);
00367   vec_i.push_back(1337);
00368   vec_i.push_back(2);
00369 
00370   ros::param::set(param_name, vec_i);
00371 
00372   ASSERT_FALSE(ros::param::get(param_name, vec_s));
00373   ASSERT_TRUE(ros::param::get(param_name, vec_d));
00374   ASSERT_TRUE(ros::param::get(param_name, vec_f));
00375   ASSERT_TRUE(ros::param::get(param_name, vec_b));
00376 
00377   ASSERT_EQ(vec_b[0],true);
00378   ASSERT_EQ(vec_b[1],false);
00379 
00380   ASSERT_TRUE(ros::param::get(param_name, vec_i2));
00381 
00382   ASSERT_EQ(vec_i.size(), vec_i2.size());
00383   ASSERT_TRUE(std::equal(vec_i.begin(), vec_i.end(), vec_i2.begin()));
00384 }
00385 
00386 TEST(Params, vectorBoolParam)
00387 {
00388   const std::string param_name = "vec_bool_param";
00389 
00390   vec_b.clear();
00391   vec_b.push_back(true);
00392   vec_b.push_back(false);
00393   vec_b.push_back(true);
00394   vec_b.push_back(true);
00395 
00396   ros::param::set(param_name, vec_b);
00397 
00398   ASSERT_FALSE(ros::param::get(param_name, vec_s));
00399   ASSERT_TRUE(ros::param::get(param_name, vec_d));
00400   ASSERT_TRUE(ros::param::get(param_name, vec_f));
00401   ASSERT_TRUE(ros::param::get(param_name, vec_i));
00402 
00403   ASSERT_EQ(vec_i[0],1);
00404   ASSERT_EQ(vec_i[1],0);
00405 
00406   ASSERT_TRUE(ros::param::get(param_name, vec_b2));
00407 
00408   ASSERT_EQ(vec_b.size(), vec_b2.size());
00409   ASSERT_TRUE(std::equal(vec_b.begin(), vec_b.end(), vec_b2.begin()));
00410 }
00411 
00412 std::map<std::string,std::string> map_s, map_s2;
00413 std::map<std::string,double> map_d, map_d2;
00414 std::map<std::string,float> map_f, map_f2;
00415 std::map<std::string,int> map_i, map_i2;
00416 std::map<std::string,bool> map_b, map_b2;
00417 
00418 TEST(Params, mapStringParam)
00419 {
00420   const std::string param_name = "map_str_param";
00421 
00422   map_s.clear();
00423   map_s["a"] = "apple";
00424   map_s["b"] = "blueberry";
00425   map_s["c"] = "carrot";
00426 
00427   ros::param::set(param_name, map_s);
00428 
00429   ASSERT_FALSE(ros::param::get(param_name, map_d));
00430   ASSERT_FALSE(ros::param::get(param_name, map_f));
00431   ASSERT_FALSE(ros::param::get(param_name, map_i));
00432   ASSERT_FALSE(ros::param::get(param_name, map_b));
00433 
00434   ASSERT_TRUE(ros::param::get(param_name, map_s2));
00435 
00436   ASSERT_EQ(map_s.size(), map_s2.size());
00437   ASSERT_TRUE(std::equal(map_s.begin(), map_s.end(), map_s2.begin()));
00438 }
00439 
00440 TEST(Params, mapDoubleParam)
00441 {
00442   const std::string param_name = "map_double_param";
00443 
00444   map_d.clear();
00445   map_d["a"] = 0.0;
00446   map_d["b"] = -0.123456789;
00447   map_d["c"] = 123456789;
00448 
00449   ros::param::set(param_name, map_d);
00450 
00451   ASSERT_FALSE(ros::param::get(param_name, map_s));
00452   ASSERT_TRUE(ros::param::get(param_name, map_f));
00453   ASSERT_TRUE(ros::param::get(param_name, map_i));
00454   ASSERT_TRUE(ros::param::get(param_name, map_b));
00455 
00456   ASSERT_TRUE(ros::param::get(param_name, map_d2));
00457 
00458   ASSERT_EQ(map_d.size(), map_d2.size());
00459   ASSERT_TRUE(std::equal(map_d.begin(), map_d.end(), map_d2.begin()));
00460 }
00461 
00462 TEST(Params, mapFloatParam)
00463 {
00464   const std::string param_name = "map_float_param";
00465 
00466   map_f.clear();
00467   map_f["a"] = 0.0;
00468   map_f["b"] = -0.123456789;
00469   map_f["c"] = 123456789;
00470 
00471   ros::param::set(param_name, map_f);
00472 
00473   ASSERT_FALSE(ros::param::get(param_name, map_s));
00474   ASSERT_TRUE(ros::param::get(param_name, map_d));
00475   ASSERT_TRUE(ros::param::get(param_name, map_i));
00476   ASSERT_TRUE(ros::param::get(param_name, map_b));
00477 
00478   ASSERT_TRUE(ros::param::get(param_name, map_f2));
00479 
00480   ASSERT_EQ(map_f.size(), map_f2.size());
00481   ASSERT_TRUE(std::equal(map_f.begin(), map_f.end(), map_f2.begin()));
00482 }
00483 
00484 TEST(Params, mapIntParam)
00485 {
00486   const std::string param_name = "map_int_param";
00487 
00488   map_i.clear();
00489   map_i["a"] = 0;
00490   map_i["b"] = -1;
00491   map_i["c"] = 1337;
00492 
00493   ros::param::set(param_name, map_i);
00494 
00495   ASSERT_FALSE(ros::param::get(param_name, map_s));
00496   ASSERT_TRUE(ros::param::get(param_name, map_d));
00497   ASSERT_TRUE(ros::param::get(param_name, map_f));
00498   ASSERT_TRUE(ros::param::get(param_name, map_b));
00499 
00500   ASSERT_TRUE(ros::param::get(param_name, map_i2));
00501 
00502   ASSERT_EQ(map_i.size(), map_i2.size());
00503   ASSERT_TRUE(std::equal(map_i.begin(), map_i.end(), map_i2.begin()));
00504 }
00505 
00506 TEST(Params, mapBoolParam)
00507 {
00508   const std::string param_name = "map_bool_param";
00509 
00510   map_b.clear();
00511   map_b["a"] = true;
00512   map_b["b"] = false;
00513   map_b["c"] = true;
00514 
00515   ros::param::set(param_name, map_b);
00516 
00517   ASSERT_FALSE(ros::param::get(param_name, map_s));
00518   ASSERT_TRUE(ros::param::get(param_name, map_d));
00519   ASSERT_TRUE(ros::param::get(param_name, map_f));
00520   ASSERT_TRUE(ros::param::get(param_name, map_i));
00521 
00522   ASSERT_EQ(map_i["a"],1);
00523   ASSERT_EQ(map_i["b"],0);
00524 
00525   ASSERT_TRUE(ros::param::get(param_name, map_b2));
00526 
00527   ASSERT_EQ(map_b.size(), map_b2.size());
00528   ASSERT_TRUE(std::equal(map_b.begin(), map_b.end(), map_b2.begin()));
00529 }
00530 
00531 TEST(Params, paramTemplateFunction)
00532 {
00533   EXPECT_EQ( param::param<std::string>( "string", "" ), "test" );
00534   EXPECT_EQ( param::param<std::string>( "gnirts", "test" ), "test" );
00535 
00536   EXPECT_EQ( param::param<int>( "int", 0 ), 10 );
00537   EXPECT_EQ( param::param<int>( "tni", 10 ), 10 );
00538 
00539   EXPECT_DOUBLE_EQ( param::param<double>( "double", 0.0 ), 10.5 );
00540   EXPECT_DOUBLE_EQ( param::param<double>( "elbuod", 10.5 ), 10.5 );
00541 
00542   EXPECT_EQ( param::param<bool>( "bool", true ), false );
00543   EXPECT_EQ( param::param<bool>( "loob", true ), true );
00544 }
00545 
00546 TEST(Params, paramNodeHandleTemplateFunction)
00547 {
00548   NodeHandle nh;
00549 
00550   EXPECT_EQ( nh.param<std::string>( "string", "" ), "test" );
00551   EXPECT_EQ( nh.param<std::string>( "gnirts", "test" ), "test" );
00552 
00553   EXPECT_EQ( nh.param<int>( "int", 0 ), 10 );
00554   EXPECT_EQ( nh.param<int>( "tni", 10 ), 10 );
00555 
00556   EXPECT_DOUBLE_EQ( nh.param<double>( "double", 0.0 ), 10.5 );
00557   EXPECT_DOUBLE_EQ( nh.param<double>( "elbuod", 10.5 ), 10.5 );
00558 
00559   EXPECT_EQ( nh.param<bool>( "bool", true ), false );
00560   EXPECT_EQ( nh.param<bool>( "loob", true ), true );
00561 }
00562 
00563 TEST(Params, getParamNames) {
00564   std::vector<std::string> test_params;
00565   EXPECT_TRUE(ros::param::getParamNames(test_params));
00566   EXPECT_LT(10, test_params.size());
00567 }
00568 
00569 int
00570 main(int argc, char** argv)
00571 {
00572   testing::InitGoogleTest(&argc, argv);
00573   ros::init( argc, argv, "params" );
00574 //  ros::NodeHandle nh;
00575 
00576   return RUN_ALL_TESTS();
00577 }


test_roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Thu Jun 6 2019 21:10:42