moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
warehouse_connector.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2012, Willow Garage, Inc.
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 Willow Garage 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: E. Gil Jones */
36
37#include <sys/types.h>
38#include <signal.h>
40#include <rclcpp/logger.hpp>
41#include <rclcpp/logging.hpp>
42#include <rclcpp/utilities.hpp>
44
45namespace
46{
47rclcpp::Logger getLogger()
48{
49 return moveit::getLogger("moveit.ros.warehouse_connector");
50}
51} // namespace
52
53#ifdef _WIN32
54void kill(int, int)
55{
56 RCLCPP_ERROR(getLogger(), "Warehouse connector not supported on Windows");
57} // Should never be called
58int fork()
59{
60 RCLCPP_ERROR(getLogger(), "Warehouse connector not supported on Windows");
61 return -1;
62}
63#else
64#include <unistd.h>
65#endif
66
67namespace moveit_warehouse
68{
69WarehouseConnector::WarehouseConnector(const std::string& dbexec) : dbexec_(dbexec), child_pid_(0)
70{
71}
72
74{
75 if (child_pid_ != 0)
76 kill(child_pid_, SIGTERM);
77}
78
79bool WarehouseConnector::connectToDatabase(const std::string& dirname)
80{
81 if (child_pid_ != 0)
82 kill(child_pid_, SIGTERM);
83
84 child_pid_ = fork();
85 if (child_pid_ == -1)
86 {
87 RCLCPP_ERROR(getLogger(), "Error forking process.");
88 child_pid_ = 0;
89 return false;
90 }
91
92 if (child_pid_ == 0)
93 {
94 std::size_t exec_file_pos = dbexec_.find_last_of("/\\");
95 if (exec_file_pos != std::string::npos)
96 {
97 char** argv = new char*[4];
98 std::size_t exec_length = 1 + dbexec_.length() - exec_file_pos;
99 argv[0] = new char[1 + exec_length];
100 snprintf(argv[0], exec_length, "%s", dbexec_.substr(exec_file_pos + 1).c_str());
101
102 argv[1] = new char[16];
103 snprintf(argv[1], 15, "--dbpath");
104
105 argv[2] = new char[1024];
106 snprintf(argv[2], 1023, "%s", dirname.c_str());
107
108 argv[3] = nullptr;
109
110 int code = execv(dbexec_.c_str(), argv);
111 delete[] argv[0];
112 delete[] argv[1];
113 delete[] argv[2];
114 delete[] argv;
115 RCLCPP_ERROR_STREAM(getLogger(),
116 "execv() returned " << code << ", errno=" << errno << " string errno = " << strerror(errno));
117 }
118 return false;
119 }
120 else
121 {
122 // sleep so mongod has time to come up
123 using namespace std::chrono_literals;
124 rclcpp::sleep_for(1s);
125 }
126 return true;
127}
128} // namespace moveit_warehouse
WarehouseConnector(const std::string &dbexec)
bool connectToDatabase(const std::string &db_dirname)
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79