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 
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ompl_planning.test.test_thread_safe_storage");
46 
49 {
50 public:
51  TestThreadSafeStateStorage(const std::string& robot_name, const std::string& group_name)
52  : LoadTestRobot(robot_name, group_name)
53  {
54  }
55 
57  void testReadback(const std::vector<double>& position_in_limits)
58  {
59  SCOPED_TRACE("testConstruction");
60 
61  // Set the robot_state_ to the given position
62  robot_state_->setJointGroupPositions(joint_model_group_, position_in_limits);
63 
64  // Construct the TSStateStorage using the constructor taking the robot state
66 
67  // Readback the stored state
68  auto robot_state_stored = tss.getStateStorage();
69 
70  // Check if robot_state_stored's joint angles matches with what we set
71  for (auto const& joint_name : robot_state_->getVariableNames())
72  {
73  auto const expected_value = robot_state_->getVariablePosition(joint_name);
74  auto const actual_value = robot_state_stored->getVariablePosition(joint_name);
75  EXPECT_EQ(actual_value, expected_value) << "Expecting joint value for " << joint_name << " to match.";
76  }
77  }
78 
79 protected:
80  void SetUp() override
81  {
82  }
83 };
84 
85 // /***************************************************************************
86 // * Run all tests on the Panda robot
87 // * ************************************************************************/
89 {
90 protected:
91  PandaTest() : TestThreadSafeStateStorage("panda", "panda_arm")
92  {
93  }
94 };
95 
96 TEST_F(PandaTest, testConstruction)
97 {
98  testReadback({ 0., -0.785, 0., -2.356, 0., 1.571, 0.785 });
99 }
100 
101 /***************************************************************************
102  * Run all tests on the Fanuc robot
103  * ************************************************************************/
105 {
106 protected:
107  FanucTest() : TestThreadSafeStateStorage("fanuc", "manipulator")
108  {
109  }
110 };
111 
112 TEST_F(FanucTest, testConstructor)
113 {
114  testReadback({ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 });
115 }
116 
117 /***************************************************************************
118  * MAIN
119  * ************************************************************************/
120 int main(int argc, char** argv)
121 {
122  testing::InitGoogleTest(&argc, argv);
123  return RUN_ALL_TESTS();
124 }
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)