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>
52 static const std::string ROBOT_DESCRIPTION =
"robot_description";
54 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.ros.warehouse.warehouse_services");
56 bool storeState(
const std::shared_ptr<moveit_msgs::srv::SaveRobotStateToWarehouse::Request>& request,
57 const std::shared_ptr<moveit_msgs::srv::SaveRobotStateToWarehouse::Response>& response,
60 if (request->name.empty())
62 RCLCPP_ERROR(LOGGER,
"You must specify a name to store a state");
63 return (response->success =
false);
65 rs.
addRobotState(request->state, request->name, request->robot);
66 return (response->success =
true);
69 bool listStates(
const std::shared_ptr<moveit_msgs::srv::ListRobotStatesInWarehouse::Request>& request,
70 const std::shared_ptr<moveit_msgs::srv::ListRobotStatesInWarehouse::Response>& response,
73 if (request->regex.empty())
84 bool hasState(
const std::shared_ptr<moveit_msgs::srv::CheckIfRobotStateExistsInWarehouse::Request>& request,
85 const std::shared_ptr<moveit_msgs::srv::CheckIfRobotStateExistsInWarehouse::Response>& response,
88 response->exists = rs.
hasRobotState(request->name, request->robot);
92 bool getState(
const std::shared_ptr<moveit_msgs::srv::GetRobotStateFromWarehouse::Request>& request,
93 const std::shared_ptr<moveit_msgs::srv::GetRobotStateFromWarehouse::Response>& response,
98 RCLCPP_ERROR_STREAM(LOGGER,
"No state called '" << request->name <<
"' for robot '" << request->robot <<
"'.");
99 moveit_msgs::msg::RobotState dummy;
100 response->state = dummy;
104 rs.
getRobotState(state_buffer, request->name, request->robot);
105 response->state =
static_cast<const moveit_msgs::msg::RobotState&
>(*state_buffer);
109 bool renameState(
const std::shared_ptr<moveit_msgs::srv::RenameRobotStateInWarehouse::Request>& request,
110 const std::shared_ptr<moveit_msgs::srv::RenameRobotStateInWarehouse::Response>& ,
115 RCLCPP_ERROR_STREAM(LOGGER,
"No state called '" << request->old_name <<
"' for robot '" << request->robot <<
"'.");
122 bool deleteState(
const std::shared_ptr<moveit_msgs::srv::DeleteRobotStateFromWarehouse::Request>& request,
123 const std::shared_ptr<moveit_msgs::srv::DeleteRobotStateFromWarehouse::Response>& ,
128 RCLCPP_ERROR_STREAM(LOGGER,
"No state called '" << request->name <<
"' for robot '" << request->robot <<
"'.");
135 int main(
int argc,
char** argv)
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);
146 double connection_timeout;
147 int connection_retries;
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);
154 warehouse_ros::DatabaseConnection::Ptr conn;
159 conn->setParams(host, port, connection_timeout);
161 RCLCPP_INFO(LOGGER,
"Connecting to warehouse on %s:%d", host.c_str(), port);
163 while (!conn->connect())
166 RCLCPP_WARN(LOGGER,
"Failed to connect to DB on %s:%d (try %d/%d).", host.c_str(), port, tries,
168 if (tries == connection_retries)
170 RCLCPP_FATAL(LOGGER,
"Failed to connect too many times, giving up");
175 catch (std::exception& ex)
177 RCLCPP_ERROR(LOGGER,
"%s", ex.what());
183 std::vector<std::string> names;
186 RCLCPP_INFO(LOGGER,
"There are no previously stored robot states");
189 RCLCPP_INFO(LOGGER,
"Previously stored robot states:");
190 for (
const std::string&
name : names)
191 RCLCPP_INFO(LOGGER,
" * %s",
name.c_str());
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 {
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 {
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);
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);
216 [&](
const std::shared_ptr<moveit_msgs::srv::RenameRobotStateInWarehouse::Request>& request,
217 const std::shared_ptr<moveit_msgs::srv::RenameRobotStateInWarehouse::Response>& response) ->
bool {
222 [&](
const std::shared_ptr<moveit_msgs::srv::DeleteRobotStateFromWarehouse::Request>& request,
223 const std::shared_ptr<moveit_msgs::srv::DeleteRobotStateFromWarehouse::Response>& response) ->
bool {
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);
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
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
const rclcpp::Logger LOGGER
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)