moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
warehouse_fixture.cpp
Go to the documentation of this file.
1// Copyright 2024 Intrinsic Innovation LLC.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
19#include <thread>
20
21#include <gtest/gtest.h>
22#include <rclcpp/rclcpp.hpp>
24
25#include "warehouse_fixture.hpp"
26
27WarehouseFixture::WarehouseFixture() : node_(rclcpp::Node::make_shared("warehouse_fixture"))
28{
29 node_->declare_parameter<std::string>("warehouse_plugin", "warehouse_ros_sqlite::DatabaseConnection");
30}
31
33{
34 is_spinning_ = false;
35 if (spin_thread_.joinable())
36 {
37 spin_thread_.join();
38 }
39}
40
42{
43 is_spinning_ = true;
44 spin_thread_ = std::thread(&WarehouseFixture::spinNode, this);
45
47 db_->setParams(":memory:", 1);
48 ASSERT_TRUE(db_->connect());
49}
50
52{
53 db_.reset();
54 is_spinning_ = false;
55 spin_thread_.join();
56}
57
58void WarehouseFixture::spinNode()
59{
60 while (is_spinning_ && rclcpp::ok())
61 {
62 rclcpp::spin_some(node_);
63 }
64}
rclcpp::Node::SharedPtr node_
warehouse_ros::DatabaseConnection::Ptr db_
void TearDown() override
void SetUp() override
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.