moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
move_group_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>
24#include <rclcpp/rclcpp.hpp>
25
27
29 : node_(rclcpp::Node::make_shared("move_group_fixture")), move_group_name_("panda_arm")
30{
31 node_->declare_parameter<std::string>("warehouse_plugin", "warehouse_ros_sqlite::DatabaseConnection");
32 move_group_ = std::make_shared<moveit::planning_interface::MoveGroupInterface>(node_, move_group_name_);
33}
34
36{
37 is_spinning_ = false;
38 if (spin_thread_.joinable())
39 {
40 spin_thread_.join();
41 }
42}
43
45{
46 is_spinning_ = true;
47 spin_thread_ = std::thread(&MoveGroupFixture::spinNode, this);
48
50 db_->setParams(":memory:", 1);
51 ASSERT_TRUE(db_->connect());
52}
53
55{
56 db_.reset();
57 is_spinning_ = false;
58 spin_thread_.join();
59}
60
61void MoveGroupFixture::spinNode()
62{
63 while (is_spinning_ && rclcpp::ok())
64 {
65 rclcpp::spin_some(node_);
66 }
67}
void TearDown() override
rclcpp::Node::SharedPtr node_
warehouse_ros::DatabaseConnection::Ptr db_
std::shared_ptr< moveit::planning_interface::MoveGroupInterface > move_group_
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.