moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_threadsafe_state_storage.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, KU Leuven
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 KU Leuven 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 /* Author: Pradeep Rajendran */
36 /*
37 This test checks if a state can be set in TSSafeStateStorage and correctly retrieved.
38 The skeleton of this test was taken from test_state_validity_checker.cpp by Jeroen De Maeyer.
39 */
40 
41 #include "load_test_robot.h"
43 #include <gtest/gtest.h>
44 
47 {
48 public:
49  TestThreadSafeStateStorage(const std::string& robot_name, const std::string& group_name)
50  : LoadTestRobot(robot_name, group_name)
51  {
52  }
53 
55  void testReadback(const std::vector<double>& position_in_limits)
56  {
57  SCOPED_TRACE("testConstruction");
58 
59  // Set the robot_state_ to the given position
60  robot_state_->setJointGroupPositions(joint_model_group_, position_in_limits);
61 
62  // Construct the TSStateStorage using the constructor taking the robot state
64 
65  // Readback the stored state
66  auto robot_state_stored = tss.getStateStorage();
67 
68  // Check if robot_state_stored's joint angles matches with what we set
69  for (const auto& joint_name : robot_state_->getVariableNames())
70  {
71  const auto expected_value = robot_state_->getVariablePosition(joint_name);
72  const auto actual_value = robot_state_stored->getVariablePosition(joint_name);
73  EXPECT_EQ(actual_value, expected_value) << "Expecting joint value for " << joint_name << " to match.";
74  }
75  }
76 
77 protected:
78  void SetUp() override
79  {
80  }
81 };
82 
83 // /***************************************************************************
84 // * Run all tests on the Panda robot
85 // * ************************************************************************/
87 {
88 protected:
89  PandaTest() : TestThreadSafeStateStorage("panda", "panda_arm")
90  {
91  }
92 };
93 
94 TEST_F(PandaTest, testConstruction)
95 {
96  testReadback({ 0., -0.785, 0., -2.356, 0., 1.571, 0.785 });
97 }
98 
99 /***************************************************************************
100  * Run all tests on the Fanuc robot
101  * ************************************************************************/
103 {
104 protected:
105  FanucTest() : TestThreadSafeStateStorage("fanuc", "manipulator")
106  {
107  }
108 };
109 
110 TEST_F(FanucTest, testConstructor)
111 {
112  testReadback({ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 });
113 }
114 
115 /***************************************************************************
116  * MAIN
117  * ************************************************************************/
118 int main(int argc, char** argv)
119 {
120  testing::InitGoogleTest(&argc, argv);
121  return RUN_ALL_TESTS();
122 }
Generic implementation of the tests that can be executed on different robots.
void testReadback(const std::vector< double > &position_in_limits)
TestThreadSafeStateStorage(const std::string &robot_name, const std::string &group_name)
moveit::core::RobotState * getStateStorage() const
Robot independent test class setup.
moveit::core::RobotStatePtr robot_state_
LoadTestRobot(const std::string &robot_name, const std::string &group_name)
const moveit::core::JointModelGroup * joint_model_group_
int main(int argc, char **argv)
TEST_F(PandaTest, testConstruction)