moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
state_storage.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: Ioan Sucan */
36
39
40#include <utility>
41
42const std::string moveit_warehouse::RobotStateStorage::DATABASE_NAME = "moveit_robot_states";
43
44const std::string moveit_warehouse::RobotStateStorage::STATE_NAME = "state_id";
45const std::string moveit_warehouse::RobotStateStorage::ROBOT_NAME = "robot_id";
46
47using warehouse_ros::Metadata;
48using warehouse_ros::Query;
49
50moveit_warehouse::RobotStateStorage::RobotStateStorage(warehouse_ros::DatabaseConnection::Ptr conn)
51 : MoveItMessageStorage(std::move(conn)), logger_(moveit::getLogger("moveit.ros.warehouse_robot_state_storage"))
52{
53 createCollections();
54}
55
56void moveit_warehouse::RobotStateStorage::createCollections()
57{
58 state_collection_ = conn_->openCollectionPtr<moveit_msgs::msg::RobotState>(DATABASE_NAME, "robot_states");
59}
60
62{
63 state_collection_.reset();
64 conn_->dropDatabase(DATABASE_NAME);
65 createCollections();
66}
67
68void moveit_warehouse::RobotStateStorage::addRobotState(const moveit_msgs::msg::RobotState& msg,
69 const std::string& name, const std::string& robot)
70{
71 bool replace = false;
72 if (hasRobotState(name, robot))
73 {
74 removeRobotState(name, robot);
75 replace = true;
76 }
77 Metadata::Ptr metadata = state_collection_->createMetadata();
78 metadata->append(STATE_NAME, name);
79 metadata->append(ROBOT_NAME, robot);
80 state_collection_->insert(msg, metadata);
81 RCLCPP_DEBUG(logger_, "%s robot state '%s'", replace ? "Replaced" : "Added", name.c_str());
82}
83
84bool moveit_warehouse::RobotStateStorage::hasRobotState(const std::string& name, const std::string& robot) const
85{
86 Query::Ptr q = state_collection_->createQuery();
87 q->append(STATE_NAME, name);
88 if (!robot.empty())
89 q->append(ROBOT_NAME, robot);
90 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q, true);
91 return !constr.empty();
92}
93
94void moveit_warehouse::RobotStateStorage::getKnownRobotStates(const std::string& regex, std::vector<std::string>& names,
95 const std::string& robot) const
96{
97 getKnownRobotStates(names, robot);
98 filterNames(regex, names);
99}
100
102 const std::string& robot) const
103{
104 names.clear();
105 Query::Ptr q = state_collection_->createQuery();
106 if (!robot.empty())
107 q->append(ROBOT_NAME, robot);
108 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q, true, STATE_NAME, true);
109 for (RobotStateWithMetadata& state : constr)
110 {
111 if (state->lookupField(STATE_NAME))
112 names.push_back(state->lookupString(STATE_NAME));
113 }
114}
115
117 const std::string& robot) const
118{
119 Query::Ptr q = state_collection_->createQuery();
120 q->append(STATE_NAME, name);
121 if (!robot.empty())
122 q->append(ROBOT_NAME, robot);
123 std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q, false);
124 if (constr.empty())
125 {
126 return false;
127 }
128 else
129 {
130 msg_m = constr.front();
131 return true;
132 }
133}
134
135void moveit_warehouse::RobotStateStorage::renameRobotState(const std::string& old_name, const std::string& new_name,
136 const std::string& robot)
137{
138 Query::Ptr q = state_collection_->createQuery();
139 q->append(STATE_NAME, old_name);
140 if (!robot.empty())
141 q->append(ROBOT_NAME, robot);
142 Metadata::Ptr m = state_collection_->createMetadata();
143 m->append(STATE_NAME, new_name);
144 state_collection_->modifyMetadata(q, m);
145 RCLCPP_DEBUG(logger_, "Renamed robot state from '%s' to '%s'", old_name.c_str(), new_name.c_str());
146}
147
148void moveit_warehouse::RobotStateStorage::removeRobotState(const std::string& name, const std::string& robot)
149{
150 Query::Ptr q = state_collection_->createQuery();
151 q->append(STATE_NAME, name);
152 if (!robot.empty())
153 q->append(ROBOT_NAME, robot);
154 unsigned int rem = state_collection_->removeMessages(q);
155 RCLCPP_DEBUG(logger_, "Removed %u RobotState messages (named '%s')", rem, name.c_str());
156}
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
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
static const std::string DATABASE_NAME
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="")
static const std::string STATE_NAME
RobotStateStorage(warehouse_ros::DatabaseConnection::Ptr conn)
void addRobotState(const moveit_msgs::msg::RobotState &msg, const std::string &name, const std::string &robot="")
static const std::string ROBOT_NAME
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotState >::ConstPtr RobotStateWithMetadata
Main namespace for MoveIt.
Definition exceptions.h:43
const std::string ROBOT_NAME