15 #include "nav2_rviz_plugins/route_tool.hpp"
16 #include <QDesktopServices>
19 #include <sys/types.h>
20 #include <QFileDialog>
21 #include "rviz_common/display_context.hpp"
24 namespace nav2_rviz_plugins
27 : rviz_common::Panel(parent),
28 ui_(std::make_unique<Ui::route_tool>())
32 node_ = std::make_shared<nav2_util::LifecycleNode>(
"route_tool_node",
"", rclcpp::NodeOptions());
34 graph_vis_publisher_ = node_->create_publisher<visualization_msgs::msg::MarkerArray>(
35 "route_graph", rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
37 tf_ = std::make_shared<tf2_ros::Buffer>(node_->get_clock());
38 graph_loader_ = std::make_shared<nav2_route::GraphLoader>(node_, tf_,
"map");
39 graph_saver_ = std::make_shared<nav2_route::GraphSaver>(node_, tf_,
"map");
40 ui_->add_node_button->setChecked(
true);
41 ui_->edit_node_button->setChecked(
true);
42 ui_->remove_node_button->setChecked(
true);
48 void RouteTool::onInitialize(
void)
50 auto ros_node_abstraction = getDisplayContext()->getRosNodeAbstraction().lock();
51 if (!ros_node_abstraction) {
53 node_->get_logger(),
"Unable to get ROS node abstraction");
56 auto node = ros_node_abstraction->get_raw_node();
58 clicked_point_subscription_ = node->create_subscription<geometry_msgs::msg::PointStamped>(
59 "clicked_point", 1, [
this](
const geometry_msgs::msg::PointStamped::SharedPtr msg) {
60 ui_->add_field_1->setText(std::to_string(msg->point.x).c_str());
61 ui_->add_field_2->setText(std::to_string(msg->point.y).c_str());
62 ui_->edit_field_1->setText(std::to_string(msg->point.x).c_str());
63 ui_->edit_field_2->setText(std::to_string(msg->point.y).c_str());
67 void RouteTool::on_load_button_clicked(
void)
69 graph_to_id_map_.clear();
70 edge_to_node_map_.clear();
71 graph_to_incoming_edges_map_.clear();
73 QString filename = QFileDialog::getOpenFileName(
75 tr(
"Open Address Book"),
"",
76 tr(
"Address Book (*.geojson);;All Files (*)"));
77 graph_loader_->loadGraphFromFile(graph_, graph_to_id_map_, filename.toStdString());
78 unsigned int max_node_id = 0;
79 for (
const auto & node : graph_) {
80 max_node_id = std::max(node.nodeid, max_node_id);
81 for (
const auto & edge : node.neighbors) {
82 max_node_id = std::max(edge.edgeid, max_node_id);
83 edge_to_node_map_[edge.edgeid] = node.nodeid;
84 if (graph_to_incoming_edges_map_.find(edge.end->nodeid) !=
85 graph_to_incoming_edges_map_.end())
87 graph_to_incoming_edges_map_[edge.end->nodeid].push_back(edge.edgeid);
89 graph_to_incoming_edges_map_[edge.end->nodeid] = std::vector<unsigned int> {edge.edgeid};
93 next_node_id_ = max_node_id + 1;
97 void RouteTool::on_save_button_clicked(
void)
99 QString filename = QFileDialog::getSaveFileName(
101 tr(
"Open Address Book"),
"",
102 tr(
"Address Book (*.geojson);;All Files (*)"));
103 RCLCPP_INFO(node_->get_logger(),
"Save graph to: %s", filename.toStdString().c_str());
104 graph_saver_->saveGraphToFile(graph_, filename.toStdString());
107 void RouteTool::on_create_button_clicked(
void)
109 if (
ui_->add_field_1->toPlainText() ==
"" ||
ui_->add_field_2->toPlainText() ==
"") {
return;}
110 if (
ui_->add_node_button->isChecked()) {
111 auto longitude =
ui_->add_field_1->toPlainText().toFloat();
112 auto latitude =
ui_->add_field_2->toPlainText().toFloat();
114 new_node.nodeid = next_node_id_;
115 new_node.coords.x = longitude;
116 new_node.coords.y = latitude;
117 graph_.push_back(new_node);
118 graph_to_id_map_[next_node_id_++] = graph_.size() - 1;
119 RCLCPP_INFO(node_->get_logger(),
"Adding node at: (%f, %f)", longitude, latitude);
120 update_route_graph();
121 }
else if (
ui_->add_edge_button->isChecked()) {
122 auto start_node =
ui_->add_field_1->toPlainText().toInt();
123 auto end_node =
ui_->add_field_2->toPlainText().toInt();
125 graph_[graph_to_id_map_[start_node]].addEdge(
126 edge_cost, &(graph_[graph_to_id_map_[end_node]]),
128 if (graph_to_incoming_edges_map_.find(end_node) != graph_to_incoming_edges_map_.end()) {
129 graph_to_incoming_edges_map_[end_node].push_back(next_node_id_);
131 graph_to_incoming_edges_map_[end_node] = std::vector<unsigned int> {next_node_id_};
133 edge_to_node_map_[next_node_id_++] = start_node;
134 RCLCPP_INFO(node_->get_logger(),
"Adding edge from %d to %d", start_node, end_node);
135 update_route_graph();
137 ui_->add_field_1->setText(
"");
138 ui_->add_field_2->setText(
"");
141 void RouteTool::on_confirm_button_clicked(
void)
143 if (
ui_->edit_id->toPlainText() ==
"" ||
ui_->edit_field_1->toPlainText() ==
"" ||
144 ui_->edit_field_2->toPlainText() ==
"") {
return;}
145 if (
ui_->edit_node_button->isChecked()) {
146 auto node_id =
ui_->edit_id->toPlainText().toInt();
147 auto new_longitude =
ui_->edit_field_1->toPlainText().toFloat();
148 auto new_latitude =
ui_->edit_field_2->toPlainText().toFloat();
149 if (graph_to_id_map_.find(node_id) != graph_to_id_map_.end()) {
150 graph_[graph_to_id_map_[node_id]].coords.x = new_longitude;
151 graph_[graph_to_id_map_[node_id]].coords.y = new_latitude;
152 update_route_graph();
154 }
else if (
ui_->edit_edge_button->isChecked()) {
155 auto edge_id = (
unsigned int)
ui_->edit_id->toPlainText().toInt();
156 auto new_start =
ui_->edit_field_1->toPlainText().toInt();
157 auto new_end =
ui_->edit_field_2->toPlainText().toInt();
159 auto current_start_node = &graph_[graph_to_id_map_[edge_to_node_map_[edge_id]]];
160 for (
auto itr = current_start_node->neighbors.begin();
161 itr != current_start_node->neighbors.end(); itr++)
163 if (itr->edgeid == edge_id) {
164 current_start_node->neighbors.erase(itr);
170 graph_[graph_to_id_map_[new_start]].addEdge(
171 edge_cost, &(graph_[graph_to_id_map_[new_end]]),
173 edge_to_node_map_[edge_id] = new_start;
174 if (graph_to_incoming_edges_map_.find(new_end) != graph_to_incoming_edges_map_.end()) {
175 graph_to_incoming_edges_map_[new_end].push_back(edge_id);
177 graph_to_incoming_edges_map_[new_end] = std::vector<unsigned int> {edge_id};
179 update_route_graph();
181 ui_->edit_id->setText(
"");
182 ui_->edit_field_1->setText(
"");
183 ui_->edit_field_2->setText(
"");
186 void RouteTool::on_delete_button_clicked(
void)
188 if (
ui_->remove_id->toPlainText() ==
"") {
return;}
189 if (
ui_->remove_node_button->isChecked()) {
190 unsigned int node_id =
ui_->remove_id->toPlainText().toInt();
192 for (
auto edge_id : graph_to_incoming_edges_map_[node_id]) {
193 auto start_node = &graph_[graph_to_id_map_[edge_to_node_map_[edge_id]]];
194 for (
auto itr = start_node->neighbors.begin(); itr != start_node->neighbors.end(); itr++) {
195 if (itr->edgeid == edge_id) {
196 start_node->neighbors.erase(itr);
197 edge_to_node_map_.erase(edge_id);
202 if (graph_[graph_to_id_map_[node_id]].nodeid == node_id) {
204 graph_[graph_to_id_map_[node_id]].nodeid = std::numeric_limits<int>::max();
205 graph_to_id_map_.erase(node_id);
206 graph_to_incoming_edges_map_.erase(node_id);
207 RCLCPP_INFO(node_->get_logger(),
"Removed node %d", node_id);
209 update_route_graph();
210 }
else if (
ui_->remove_edge_button->isChecked()) {
211 auto edge_id = (
unsigned int)
ui_->remove_id->toPlainText().toInt();
212 auto start_node = &graph_[graph_to_id_map_[edge_to_node_map_[edge_id]]];
213 for (
auto itr = start_node->neighbors.begin(); itr != start_node->neighbors.end(); itr++) {
214 if (itr->edgeid == edge_id) {
215 RCLCPP_INFO(node_->get_logger(),
"Removed edge %d", edge_id);
216 start_node->neighbors.erase(itr);
217 edge_to_node_map_.erase(edge_id);
221 update_route_graph();
223 ui_->remove_id->setText(
"");
226 void RouteTool::on_add_node_button_toggled(
void)
228 if (
ui_->add_node_button->isChecked()) {
229 ui_->add_text->setText(
"Position:");
230 ui_->add_label_1->setText(
"X:");
231 ui_->add_label_2->setText(
"Y:");
233 ui_->add_text->setText(
"Connections:");
234 ui_->add_label_1->setText(
"Start Node ID:");
235 ui_->add_label_2->setText(
"End Node ID:");
239 void RouteTool::on_edit_node_button_toggled(
void)
241 if (
ui_->edit_node_button->isChecked()) {
242 ui_->edit_text->setText(
"Position:");
243 ui_->edit_label_1->setText(
"X:");
244 ui_->edit_label_2->setText(
"Y:");
246 ui_->edit_text->setText(
"Connections:");
247 ui_->edit_label_1->setText(
"Start Node ID:");
248 ui_->edit_label_2->setText(
"End Node ID:");
252 void RouteTool::update_route_graph(
void)
254 graph_vis_publisher_->publish(nav2_route::utils::toMsg(graph_,
"map", node_->now()));
259 rviz_common::Panel::save(config);
262 void RouteTool::load(
const rviz_common::Config & config)
264 rviz_common::Panel::load(config);
268 #include <pluginlib/class_list_macros.hpp>
An object to store edge cost or cost metadata for scoring.
An object to store the nodes in the graph file.