41 #include <boost/algorithm/string/join.hpp>
42 #include <boost/program_options/cmdline.hpp>
43 #include <boost/program_options/options_description.hpp>
44 #include <boost/program_options/parsers.hpp>
45 #include <boost/program_options/variables_map.hpp>
46 #include <tf2_ros/transform_listener.h>
47 #include <rclcpp/executors.hpp>
48 #include <rclcpp/experimental/buffers/intra_process_buffer.hpp>
49 #include <rclcpp/logger.hpp>
50 #include <rclcpp/logging.hpp>
51 #include <rclcpp/node.hpp>
52 #include <rclcpp/node_options.hpp>
53 #include <rclcpp/qos_event.hpp>
54 #include <rclcpp/subscription.hpp>
55 #include <rclcpp/utilities.hpp>
57 static const std::string ROBOT_DESCRIPTION =
"robot_description";
59 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.ros.warehouse.save_to_warehouse");
63 RCLCPP_INFO(LOGGER,
"Received an update to the planning scene...");
69 moveit_msgs::msg::PlanningScene psmsg;
74 RCLCPP_INFO(LOGGER,
"Scene '%s' was previously added. Not adding again.",
78 RCLCPP_INFO(LOGGER,
"Scene name is empty. Not saving.");
86 RCLCPP_INFO(LOGGER,
"Scene name is empty. Not saving planning request.");
96 RCLCPP_INFO(LOGGER,
"No name specified for constraints. Not saving.");
102 RCLCPP_INFO(LOGGER,
"Replacing constraints '%s'", msg.name.c_str());
108 RCLCPP_INFO(LOGGER,
"Adding constraints '%s'", msg.name.c_str());
115 std::vector<std::string> names;
117 std::set<std::string> names_set(names.begin(), names.end());
118 std::size_t n = names.size();
119 while (names_set.find(
"S" + std::to_string(n)) != names_set.end())
121 std::string
name =
"S" + std::to_string(n);
122 RCLCPP_INFO(LOGGER,
"Adding robot state '%s'",
name.c_str());
126 int main(
int argc,
char** argv)
128 rclcpp::init(argc, argv);
129 rclcpp::NodeOptions node_options;
130 node_options.allow_undeclared_parameters(
true);
131 node_options.automatically_declare_parameters_from_overrides(
true);
132 rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(
"save_to_warehouse", node_options);
134 boost::program_options::options_description desc;
135 desc.add_options()(
"help",
"Show help message")(
"host", boost::program_options::value<std::string>(),
137 "DB.")(
"port", boost::program_options::value<std::size_t>(),
140 boost::program_options::variables_map vm;
141 boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
142 boost::program_options::notify(vm);
144 if (vm.count(
"help"))
146 std::cout << desc <<
'\n';
151 if (vm.count(
"host") && vm.count(
"port"))
152 conn->setParams(vm[
"host"].as<std::string>(), vm[
"port"].as<std::size_t>());
153 if (!conn->connect())
159 RCLCPP_ERROR(LOGGER,
"Unable to initialize PlanningSceneMonitor");
168 std::vector<std::string> names;
171 RCLCPP_INFO(LOGGER,
"There are no previously stored scenes");
174 RCLCPP_INFO(LOGGER,
"Previously stored scenes:");
175 for (
const std::string&
name : names)
176 RCLCPP_INFO(LOGGER,
" * %s",
name.c_str());
180 RCLCPP_INFO(LOGGER,
"There are no previously stored constraints");
183 RCLCPP_INFO(LOGGER,
"Previously stored constraints:");
184 for (
const std::string&
name : names)
185 RCLCPP_INFO(LOGGER,
" * %s",
name.c_str());
189 RCLCPP_INFO(LOGGER,
"There are no previously stored robot states");
192 RCLCPP_INFO(LOGGER,
"Previously stored robot states:");
193 for (
const std::string&
name : names)
194 RCLCPP_INFO(LOGGER,
" * %s",
name.c_str());
200 "motion_plan_request", rclcpp::SystemDefaultsQoS(),
202 auto constr_sub = node->create_subscription<moveit_msgs::msg::Constraints>(
203 "constraints", rclcpp::SystemDefaultsQoS(),
204 [&](
const moveit_msgs::msg::Constraints& msg) {
onConstraints(msg, cs); });
205 auto state_sub = node->create_subscription<moveit_msgs::msg::RobotState>(
206 "robot_state", rclcpp::SystemDefaultsQoS(),
207 [&](
const moveit_msgs::msg::RobotState& msg) {
onRobotState(msg, rs); });
209 std::vector<std::string> topics;
211 RCLCPP_INFO_STREAM(LOGGER,
"Listening for scene updates on topics " << boost::algorithm::join(topics,
", "));
212 RCLCPP_INFO_STREAM(LOGGER,
"Listening for planning requests on topic " << mplan_req_sub->get_topic_name());
213 RCLCPP_INFO_STREAM(LOGGER,
"Listening for named constraints on topic " << constr_sub->get_topic_name());
214 RCLCPP_INFO_STREAM(LOGGER,
"Listening for states on topic " << state_sub->get_topic_name());
void removeConstraints(const std::string &name, const std::string &robot="", const std::string &group="")
bool hasConstraints(const std::string &name, const std::string &robot="", const std::string &group="") const
void getKnownConstraints(std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
void addConstraints(const moveit_msgs::msg::Constraints &msg, const std::string &robot="", const std::string &group="")
void addPlanningQuery(const moveit_msgs::msg::MotionPlanRequest &planning_query, const std::string &scene_name, const std::string &query_name="")
void addPlanningScene(const moveit_msgs::msg::PlanningScene &scene)
void getPlanningSceneNames(std::vector< std::string > &names) const
bool hasPlanningScene(const std::string &name) const
void getKnownRobotStates(std::vector< std::string > &names, const std::string &robot="") const
void addRobotState(const moveit_msgs::msg::RobotState &msg, const std::string &name, const std::string &robot="")
PlanningSceneMonitor Subscribes to the topic planning_scene.
const planning_scene::PlanningScenePtr & getPlanningScene()
Avoid this function! Returns an unsafe pointer to the current planning scene.
void addUpdateCallback(const std::function< void(SceneUpdateType)> &fn)
Add a function to be called when an update to the scene is received.
void getMonitoredTopics(std::vector< std::string > &topics) const
Get the topic names that the monitor is listening to.
void startSceneMonitor(const std::string &scene_topic=DEFAULT_PLANNING_SCENE_TOPIC)
Start the scene monitor (ROS topic-based)
void startWorldGeometryMonitor(const std::string &collision_objects_topic=DEFAULT_COLLISION_OBJECT_TOPIC, const std::string &planning_scene_world_topic=DEFAULT_PLANNING_SCENE_WORLD_TOPIC, const bool load_octomap_monitor=true)
Start the OccupancyMapMonitor and listening for:
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
const rclcpp::Logger LOGGER
void onRobotState(const moveit_msgs::msg::RobotState &msg, moveit_warehouse::RobotStateStorage &rs)
int main(int argc, char **argv)
void onSceneUpdate(planning_scene_monitor::PlanningSceneMonitor &psm, moveit_warehouse::PlanningSceneStorage &pss)
void onMotionPlanRequest(const moveit_msgs::msg::MotionPlanRequest &req, planning_scene_monitor::PlanningSceneMonitor &psm, moveit_warehouse::PlanningSceneStorage &pss)
void onConstraints(const moveit_msgs::msg::Constraints &msg, moveit_warehouse::ConstraintsStorage &cs)