41 #include <boost/program_options/cmdline.hpp>
42 #include <boost/program_options/options_description.hpp>
43 #include <boost/program_options/parsers.hpp>
44 #include <boost/program_options/variables_map.hpp>
45 #include <rclcpp/executors/static_single_threaded_executor.hpp>
46 #include <rclcpp/logger.hpp>
47 #include <rclcpp/logging.hpp>
48 #include <rclcpp/node.hpp>
49 #include <rclcpp/node_options.hpp>
50 #include <rclcpp/publisher.hpp>
51 #include <rclcpp/version.h>
52 #if RCLCPP_VERSION_GTE(20, 0, 0)
53 #include <rclcpp/event_handler.hpp>
55 #include <rclcpp/qos_event.hpp>
57 #include <rclcpp/rate.hpp>
58 #include <rclcpp/utilities.hpp>
60 static const std::string PLANNING_SCENE_TOPIC =
"planning_scene";
61 static const std::string PLANNING_REQUEST_TOPIC =
"motion_plan_request";
62 static const std::string PLANNING_RESULTS_TOPIC =
"motion_plan_results";
64 static const std::string CONSTRAINTS_TOPIC =
"constraints";
66 static const std::string STATES_TOPIC =
"robot_states";
68 using namespace std::chrono_literals;
70 int main(
int argc,
char** argv)
72 rclcpp::init(argc, argv);
73 rclcpp::NodeOptions node_options;
74 node_options.allow_undeclared_parameters(
true);
75 node_options.automatically_declare_parameters_from_overrides(
true);
76 rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(
"publish_warehouse_data", node_options);
83 boost::program_options::options_description desc;
84 desc.add_options()(
"help",
"Show help message")(
"host", boost::program_options::value<std::string>(),
86 "DB.")(
"port", boost::program_options::value<std::size_t>(),
88 "scene", boost::program_options::value<std::string>(),
"Name of scene to publish.")(
89 "planning_requests",
"Also publish the planning requests that correspond to the scene")(
90 "planning_results",
"Also publish the planning results that correspond to the scene")(
91 "constraint", boost::program_options::value<std::string>(),
"Name of constraint to publish.")(
92 "state", boost::program_options::value<std::string>(),
93 "Name of the robot state to publish.")(
"delay", boost::program_options::value<double>()->default_value(delay),
94 "Time to wait in between publishing messages (s)");
96 boost::program_options::variables_map vm;
97 boost::program_options::store(boost::program_options::parse_command_line(argc, argv, desc), vm);
98 boost::program_options::notify(vm);
100 if (vm.count(
"help") || (!vm.count(
"scene") && !vm.count(
"constraint") && !vm.count(
"state")))
102 std::cout << desc <<
'\n';
107 delay = vm[
"delay"].as<
double>();
111 std::cout << desc <<
'\n';
116 if (vm.count(
"host") && vm.count(
"port"))
117 conn->setParams(vm[
"host"].as<std::string>(), vm[
"port"].as<std::size_t>());
118 if (!conn->connect())
121 rclcpp::executors::StaticSingleThreadedExecutor executor;
122 executor.add_node(node);
124 rclcpp::Rate rate(
static_cast<int64_t
>(delay) * 1000ms);
127 if (vm.count(
"scene"))
129 auto pub_scene = node->create_publisher<moveit_msgs::msg::PlanningScene>(PLANNING_SCENE_TOPIC, 10);
130 bool req = vm.count(
"planning_requests");
131 bool res = vm.count(
"planning_results");
134 executor.spin_once(0ns);
136 std::vector<std::string> scene_names;
139 for (
const std::string& scene_name : scene_names)
144 RCLCPP_INFO(node->get_logger(),
"Publishing scene '%s'",
146 pub_scene->publish(
static_cast<const moveit_msgs::msg::PlanningScene&
>(*pswm));
147 executor.spin_once(0ns);
153 auto pub_res = node->create_publisher<moveit_msgs::msg::RobotTrajectory>(PLANNING_RESULTS_TOPIC, 100);
154 std::vector<moveit_warehouse::MotionPlanRequestWithMetadata> planning_queries;
155 std::vector<std::string> query_names;
157 RCLCPP_INFO(node->get_logger(),
"There are %d planning queries associated to the scene",
158 static_cast<int>(planning_queries.size()));
159 rclcpp::sleep_for(500ms);
160 for (std::size_t i = 0; i < planning_queries.size(); ++i)
164 RCLCPP_INFO(node->get_logger(),
"Publishing query '%s'", query_names[i].c_str());
166 executor.spin_once(0ns);
170 std::vector<moveit_warehouse::RobotTrajectoryWithMetadata> planning_results;
174 pub_res->publish(
static_cast<const moveit_msgs::msg::RobotTrajectory&
>(*planning_result));
175 executor.spin_once(0ns);
186 if (vm.count(
"constraint"))
189 auto pub_constr = node->create_publisher<moveit_msgs::msg::Constraints>(CONSTRAINTS_TOPIC, 100);
190 std::vector<std::string> cnames;
193 for (
const std::string& cname : cnames)
198 RCLCPP_INFO(node->get_logger(),
"Publishing constraints '%s'",
200 pub_constr->publish(
static_cast<const moveit_msgs::msg::Constraints&
>(*cwm));
201 executor.spin_once(0ns);
208 if (vm.count(
"state"))
211 auto pub_state = node->create_publisher<moveit_msgs::msg::RobotState>(STATES_TOPIC, 100);
212 std::vector<std::string> rnames;
215 for (
const std::string& rname : rnames)
220 RCLCPP_INFO(node->get_logger(),
"Publishing state '%s'",
222 pub_state->publish(
static_cast<const moveit_msgs::msg::RobotState&
>(*rswm));
223 executor.spin_once(0ns);
229 rclcpp::sleep_for(1s);
230 RCLCPP_INFO(node->get_logger(),
"Done.");
int main(int argc, char **argv)
bool getConstraints(ConstraintsWithMetadata &msg_m, const std::string &name, const std::string &robot="", const std::string &group="") const
Get the constraints named name. Return false on failure.
void getKnownConstraints(std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
static const std::string CONSTRAINTS_ID_NAME
static const std::string PLANNING_SCENE_ID_NAME
void getPlanningResults(std::vector< RobotTrajectoryWithMetadata > &planning_results, const std::string &scene_name, const moveit_msgs::msg::MotionPlanRequest &planning_query) const
void getPlanningQueries(std::vector< MotionPlanRequestWithMetadata > &planning_queries, const std::string &scene_name) const
void getPlanningSceneNames(std::vector< std::string > &names) const
bool getPlanningScene(PlanningSceneWithMetadata &scene_m, const std::string &scene_name) const
Get the latest planning scene named scene_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.
static const std::string STATE_NAME
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotState >::ConstPtr RobotStateWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr RobotTrajectoryWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningScene >::ConstPtr PlanningSceneWithMetadata
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::Constraints >::ConstPtr ConstraintsWithMetadata
void setNodeLoggerName(const std::string &name)
Call once after creating a node to initialize logging namespaces.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest