moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
test_rdf_integration.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2021, PickNik Robotics
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 PickNik Robotics 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: David V. Lu!! */
36
38#include <rclcpp/rclcpp.hpp>
39#include <gtest/gtest.h>
40
41TEST(RDFIntegration, default_arguments)
42{
43 rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("default_arguments");
44 rdf_loader::RDFLoader loader(node);
45 ASSERT_NE(nullptr, loader.getURDF());
46 EXPECT_EQ("kermit", loader.getURDF()->name_);
47 ASSERT_NE(nullptr, loader.getSRDF());
48 EXPECT_EQ("kermit", loader.getSRDF()->getName());
49}
50
51TEST(RDFIntegration, non_existent)
52{
53 rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("non_existent");
54 rdf_loader::RDFLoader loader(node, "does_not_exist");
55 ASSERT_EQ(nullptr, loader.getURDF());
56 ASSERT_EQ(nullptr, loader.getSRDF());
57}
58
59TEST(RDFIntegration, topic_based)
60{
61 rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("topic_based");
62 rdf_loader::RDFLoader loader(node, "topic_description");
63 ASSERT_NE(nullptr, loader.getURDF());
64 EXPECT_EQ("gonzo", loader.getURDF()->name_);
65 ASSERT_NE(nullptr, loader.getSRDF());
66 EXPECT_EQ("gonzo", loader.getSRDF()->getName());
67}
68
69TEST(RDFIntegration, executor)
70{
71 // RDFLoader should successfully load URDF and SRDF strings from a ROS topic when the node that is
72 // passed to it is spinning.
73 // GIVEN a node that has been added to an executor that is spinning on another thread
74 rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("executor");
75
76 // Create a thread to spin an Executor.
77 rclcpp::executors::SingleThreadedExecutor executor;
78 executor.add_node(node);
79 std::thread spinning_thread([&executor] { executor.spin(); });
80
81 // WHEN the RDFLoader is created
82 rdf_loader::RDFLoader loader(node, "topic_description");
83
84 // THEN the RDFLoader should return non-null values for the URDF and SRDF model.
85 ASSERT_NE(nullptr, loader.getURDF());
86 EXPECT_EQ("gonzo", loader.getURDF()->name_);
87 ASSERT_NE(nullptr, loader.getSRDF());
88 EXPECT_EQ("gonzo", loader.getSRDF()->getName());
89 executor.cancel();
90 spinning_thread.join();
91}
92
93TEST(RDFIntegration, xacro_test)
94{
95 std::string output;
96 std::vector<std::string> xacro_args;
97 ASSERT_TRUE(rdf_loader::RDFLoader::loadPkgFileToString(output, "moveit_ros_planning",
98 "rdf_loader/test/data/robin.srdf.xacro", xacro_args));
99 EXPECT_GT(output.size(), 0u);
100}
101
102int main(int argc, char** argv)
103{
104 rclcpp::init(argc, argv);
105 ::testing::InitGoogleTest(&argc, argv);
106
107 int ret = RUN_ALL_TESTS();
108 rclcpp::shutdown();
109 return ret;
110}
const urdf::ModelInterfaceSharedPtr & getURDF() const
Get the parsed URDF model.
Definition rdf_loader.h:91
static bool loadPkgFileToString(std::string &buffer, const std::string &package_name, const std::string &relative_path, const std::vector< std::string > &xacro_args)
helper that generates a file path based on package name and relative file path to package
const srdf::ModelSharedPtr & getSRDF() const
Get the parsed SRDF model.
Definition rdf_loader.h:97
int main(int argc, char **argv)
TEST(RDFIntegration, default_arguments)