43 #include <gtest/gtest.h> 
   45 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit.ompl_planning.test.test_thread_safe_storage");
 
   59     SCOPED_TRACE(
"testConstruction");
 
   71     for (
auto const& joint_name : 
robot_state_->getVariableNames())
 
   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.";
 
   98   testReadback({ 0., -0.785, 0., -2.356, 0., 1.571, 0.785 });
 
  114   testReadback({ 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 });
 
  120 int main(
int argc, 
char** argv)
 
  122   testing::InitGoogleTest(&argc, argv);
 
  123   return RUN_ALL_TESTS();
 
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)