moveit2
The MoveIt Motion Planning Framework for ROS 2.
warehouse_services.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: Dan Greenwald */
36 
38 #include <moveit_msgs/srv/save_robot_state_to_warehouse.hpp>
39 #include <moveit_msgs/srv/list_robot_states_in_warehouse.hpp>
40 #include <moveit_msgs/srv/get_robot_state_from_warehouse.hpp>
41 #include <moveit_msgs/srv/check_if_robot_state_exists_in_warehouse.hpp>
42 #include <moveit_msgs/srv/delete_robot_state_from_warehouse.hpp>
43 #include <moveit_msgs/srv/rename_robot_state_in_warehouse.hpp>
44 #include <rclcpp/executors.hpp>
45 #include <rclcpp/logger.hpp>
46 #include <rclcpp/logging.hpp>
47 #include <rclcpp/node.hpp>
48 #include <rclcpp/node_options.hpp>
49 #include <rclcpp/parameter_value.hpp>
50 #include <rclcpp/utilities.hpp>
51 
52 static const std::string ROBOT_DESCRIPTION = "robot_description";
53 
54 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.warehouse_services");
55 
56 bool storeState(const std::shared_ptr<moveit_msgs::srv::SaveRobotStateToWarehouse::Request>& request,
57  const std::shared_ptr<moveit_msgs::srv::SaveRobotStateToWarehouse::Response>& response,
59 {
60  if (request->name.empty())
61  {
62  RCLCPP_ERROR(LOGGER, "You must specify a name to store a state");
63  return (response->success = false);
64  }
65  rs.addRobotState(request->state, request->name, request->robot);
66  return (response->success = true);
67 }
68 
69 bool listStates(const std::shared_ptr<moveit_msgs::srv::ListRobotStatesInWarehouse::Request>& request,
70  const std::shared_ptr<moveit_msgs::srv::ListRobotStatesInWarehouse::Response>& response,
72 {
73  if (request->regex.empty())
74  {
75  rs.getKnownRobotStates(response->states, request->robot);
76  }
77  else
78  {
79  rs.getKnownRobotStates(request->regex, response->states, request->robot);
80  }
81  return true;
82 }
83 
84 bool hasState(const std::shared_ptr<moveit_msgs::srv::CheckIfRobotStateExistsInWarehouse::Request>& request,
85  const std::shared_ptr<moveit_msgs::srv::CheckIfRobotStateExistsInWarehouse::Response>& response,
87 {
88  response->exists = rs.hasRobotState(request->name, request->robot);
89  return true;
90 }
91 
92 bool getState(const std::shared_ptr<moveit_msgs::srv::GetRobotStateFromWarehouse::Request>& request,
93  const std::shared_ptr<moveit_msgs::srv::GetRobotStateFromWarehouse::Response>& response,
95 {
96  if (!rs.hasRobotState(request->name, request->robot))
97  {
98  RCLCPP_ERROR_STREAM(LOGGER, "No state called '" << request->name << "' for robot '" << request->robot << "'.");
99  moveit_msgs::msg::RobotState dummy;
100  response->state = dummy;
101  return false;
102  }
104  rs.getRobotState(state_buffer, request->name, request->robot);
105  response->state = static_cast<const moveit_msgs::msg::RobotState&>(*state_buffer);
106  return true;
107 }
108 
109 bool renameState(const std::shared_ptr<moveit_msgs::srv::RenameRobotStateInWarehouse::Request>& request,
110  const std::shared_ptr<moveit_msgs::srv::RenameRobotStateInWarehouse::Response>& /*response*/,
112 {
113  if (!rs.hasRobotState(request->old_name, request->robot))
114  {
115  RCLCPP_ERROR_STREAM(LOGGER, "No state called '" << request->old_name << "' for robot '" << request->robot << "'.");
116  return false;
117  }
118  rs.renameRobotState(request->old_name, request->new_name, request->robot);
119  return true;
120 }
121 
122 bool deleteState(const std::shared_ptr<moveit_msgs::srv::DeleteRobotStateFromWarehouse::Request>& request,
123  const std::shared_ptr<moveit_msgs::srv::DeleteRobotStateFromWarehouse::Response>& /*response*/,
125 {
126  if (!rs.hasRobotState(request->name, request->robot))
127  {
128  RCLCPP_ERROR_STREAM(LOGGER, "No state called '" << request->name << "' for robot '" << request->robot << "'.");
129  return false;
130  }
131  rs.removeRobotState(request->name, request->robot);
132  return true;
133 }
134 
135 int main(int argc, char** argv)
136 {
137  rclcpp::init(argc, argv);
138  rclcpp::NodeOptions node_options;
139  node_options.allow_undeclared_parameters(true);
140  node_options.automatically_declare_parameters_from_overrides(true);
141  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("moveit_warehouse_services", node_options);
142 
143  std::string host;
144 
145  int port;
146  double connection_timeout;
147  int connection_retries;
148 
149  node->get_parameter_or(std::string("warehouse_host"), host, std::string("localhost"));
150  node->get_parameter_or(std::string("warehouse_port"), port, 33829);
151  node->get_parameter_or(std::string("warehouse_db_connection_timeout"), connection_timeout, 5.0);
152  node->get_parameter_or(std::string("warehouse_db_connection_retries"), connection_retries, 5);
153 
154  warehouse_ros::DatabaseConnection::Ptr conn;
155 
156  try
157  {
158  conn = moveit_warehouse::loadDatabase(node);
159  conn->setParams(host, port, connection_timeout);
160 
161  RCLCPP_INFO(LOGGER, "Connecting to warehouse on %s:%d", host.c_str(), port);
162  int tries = 0;
163  while (!conn->connect())
164  {
165  ++tries;
166  RCLCPP_WARN(LOGGER, "Failed to connect to DB on %s:%d (try %d/%d).", host.c_str(), port, tries,
167  connection_retries);
168  if (tries == connection_retries)
169  {
170  RCLCPP_FATAL(LOGGER, "Failed to connect too many times, giving up");
171  return 1;
172  }
173  }
174  }
175  catch (std::exception& ex)
176  {
177  RCLCPP_ERROR(LOGGER, "%s", ex.what());
178  return 1;
179  }
180 
182 
183  std::vector<std::string> names;
184  rs.getKnownRobotStates(names);
185  if (names.empty())
186  RCLCPP_INFO(LOGGER, "There are no previously stored robot states");
187  else
188  {
189  RCLCPP_INFO(LOGGER, "Previously stored robot states:");
190  for (const std::string& name : names)
191  RCLCPP_INFO(LOGGER, " * %s", name.c_str());
192  }
193 
194  auto save_cb = [&](const std::shared_ptr<moveit_msgs::srv::SaveRobotStateToWarehouse::Request>& request,
195  const std::shared_ptr<moveit_msgs::srv::SaveRobotStateToWarehouse::Response>& response) -> bool {
196  return storeState(request, response, rs);
197  };
198 
199  auto list_cb = [&](const std::shared_ptr<moveit_msgs::srv::ListRobotStatesInWarehouse::Request>& request,
200  const std::shared_ptr<moveit_msgs::srv::ListRobotStatesInWarehouse::Response>& response) -> bool {
201  return listStates(request, response, rs);
202  };
203 
204  auto get_cb = [&](const std::shared_ptr<moveit_msgs::srv::GetRobotStateFromWarehouse::Request>& request,
205  const std::shared_ptr<moveit_msgs::srv::GetRobotStateFromWarehouse::Response>& response) -> bool {
206  return getState(request, response, rs);
207  };
208 
209  auto has_cb =
210  [&](const std::shared_ptr<moveit_msgs::srv::CheckIfRobotStateExistsInWarehouse::Request>& request,
211  const std::shared_ptr<moveit_msgs::srv::CheckIfRobotStateExistsInWarehouse::Response>& response) -> bool {
212  return hasState(request, response, rs);
213  };
214 
215  auto rename_cb =
216  [&](const std::shared_ptr<moveit_msgs::srv::RenameRobotStateInWarehouse::Request>& request,
217  const std::shared_ptr<moveit_msgs::srv::RenameRobotStateInWarehouse::Response>& response) -> bool {
218  return renameState(request, response, rs);
219  };
220 
221  auto delete_cb =
222  [&](const std::shared_ptr<moveit_msgs::srv::DeleteRobotStateFromWarehouse::Request>& request,
223  const std::shared_ptr<moveit_msgs::srv::DeleteRobotStateFromWarehouse::Response>& response) -> bool {
224  return deleteState(request, response, rs);
225  };
226 
227  auto save_state_server =
228  node->create_service<moveit_msgs::srv::SaveRobotStateToWarehouse>("save_robot_state", save_cb);
229  auto list_states_server =
230  node->create_service<moveit_msgs::srv::ListRobotStatesInWarehouse>("list_robot_states", list_cb);
231  auto get_state_server = node->create_service<moveit_msgs::srv::GetRobotStateFromWarehouse>("get_robot_state", get_cb);
232  auto has_state_server =
233  node->create_service<moveit_msgs::srv::CheckIfRobotStateExistsInWarehouse>("has_robot_state", has_cb);
234  auto rename_state_server =
235  node->create_service<moveit_msgs::srv::RenameRobotStateInWarehouse>("rename_robot_state", rename_cb);
236  auto delete_state_server =
237  node->create_service<moveit_msgs::srv::DeleteRobotStateFromWarehouse>("delete_robot_state", delete_cb);
238 
239  rclcpp::spin(node);
240  return 0;
241 }
void renameRobotState(const std::string &old_name, const std::string &new_name, const std::string &robot="")
bool hasRobotState(const std::string &name, const std::string &robot="") const
void getKnownRobotStates(std::vector< std::string > &names, const std::string &robot="") const
bool getRobotState(RobotStateWithMetadata &msg_m, const std::string &name, const std::string &robot="") const
Get the constraints named name. Return false on failure.
void removeRobotState(const std::string &name, const std::string &robot="")
void addRobotState(const moveit_msgs::msg::RobotState &msg, const std::string &name, const std::string &robot="")
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotState >::ConstPtr RobotStateWithMetadata
Definition: state_storage.h:47
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31
bool storeState(const std::shared_ptr< moveit_msgs::srv::SaveRobotStateToWarehouse::Request > &request, const std::shared_ptr< moveit_msgs::srv::SaveRobotStateToWarehouse::Response > &response, moveit_warehouse::RobotStateStorage &rs)
int main(int argc, char **argv)
bool hasState(const std::shared_ptr< moveit_msgs::srv::CheckIfRobotStateExistsInWarehouse::Request > &request, const std::shared_ptr< moveit_msgs::srv::CheckIfRobotStateExistsInWarehouse::Response > &response, moveit_warehouse::RobotStateStorage &rs)
bool listStates(const std::shared_ptr< moveit_msgs::srv::ListRobotStatesInWarehouse::Request > &request, const std::shared_ptr< moveit_msgs::srv::ListRobotStatesInWarehouse::Response > &response, moveit_warehouse::RobotStateStorage &rs)
bool getState(const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Request > &request, const std::shared_ptr< moveit_msgs::srv::GetRobotStateFromWarehouse::Response > &response, moveit_warehouse::RobotStateStorage &rs)
bool renameState(const std::shared_ptr< moveit_msgs::srv::RenameRobotStateInWarehouse::Request > &request, const std::shared_ptr< moveit_msgs::srv::RenameRobotStateInWarehouse::Response > &, moveit_warehouse::RobotStateStorage &rs)
bool deleteState(const std::shared_ptr< moveit_msgs::srv::DeleteRobotStateFromWarehouse::Request > &request, const std::shared_ptr< moveit_msgs::srv::DeleteRobotStateFromWarehouse::Response > &, moveit_warehouse::RobotStateStorage &rs)