locked_robot_state_test.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Willow Garage, Inc.
00005  *  Copyright (c) 2014, SRI International
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 /* Author: Acorn Pooley, Ioan Sucan */
00037 
00038 #include <gtest/gtest.h>
00039 #include <moveit/robot_interaction/locked_robot_state.h>
00040 #include <moveit/robot_model/robot_model.h>
00041 #include <moveit/robot_state/robot_state.h>
00042 #include <urdf_parser/urdf_parser.h>
00043 
00044 static const char* URDF_STR = "<?xml version=\"1.0\" ?>"
00045                               "<robot name=\"one_robot\">"
00046                               "<link name=\"base_link\">"
00047                               "  <inertial>"
00048                               "    <mass value=\"2.81\"/>"
00049                               "    <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>"
00050                               "    <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
00051                               "  </inertial>"
00052                               "  <collision name=\"my_collision\">"
00053                               "    <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
00054                               "    <geometry>"
00055                               "      <box size=\"1 2 1\" />"
00056                               "    </geometry>"
00057                               "  </collision>"
00058                               "  <visual>"
00059                               "    <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
00060                               "    <geometry>"
00061                               "      <box size=\"1 2 1\" />"
00062                               "    </geometry>"
00063                               "  </visual>"
00064                               "</link>"
00065                               "<joint name=\"joint_a\" type=\"continuous\">"
00066                               "   <axis xyz=\"0 0 1\"/>"
00067                               "   <parent link=\"base_link\"/>"
00068                               "   <child link=\"link_a\"/>"
00069                               "   <origin rpy=\" 0.0 0 0 \" xyz=\"0.0 0 0 \"/>"
00070                               "</joint>"
00071                               "<link name=\"link_a\">"
00072                               "  <inertial>"
00073                               "    <mass value=\"1.0\"/>"
00074                               "    <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>"
00075                               "    <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
00076                               "  </inertial>"
00077                               "  <collision>"
00078                               "    <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
00079                               "    <geometry>"
00080                               "      <box size=\"1 2 1\" />"
00081                               "    </geometry>"
00082                               "  </collision>"
00083                               "  <visual>"
00084                               "    <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
00085                               "    <geometry>"
00086                               "      <box size=\"1 2 1\" />"
00087                               "    </geometry>"
00088                               "  </visual>"
00089                               "</link>"
00090                               "<joint name=\"joint_b\" type=\"fixed\">"
00091                               "  <parent link=\"link_a\"/>"
00092                               "  <child link=\"link_b\"/>"
00093                               "  <origin rpy=\" 0.0 -0.42 0 \" xyz=\"0.0 0.5 0 \"/>"
00094                               "</joint>"
00095                               "<link name=\"link_b\">"
00096                               "  <inertial>"
00097                               "    <mass value=\"1.0\"/>"
00098                               "    <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>"
00099                               "    <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
00100                               "  </inertial>"
00101                               "  <collision>"
00102                               "    <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
00103                               "    <geometry>"
00104                               "      <box size=\"1 2 1\" />"
00105                               "    </geometry>"
00106                               "  </collision>"
00107                               "  <visual>"
00108                               "    <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
00109                               "    <geometry>"
00110                               "      <box size=\"1 2 1\" />"
00111                               "    </geometry>"
00112                               "  </visual>"
00113                               "</link>"
00114                               "  <joint name=\"joint_c\" type=\"prismatic\">"
00115                               "    <axis xyz=\"1 0 0\"/>"
00116                               "    <limit effort=\"100.0\" lower=\"0.0\" upper=\"0.09\" velocity=\"0.2\"/>"
00117                               "    <safety_controller k_position=\"20.0\" k_velocity=\"500.0\" "
00118                               "soft_lower_limit=\"0.0\" soft_upper_limit=\"0.089\"/>"
00119                               "    <parent link=\"link_b\"/>"
00120                               "    <child link=\"link_c\"/>"
00121                               "    <origin rpy=\" 0.0 0.42 0.0 \" xyz=\"0.0 -0.1 0 \"/>"
00122                               "  </joint>"
00123                               "<link name=\"link_c\">"
00124                               "  <inertial>"
00125                               "    <mass value=\"1.0\"/>"
00126                               "    <origin rpy=\"0 0 0\" xyz=\"0.0 0 .0\"/>"
00127                               "    <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
00128                               "  </inertial>"
00129                               "  <collision>"
00130                               "    <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
00131                               "    <geometry>"
00132                               "      <box size=\"1 2 1\" />"
00133                               "    </geometry>"
00134                               "  </collision>"
00135                               "  <visual>"
00136                               "    <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
00137                               "    <geometry>"
00138                               "      <box size=\"1 2 1\" />"
00139                               "    </geometry>"
00140                               "  </visual>"
00141                               "</link>"
00142                               "  <joint name=\"mim_f\" type=\"prismatic\">"
00143                               "    <axis xyz=\"1 0 0\"/>"
00144                               "    <limit effort=\"100.0\" lower=\"0.0\" upper=\"0.19\" velocity=\"0.2\"/>"
00145                               "    <parent link=\"link_c\"/>"
00146                               "    <child link=\"link_d\"/>"
00147                               "    <origin rpy=\" 0.0 0.1 0.0 \" xyz=\"0.1 0.1 0 \"/>"
00148                               "    <mimic joint=\"joint_f\" multiplier=\"1.5\" offset=\"0.1\"/>"
00149                               "  </joint>"
00150                               "  <joint name=\"joint_f\" type=\"prismatic\">"
00151                               "    <axis xyz=\"1 0 0\"/>"
00152                               "    <limit effort=\"100.0\" lower=\"0.0\" upper=\"0.19\" velocity=\"0.2\"/>"
00153                               "    <parent link=\"link_d\"/>"
00154                               "    <child link=\"link_e\"/>"
00155                               "    <origin rpy=\" 0.0 0.1 0.0 \" xyz=\"0.1 0.1 0 \"/>"
00156                               "  </joint>"
00157                               "<link name=\"link_d\">"
00158                               "  <collision>"
00159                               "    <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
00160                               "    <geometry>"
00161                               "      <box size=\"1 2 1\" />"
00162                               "    </geometry>"
00163                               "  </collision>"
00164                               "  <visual>"
00165                               "    <origin rpy=\"0 1 0\" xyz=\"0 0.1 0\"/>"
00166                               "    <geometry>"
00167                               "      <box size=\"1 2 1\" />"
00168                               "    </geometry>"
00169                               "  </visual>"
00170                               "</link>"
00171                               "<link name=\"link_e\">"
00172                               "  <collision>"
00173                               "    <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
00174                               "    <geometry>"
00175                               "      <box size=\"1 2 1\" />"
00176                               "    </geometry>"
00177                               "  </collision>"
00178                               "  <visual>"
00179                               "    <origin rpy=\"0 1 0\" xyz=\"0 0.1 0\"/>"
00180                               "    <geometry>"
00181                               "      <box size=\"1 2 1\" />"
00182                               "    </geometry>"
00183                               "  </visual>"
00184                               "</link>"
00185                               "</robot>";
00186 
00187 static const char* SRDF_STR =
00188     "<?xml version=\"1.0\" ?>"
00189     "<robot name=\"one_robot\">"
00190     "<virtual_joint name=\"base_joint\" child_link=\"base_link\" parent_frame=\"odom_combined\" type=\"planar\"/>"
00191     "<group name=\"base_from_joints\">"
00192     "<joint name=\"base_joint\"/>"
00193     "<joint name=\"joint_a\"/>"
00194     "<joint name=\"joint_c\"/>"
00195     "</group>"
00196     "<group name=\"mim_joints\">"
00197     "<joint name=\"joint_f\"/>"
00198     "<joint name=\"mim_f\"/>"
00199     "</group>"
00200     "<group name=\"base_with_subgroups\">"
00201     "<group name=\"base_from_base_to_tip\"/>"
00202     "<joint name=\"joint_c\"/>"
00203     "</group>"
00204     "<group name=\"base_from_base_to_tip\">"
00205     "<chain base_link=\"base_link\" tip_link=\"link_b\"/>"
00206     "<joint name=\"base_joint\"/>"
00207     "</group>"
00208     "</robot>";
00209 
00210 // index of joints from URDF
00211 enum
00212 {
00213   JOINT_A = 3,
00214   JOINT_C = 4,
00215   MIM_F = 5,
00216   JOINT_F = 6
00217 };
00218 
00219 static moveit::core::RobotModelPtr getModel()
00220 {
00221   static moveit::core::RobotModelPtr model;
00222   if (!model)
00223   {
00224     boost::shared_ptr<urdf::ModelInterface> urdf(urdf::parseURDF(URDF_STR));
00225     boost::shared_ptr<srdf::Model> srdf(new srdf::Model());
00226     srdf->initString(*urdf, SRDF_STR);
00227     model.reset(new moveit::core::RobotModel(urdf, srdf));
00228   }
00229   return model;
00230 }
00231 
00232 // Test constructors and robot model loading
00233 TEST(LockedRobotState, load)
00234 {
00235   moveit::core::RobotModelPtr model = getModel();
00236 
00237   robot_interaction::LockedRobotState ls1(model);
00238 
00239   moveit::core::RobotState state2(model);
00240   state2.setToDefaultValues();
00241   robot_interaction::LockedRobotState ls2(state2);
00242 
00243   robot_interaction::LockedRobotStatePtr ls4(new robot_interaction::LockedRobotState(model));
00244 }
00245 
00246 // sanity test the URDF and enum
00247 TEST(LockedRobotState, URDF_sanity)
00248 {
00249   moveit::core::RobotModelPtr model = getModel();
00250   robot_interaction::LockedRobotState ls1(model);
00251 
00252   EXPECT_EQ(ls1.getState()->getVariableNames()[JOINT_A], "joint_a");
00253 }
00254 
00255 // A superclass to test the robotStateChanged() virtual method
00256 class Super1 : public robot_interaction::LockedRobotState
00257 {
00258 public:
00259   Super1(const robot_model::RobotModelPtr& model) : LockedRobotState(model), cnt_(0)
00260   {
00261   }
00262 
00263   virtual void robotStateChanged()
00264   {
00265     cnt_++;
00266   }
00267 
00268   int cnt_;
00269 };
00270 
00271 static void modify1(robot_state::RobotState* state)
00272 {
00273   state->setVariablePosition(JOINT_A, 0.00006);
00274 }
00275 
00276 TEST(LockedRobotState, robotStateChanged)
00277 {
00278   moveit::core::RobotModelPtr model = getModel();
00279 
00280   Super1 ls1(model);
00281 
00282   EXPECT_EQ(ls1.cnt_, 0);
00283 
00284   robot_state::RobotState cp1(*ls1.getState());
00285   cp1.setVariablePosition(JOINT_A, 0.00001);
00286   cp1.setVariablePosition(JOINT_C, 0.00002);
00287   cp1.setVariablePosition(JOINT_F, 0.00003);
00288   ls1.setState(cp1);
00289 
00290   EXPECT_EQ(ls1.cnt_, 1);
00291 
00292   ls1.modifyState(modify1);
00293   EXPECT_EQ(ls1.cnt_, 2);
00294 
00295   ls1.modifyState(modify1);
00296   EXPECT_EQ(ls1.cnt_, 3);
00297 }
00298 
00299 // Class for testing LockedRobotState in multithreaded environment.
00300 // Contains thread functions for modifying/checking a LockedRobotState.
00301 class MyInfo
00302 {
00303 public:
00304   MyInfo() : quit_(false)
00305   {
00306   }
00307 
00308   // Thread that repeatedly sets state to different values
00309   void setThreadFunc(robot_interaction::LockedRobotState* locked_state, int* counter, double offset);
00310 
00311   // Thread that repeatedly modifies  state with different values
00312   void modifyThreadFunc(robot_interaction::LockedRobotState* locked_state, int* counter, double offset);
00313 
00314   // Thread that repeatedly checks that state is valid (not half-updated)
00315   void checkThreadFunc(robot_interaction::LockedRobotState* locked_state, int* counter);
00316 
00317   // Thread that waits for other threads to complete
00318   void waitThreadFunc(robot_interaction::LockedRobotState* locked_state, int** counters, int max);
00319 
00320 private:
00321   // helper function for modifyThreadFunc
00322   void modifyFunc(robot_state::RobotState* state, double val);
00323 
00324   // Checks state for validity and self-consistancy.
00325   void checkState(robot_interaction::LockedRobotState& locked_state);
00326 
00327   // mutex protects quit_ and counter variables
00328   boost::mutex cnt_lock_;
00329 
00330   // set to true by waitThreadFunc() when all counters have reached at least
00331   // max.
00332   bool quit_;
00333 };
00334 
00335 // Check the state.  It should always be valid.
00336 void MyInfo::checkState(robot_interaction::LockedRobotState& locked_state)
00337 {
00338   robot_state::RobotStateConstPtr s = locked_state.getState();
00339 
00340   robot_state::RobotState cp1(*s);
00341 
00342   // take some time
00343   cnt_lock_.lock();
00344   cnt_lock_.unlock();
00345   cnt_lock_.lock();
00346   cnt_lock_.unlock();
00347   cnt_lock_.lock();
00348   cnt_lock_.unlock();
00349 
00350   // check mim_f == joint_f
00351   EXPECT_EQ(s->getVariablePositions()[MIM_F], s->getVariablePositions()[JOINT_F] * 1.5 + 0.1);
00352 
00353   robot_state::RobotState cp2(*s);
00354 
00355   EXPECT_NE(cp1.getVariablePositions(), cp2.getVariablePositions());
00356   EXPECT_NE(cp1.getVariablePositions(), s->getVariablePositions());
00357 
00358   int cnt = cp1.getVariableCount();
00359   for (int i = 0; i < cnt; ++i)
00360   {
00361     EXPECT_EQ(cp1.getVariablePositions()[i], cp2.getVariablePositions()[i]);
00362     EXPECT_EQ(cp1.getVariablePositions()[i], s->getVariablePositions()[i]);
00363   }
00364 
00365   // check mim_f == joint_f
00366   EXPECT_EQ(s->getVariablePositions()[MIM_F], s->getVariablePositions()[JOINT_F] * 1.5 + 0.1);
00367 }
00368 
00369 // spin, checking the state
00370 void MyInfo::checkThreadFunc(robot_interaction::LockedRobotState* locked_state, int* counter)
00371 {
00372   bool go = true;
00373   while (go)
00374   {
00375     for (int loops = 0; loops < 100; ++loops)
00376     {
00377       checkState(*locked_state);
00378     }
00379 
00380     cnt_lock_.lock();
00381     go = !quit_;
00382     ++*counter;
00383     cnt_lock_.unlock();
00384   }
00385 }
00386 
00387 // spin, setting the state to different values
00388 void MyInfo::setThreadFunc(robot_interaction::LockedRobotState* locked_state, int* counter, double offset)
00389 {
00390   bool go = true;
00391   while (go)
00392   {
00393     double val = offset;
00394     for (int loops = 0; loops < 100; ++loops)
00395     {
00396       val += 0.0001;
00397       robot_state::RobotState cp1(*locked_state->getState());
00398 
00399       cp1.setVariablePosition(JOINT_A, val + 0.00001);
00400       cp1.setVariablePosition(JOINT_C, val + 0.00002);
00401       cp1.setVariablePosition(JOINT_F, val + 0.00003);
00402 
00403       locked_state->setState(cp1);
00404     }
00405 
00406     cnt_lock_.lock();
00407     go = !quit_;
00408     ++*counter;
00409     cnt_lock_.unlock();
00410 
00411     checkState(*locked_state);
00412 
00413     val += 0.000001;
00414   }
00415 }
00416 
00417 // modify the state in place.  Used by MyInfo::modifyThreadFunc()
00418 void MyInfo::modifyFunc(robot_state::RobotState* state, double val)
00419 {
00420   state->setVariablePosition(JOINT_A, val + 0.00001);
00421   state->setVariablePosition(JOINT_C, val + 0.00002);
00422   state->setVariablePosition(JOINT_F, val + 0.00003);
00423 }
00424 
00425 // spin, modifying the state to different values
00426 void MyInfo::modifyThreadFunc(robot_interaction::LockedRobotState* locked_state, int* counter, double offset)
00427 {
00428   bool go = true;
00429   while (go)
00430   {
00431     double val = offset;
00432     for (int loops = 0; loops < 100; ++loops)
00433     {
00434       val += 0.0001;
00435 
00436       locked_state->modifyState(boost::bind(&MyInfo::modifyFunc, this, _1, val));
00437     }
00438 
00439     cnt_lock_.lock();
00440     go = !quit_;
00441     ++*counter;
00442     cnt_lock_.unlock();
00443 
00444     checkState(*locked_state);
00445 
00446     val += 0.000001;
00447   }
00448 }
00449 
00450 // spin until all counters reach at least max
00451 void MyInfo::waitThreadFunc(robot_interaction::LockedRobotState* locked_state, int** counters, int max)
00452 {
00453   bool go = true;
00454   while (go)
00455   {
00456     go = false;
00457     cnt_lock_.lock();
00458     for (int i = 0; counters[i]; ++i)
00459     {
00460       if (counters[i][0] < max)
00461         go = true;
00462     }
00463     cnt_lock_.unlock();
00464 
00465     checkState(*locked_state);
00466     checkState(*locked_state);
00467   }
00468   cnt_lock_.lock();
00469   quit_ = true;
00470   cnt_lock_.unlock();
00471 }
00472 
00473 // Run several threads and ensure they modify the state consistantly
00474 //   ncheck - # of checkThreadFunc threads to run
00475 //   nset   - # of setThreadFunc threads to run
00476 //   nmod   - # of modifyThreadFunc threads to run
00477 static void runThreads(int ncheck, int nset, int nmod)
00478 {
00479   MyInfo info;
00480 
00481   moveit::core::RobotModelPtr model = getModel();
00482   robot_interaction::LockedRobotState ls1(model);
00483 
00484   int num = ncheck + nset + nmod;
00485 
00486   typedef int* int_ptr;
00487   typedef boost::thread* thread_ptr;
00488   int* cnt = new int[num];
00489   int_ptr* counters = new int_ptr[num + 1];
00490   thread_ptr* threads = new thread_ptr[num];
00491 
00492   int p = 0;
00493   double val = 0.1;
00494 
00495   // These threads check the validity of the RobotState
00496   for (int i = 0; i < ncheck; ++i)
00497   {
00498     cnt[p] = 0;
00499     counters[p] = &cnt[p];
00500     threads[p] = new boost::thread(&MyInfo::checkThreadFunc, &info, &ls1, &cnt[p]);
00501     val += 0.1;
00502     p++;
00503   }
00504 
00505   // These threads set the RobotState to new values
00506   for (int i = 0; i < nset; ++i)
00507   {
00508     cnt[p] = 0;
00509     counters[p] = &cnt[p];
00510     threads[p] = new boost::thread(&MyInfo::setThreadFunc, &info, &ls1, &cnt[p], val);
00511     val += 0.1;
00512     p++;
00513   }
00514 
00515   // These threads modify the RobotState in place
00516   for (int i = 0; i < nmod; ++i)
00517   {
00518     cnt[p] = 0;
00519     counters[p] = &cnt[p];
00520     threads[p] = new boost::thread(&MyInfo::modifyThreadFunc, &info, &ls1, &cnt[p], val);
00521     val += 0.1;
00522     p++;
00523   }
00524 
00525   ASSERT_EQ(p, num);
00526   counters[p] = NULL;
00527 
00528   // this thread waits for all the other threads to make progress, then stops
00529   // everything.
00530   boost::thread wthread(&MyInfo::waitThreadFunc, &info, &ls1, counters, 1000);
00531 
00532   // wait for all threads to finish
00533   for (int i = 0; i < p; ++i)
00534   {
00535     threads[i]->join();
00536     wthread.join();
00537   }
00538 
00539   // clean up
00540   for (int i = 0; i < p; ++i)
00541   {
00542     delete threads[i];
00543   }
00544   delete[] cnt;
00545   delete[] counters;
00546   delete[] threads;
00547 }
00548 
00549 TEST(LockedRobotState, set1)
00550 {
00551   runThreads(1, 1, 0);
00552 }
00553 
00554 TEST(LockedRobotState, set2)
00555 {
00556   runThreads(1, 2, 0);
00557 }
00558 
00559 TEST(LockedRobotState, set3)
00560 {
00561   runThreads(1, 3, 0);
00562 }
00563 
00564 TEST(LockedRobotState, mod1)
00565 {
00566   runThreads(1, 0, 1);
00567 }
00568 
00569 TEST(LockedRobotState, mod2)
00570 {
00571   runThreads(1, 0, 1);
00572 }
00573 
00574 TEST(LockedRobotState, mod3)
00575 {
00576   runThreads(1, 0, 1);
00577 }
00578 
00579 TEST(LockedRobotState, set1mod1)
00580 {
00581   runThreads(1, 1, 1);
00582 }
00583 
00584 TEST(LockedRobotState, set2mod1)
00585 {
00586   runThreads(1, 2, 1);
00587 }
00588 
00589 TEST(LockedRobotState, set1mod2)
00590 {
00591   runThreads(1, 1, 2);
00592 }
00593 
00594 TEST(LockedRobotState, set3mod1)
00595 {
00596   runThreads(1, 3, 1);
00597 }
00598 
00599 TEST(LockedRobotState, set1mod3)
00600 {
00601   runThreads(1, 1, 3);
00602 }
00603 
00604 TEST(LockedRobotState, set3mod3)
00605 {
00606   runThreads(1, 3, 3);
00607 }
00608 
00609 TEST(LockedRobotState, set3mod3c3)
00610 {
00611   runThreads(3, 3, 3);
00612 }
00613 
00614 int main(int argc, char** argv)
00615 {
00616   testing::InitGoogleTest(&argc, argv);
00617   int arg;
00618 
00619   return RUN_ALL_TESTS();
00620 }


robot_interaction
Author(s): Ioan Sucan
autogenerated on Wed Jun 19 2019 19:24:44