Skip to content

Commit 33f4015

Browse files
john-chrosniakSaikrishnaBairamoniSteveMacenski
authored
Route Tool Rviz Panel (#4775)
* added route tool skeleton code and gui Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * rviz2 panel can load route graph Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * can add nodes using route tool Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added logic for creating edges Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * graph nodes can be edited, existing edges will still connect if a node is moved Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * can edit edges Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * can delete nodes and edges Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * route graphs can be saved Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed bug for loading in route graphs Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added dynamic text to UI, created launch file and rviz configuration Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed bug for deleting nodes Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * actually fixed node removal bug Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * publishing clicked point populates x and y fields Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * removed debugging log statements Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added check to make sure node/edges exist before editing Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * bug fix Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * migrated route tool to rviz plugin Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * minor refactoring Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added metadata and operations to graph saver so nothing should be erased Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * edited set route service to clear current route before setting new Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * Update README.md Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * addressed comments Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * documentation cleanup Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * changed copyright Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * addressed comments Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * moved copyright due to compiler error Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * revert removal of files Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added gen ai comment Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed rebasing issue Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fix linting errors Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added export for graph saver dependencies Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added ui file to library Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added nav2_route_core to link libaries Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed cmake error Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed build issues Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * uncrustified Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * cpplint Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added unit tests and fixed bugs Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * increased test coverage Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed linter errors Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed pre-commit errors Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed formatting error Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * double -> single quotes Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * added test for using default filepath Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * fixed license Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * addressed comments Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * Update nav2_route/include/nav2_route/graph_saver.hpp Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * Update nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * Update nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * Update nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * Update nav2_route/src/plugins/graph_file_savers/geojson_graph_file_saver.cpp Co-authored-by: Steve Macenski <stevenmacenski@gmail.com> Signed-off-by: John Chrosniak <chrosniakj@gmail.com> * linter fix Signed-off-by: John Chrosniak <chrosniakj@gmail.com> --------- Signed-off-by: John Chrosniak <chrosniakj@gmail.com> Co-authored-by: Saikrishna Bairamoni <84093461+SaikrishnaBairamoni@users.noreply.github.com> Co-authored-by: Steve Macenski <stevenmacenski@gmail.com>
1 parent bcb539a commit 33f4015

File tree

24 files changed

+2222
-39
lines changed

24 files changed

+2222
-39
lines changed

nav2_route/CMakeLists.txt

Lines changed: 36 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,7 @@ add_library(${library_name} SHARED
3939
src/node_spatial_tree.cpp
4040
src/path_converter.cpp
4141
src/graph_loader.cpp
42+
src/graph_saver.cpp
4243
src/goal_intent_extractor.cpp
4344
)
4445

@@ -187,6 +188,37 @@ target_link_libraries(graph_file_loaders PRIVATE
187188
tf2::tf2
188189
)
189190

191+
add_library(graph_file_savers SHARED
192+
src/plugins/graph_file_savers/geojson_graph_file_saver.cpp
193+
)
194+
target_include_directories(graph_file_savers
195+
PUBLIC
196+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
197+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>"
198+
)
199+
target_link_libraries(graph_file_savers PUBLIC
200+
nav2_core::nav2_core
201+
nav2_costmap_2d::nav2_costmap_2d_core
202+
${nav2_msgs_TARGETS}
203+
nav2_util::nav2_util_core
204+
${nav_msgs_TARGETS}
205+
pluginlib::pluginlib
206+
rclcpp::rclcpp
207+
rclcpp_lifecycle::rclcpp_lifecycle
208+
${rcl_interfaces_TARGETS}
209+
${geometry_msgs_TARGETS}
210+
${visualization_msgs_TARGETS}
211+
${std_msgs_TARGETS}
212+
${nav_msgs_TARGETS}
213+
tf2_ros::tf2_ros
214+
nlohmann_json::nlohmann_json
215+
)
216+
target_link_libraries(graph_file_savers PRIVATE
217+
${lifecycle_msgs_TARGETS}
218+
rclcpp_components::component
219+
tf2::tf2
220+
)
221+
190222
pluginlib_export_plugin_description_file(nav2_route plugins.xml)
191223

192224
install(DIRECTORY include/
@@ -197,7 +229,8 @@ install(TARGETS ${executable_name}
197229
RUNTIME DESTINATION lib/${PROJECT_NAME}
198230
)
199231

200-
install(TARGETS ${library_name} edge_scorers route_operations graph_file_loaders
232+
install(TARGETS ${library_name} edge_scorers route_operations graph_file_loaders graph_file_savers
233+
EXPORT export_${PROJECT_NAME}
201234
ARCHIVE DESTINATION lib
202235
LIBRARY DESTINATION lib
203236
RUNTIME DESTINATION bin
@@ -216,7 +249,6 @@ if(BUILD_TESTING)
216249
endif()
217250

218251
ament_export_include_directories(include/${PROJECT_NAME})
219-
ament_export_dependencies(${dependencies})
220252
ament_export_dependencies(
221253
rclcpp
222254
rclcpp_lifecycle
@@ -232,5 +264,6 @@ ament_export_dependencies(
232264
nanoflann
233265
nlohmann_json
234266
)
235-
ament_export_libraries(${library_name} edge_scorers route_operations graph_file_loaders)
267+
ament_export_libraries(${library_name} edge_scorers route_operations graph_file_loaders graph_file_savers)
268+
ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
236269
ament_package()
Lines changed: 91 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,91 @@
1+
// Copyright (c) 2024 John Chrosniak
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef NAV2_ROUTE__GRAPH_SAVER_HPP_
16+
#define NAV2_ROUTE__GRAPH_SAVER_HPP_
17+
18+
#include <string>
19+
#include <memory>
20+
#include <vector>
21+
#include <unordered_map>
22+
#include <nlohmann/json.hpp>
23+
#include <pluginlib/class_loader.hpp>
24+
25+
#include "nav2_util/lifecycle_node.hpp"
26+
#include "tf2_ros/buffer.h"
27+
#include "tf2_ros/transform_listener.h"
28+
#include "nav2_util/node_utils.hpp"
29+
#include "nav2_util/robot_utils.hpp"
30+
#include "nav2_route/types.hpp"
31+
#include "nav2_route/interfaces/graph_file_saver.hpp"
32+
#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
33+
34+
namespace nav2_route
35+
{
36+
37+
/**
38+
* @class nav2_route::GraphSaver
39+
* @brief An object to save graph objects to a file
40+
*/
41+
class GraphSaver
42+
{
43+
public:
44+
/**
45+
* @brief A constructor for nav2_route::GraphSaver
46+
* @param node Lifecycle node encapsulated by the GraphSaver
47+
* @param tf A tf buffer
48+
* @param frame Coordinate frame that the graph belongs to
49+
*/
50+
explicit GraphSaver(
51+
nav2_util::LifecycleNode::SharedPtr node,
52+
std::shared_ptr<tf2_ros::Buffer> tf,
53+
const std::string frame);
54+
55+
/**
56+
* @brief A destructor for nav2_route::GraphSaver
57+
*/
58+
~GraphSaver() = default;
59+
60+
/**
61+
* @brief Saves a graph object to a file
62+
* @param graph Graph to save
63+
* @param filepath The filepath to the graph data
64+
* @return bool If successful
65+
*/
66+
bool saveGraphToFile(
67+
Graph & graph,
68+
std::string filepath = "");
69+
70+
/**
71+
* @brief Transform the coordinates in the graph to the route frame
72+
* @param[in/out] graph The graph to be transformed
73+
* @return True if transformation was successful
74+
*/
75+
bool transformGraph(Graph & graph);
76+
77+
protected:
78+
std::string route_frame_, graph_filepath_;
79+
std::shared_ptr<tf2_ros::Buffer> tf_;
80+
rclcpp::Logger logger_{rclcpp::get_logger("GraphSaver")};
81+
82+
// Graph Parser
83+
pluginlib::ClassLoader<GraphFileSaver> plugin_loader_;
84+
GraphFileSaver::Ptr graph_file_saver_;
85+
std::string default_plugin_id_;
86+
std::string plugin_type_;
87+
};
88+
89+
} // namespace nav2_route
90+
91+
#endif // NAV2_ROUTE__GRAPH_SAVER_HPP_
Lines changed: 67 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,67 @@
1+
// Copyright (c) 2024 John Chrosniak
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#ifndef NAV2_ROUTE__INTERFACES__GRAPH_FILE_SAVER_HPP_
16+
#define NAV2_ROUTE__INTERFACES__GRAPH_FILE_SAVER_HPP_
17+
18+
#include <string>
19+
#include <memory>
20+
21+
22+
#include "rclcpp/rclcpp.hpp"
23+
#include "rclcpp_lifecycle/lifecycle_node.hpp"
24+
#include "nav2_route/types.hpp"
25+
26+
namespace nav2_route
27+
{
28+
29+
/**
30+
* @class GraphFileSaver
31+
* @brief A plugin interface to parse a file into the graph
32+
*/
33+
class GraphFileSaver
34+
{
35+
public:
36+
using Ptr = std::shared_ptr<GraphFileSaver>;
37+
38+
/**
39+
* @brief Constructor
40+
*/
41+
GraphFileSaver() = default;
42+
43+
/**
44+
* @brief Virtual destructor
45+
*/
46+
virtual ~GraphFileSaver() = default;
47+
48+
/**
49+
* @brief Configure the graph file saver, but do not store the node
50+
* @param parent pointer to user's node
51+
*/
52+
virtual void configure(
53+
const rclcpp_lifecycle::LifecycleNode::SharedPtr node) = 0;
54+
55+
/**
56+
* @brief Method to save the graph to the filepath
57+
* @param graph The graph to save
58+
* @param filepath The path to save the file to
59+
* @return true if graph was successfully saved
60+
*/
61+
virtual bool saveGraphToFile(
62+
Graph & graph,
63+
std::string filepath) = 0;
64+
};
65+
} // namespace nav2_route
66+
67+
#endif // NAV2_ROUTE__INTERFACES__GRAPH_FILE_SAVER_HPP_
Lines changed: 99 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,99 @@
1+
// Copyright (c) 2024 John Chrosniak
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <memory>
16+
#include <string>
17+
#include <vector>
18+
#include <nlohmann/json.hpp>
19+
20+
#include "nav2_core/route_exceptions.hpp"
21+
#include "nav2_route/interfaces/graph_file_saver.hpp"
22+
#include "nav2_route/plugins/graph_file_loaders/geojson_graph_file_loader.hpp"
23+
24+
#ifndef NAV2_ROUTE__PLUGINS__GRAPH_FILE_SAVERS__GEOJSON_GRAPH_FILE_SAVER_HPP_
25+
#define NAV2_ROUTE__PLUGINS__GRAPH_FILE_SAVERS__GEOJSON_GRAPH_FILE_SAVER_HPP_
26+
27+
namespace nav2_route
28+
{
29+
30+
/**
31+
* @class nav2_route::GeoJsonGraphFileSaver
32+
* @brief A GraphFileSaver plugin to save a geojson graph representation
33+
*/
34+
class GeoJsonGraphFileSaver : public GraphFileSaver
35+
{
36+
public:
37+
using Json = nlohmann::json;
38+
39+
/**
40+
* @brief Constructor
41+
*/
42+
GeoJsonGraphFileSaver() = default;
43+
44+
/**
45+
* @brief Destructor
46+
*/
47+
~GeoJsonGraphFileSaver() = default;
48+
49+
/**
50+
* @brief Configure, but do not store the node
51+
* @param parent pointer to user's node
52+
*/
53+
void configure(
54+
const rclcpp_lifecycle::LifecycleNode::SharedPtr node) override;
55+
56+
/**
57+
* @brief Saves the graph to a geojson file
58+
* @param graph The graph to save to the geojson file
59+
* @param filepath The path to save the graph to
60+
* @return True if successful
61+
*/
62+
bool saveGraphToFile(
63+
Graph & graph,
64+
std::string filepath) override;
65+
66+
protected:
67+
/**
68+
* @brief Add nodes into the graph
69+
* @param[out] graph The graph that will contain the new nodes
70+
* @param[in] json_features Json array to add the nodes to
71+
*/
72+
void loadNodesFromGraph(Graph & graph, std::vector<Json> & json_features);
73+
74+
/**
75+
* @brief Add edges into the graph
76+
* @param[out] graph The graph that will contain the new edges
77+
* @param[in] json_edges Json array to add the edges to
78+
*/
79+
void loadEdgesFromGraph(Graph & graph, std::vector<Json> & json_edges);
80+
81+
/**
82+
* @brief Convert graph metadata to Json
83+
* @param metadata Metadata from a node or edge in the graph
84+
* @param json_metadata Json entry to store metadata in
85+
*/
86+
void convertMetaDataToJson(const Metadata & metadata, Json & json_metadata);
87+
88+
/**
89+
* @brief Convert graph operation to Json
90+
* @param Operations Operations information from the graph
91+
* @param json_operations Json entry to store operation data in
92+
*/
93+
void convertOperationsToJson(const Operations & operations, Json & json_operations);
94+
95+
rclcpp::Logger logger_{rclcpp::get_logger("GeoJsonGraphFileSaver")};
96+
};
97+
} // namespace nav2_route
98+
99+
#endif // NAV2_ROUTE__PLUGINS__GRAPH_FILE_SAVERS__GEOJSON_GRAPH_FILE_SAVER_HPP_

nav2_route/include/nav2_route/types.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -61,6 +61,8 @@ typedef Node * NodePtr;
6161
typedef std::vector<Node> NodeVector;
6262
typedef NodeVector Graph;
6363
typedef std::unordered_map<unsigned int, unsigned int> GraphToIDMap;
64+
typedef std::unordered_map<unsigned int, std::vector<unsigned int>> GraphToIncomingEdgesMap;
65+
typedef std::vector<NodePtr> NodePtrVector;
6466
typedef std::pair<float, NodePtr> NodeElement;
6567
typedef std::pair<unsigned int, unsigned int> NodeExtents;
6668

nav2_route/include/nav2_route/utils.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
#include <limits>
1516
#include <string>
1617
#include <vector>
1718
#include "std_msgs/msg/color_rgba.hpp"
@@ -89,6 +90,9 @@ inline visualization_msgs::msg::MarkerArray toMsg(
8990

9091
unsigned int marker_idx = 1;
9192
for (unsigned int i = 0; i != graph.size(); i++) {
93+
if (graph[i].nodeid == std::numeric_limits<int>::max()) {
94+
continue; // Skip "deleted" nodes
95+
}
9296
curr_marker.ns = "route_graph";
9397
curr_marker.id = marker_idx++;
9498
curr_marker.type = visualization_msgs::msg::Marker::SPHERE;

nav2_route/plugins.xml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -61,6 +61,11 @@
6161
<description>Parse the geojson graph file into the graph data type</description>
6262
</class>
6363
</library>
64+
<library path="graph_file_savers">
65+
<class type="nav2_route::GeoJsonGraphFileSaver" base_class_type="nav2_route::GraphFileSaver">
66+
<description>Save a route graph to a geojson graph file</description>
67+
</class>
68+
</library>
6469

6570
<library path="route_operations">
6671
<class type="nav2_route::CollisionMonitor" base_class_type="nav2_route::RouteOperation">

0 commit comments

Comments
 (0)