Skip to content

Commit 96f46d7

Browse files
committed
rviz panel working when rviz2 supports it
1 parent 13b790e commit 96f46d7

File tree

4 files changed

+46
-44
lines changed

4 files changed

+46
-44
lines changed

CMakeLists.txt

Lines changed: 26 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -46,6 +46,8 @@ set(dependencies
4646
std_srvs
4747
builtin_interfaces
4848
rviz_common
49+
rviz_rendering
50+
rviz_default_plugins
4951
#interactive_markers
5052
)
5153

@@ -55,7 +57,7 @@ set(libraries
5557
sync_slam_toolbox
5658
async_slam_toolbox
5759
toolbox_common
58-
SlamToolboxPlugin
60+
#SlamToolboxPlugin
5961
ceres_solver_plugin
6062
)
6163

@@ -95,27 +97,28 @@ rosidl_generate_interfaces(${PROJECT_NAME}
9597
DEPENDENCIES builtin_interfaces geometry_msgs std_msgs action_msgs nav_msgs
9698
)
9799

98-
set(CMAKE_AUTOMOC ON)
99-
find_package(Qt5 ${rviz_QT_VERSION} REQUIRED Core Widgets)
100-
set(QT_LIBRARIES Qt5::Widgets Qt5::Core)
101-
macro(qt_wrap_ui)
102-
qt5_wrap_ui(${ARGN})
103-
endmacro()
104-
macro(qt_wrap_cpp)
105-
qt5_wrap_cpp(${ARGN})
106-
endmacro()
107-
108-
#### rviz Plugin TODO port to ROS2
109-
qt_wrap_cpp(MOC_FILES rviz_plugin/slam_toolbox_rviz_plugin.h)
110-
set(SOURCE_FILES rviz_plugin/slam_toolbox_rviz_plugin.cpp )
111-
set(HEADER_FILES rviz_plugin/slam_toolbox_rviz_plugin.h )
112-
add_library(SlamToolboxPlugin ${SOURCE_FILES} ${HEADER_FILES})
113-
ament_target_dependencies(SlamToolboxPlugin
114-
${dependencies}
115-
)
116-
target_link_libraries(SlamToolboxPlugin karto ${rviz_DEFAULT_PLUGIN_LIBRARIES} ${QT_LIBRARIES})
117-
rosidl_target_interfaces(SlamToolboxPlugin ${PROJECT_NAME} "rosidl_typesupport_cpp")
118-
pluginlib_export_plugin_description_file(rviz_common rviz_plugins.xml)
100+
#set(CMAKE_AUTOMOC ON)
101+
#find_package(Qt5 ${rviz_QT_VERSION} REQUIRED Core Widgets)
102+
#set(QT_LIBRARIES Qt5::Widgets Qt5::Core)
103+
#macro(qt_wrap_ui)
104+
# qt5_wrap_ui(${ARGN})
105+
#endmacro()
106+
#macro(qt_wrap_cpp)
107+
# qt5_wrap_cpp(${ARGN})
108+
#endmacro()
109+
110+
#### rviz Plugin
111+
#qt_wrap_cpp(MOC_FILES rviz_plugin/slam_toolbox_rviz_plugin.h)
112+
#set(SOURCE_FILES rviz_plugin/slam_toolbox_rviz_plugin.cpp )
113+
#set(HEADER_FILES rviz_plugin/slam_toolbox_rviz_plugin.h )
114+
#add_library(SlamToolboxPlugin ${SOURCE_FILES} ${HEADER_FILES})
115+
#ament_target_dependencies(SlamToolboxPlugin
116+
# ${dependencies}
117+
#)
118+
#target_link_libraries(SlamToolboxPlugin karto ${rviz_DEFAULT_PLUGIN_LIBRARIES} ${QT_LIBRARIES})
119+
#rosidl_target_interfaces(SlamToolboxPlugin ${PROJECT_NAME} "rosidl_typesupport_cpp")
120+
#target_compile_definitions(SlamToolboxPlugin PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
121+
#pluginlib_export_plugin_description_file(slam_toolbox rviz_plugins.xml)
119122

120123
#### Ceres Plugin
121124
add_library(ceres_solver_plugin solvers/ceres_solver.cpp)
@@ -194,7 +197,7 @@ install(DIRECTORY config
194197
DESTINATION share
195198
)
196199

197-
install(FILES solver_plugins.xml rviz_plugins.xml
200+
install(FILES solver_plugins.xml #rviz_plugins.xml
198201
DESTINATION share
199202
)
200203

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,8 @@
88

99
NOTE: ROS2 Port of Slam Toolbox is still experimental. Known on-going work:
1010
- Interactive markers need to be ported to ROS2 and integrated
11+
- Panel plugins need to be ported to ROS2 to test and ship the rviz plugin
1112
- The toolbox needs to be largely tested
12-
- The rviz plugin needs to work as a nested widget
1313
- launch and config files need to be ported
1414

1515
# Introduction

rviz_plugins.xml

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,8 @@
1-
<library path="libSlamToolboxPlugin">
2-
<class name="slam_toolbox::SlamToolboxPlugin"
3-
type="slam_toolbox::SlamToolboxPlugin"
4-
base_class_type="rviz::Panel">
5-
<description>
6-
Panel to assist in Mapping and SLAM with the slam_toolbox
7-
</description>
8-
</class>
1+
<library path="SlamToolboxPlugin">
2+
<class
3+
name="slam_toolbox::SlamToolboxPlugin"
4+
type="slam_toolbox::SlamToolboxPlugin"
5+
base_class_type="rviz_common::Panel">
6+
<description> Panel to assist in Mapping and SLAM with the slam_toolbox </description>
7+
</class>
98
</library>

solver_plugins.xml

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -1,15 +1,3 @@
1-
<!-- <library path="spa_solver_plugin">
2-
<class type="solver_plugins::SpaSolver" base_class_type="karto::ScanSolver">
3-
<description> SPA Optimizer for karto </description>
4-
</class>
5-
</library> -->
6-
7-
<!-- <library path="g2O_solver_plugin">
8-
<class type="solver_plugins::G2OSolver" base_class_type="karto::ScanSolver">
9-
<description> G2O Optimizer for karto </description>
10-
</class>
11-
</library> -->
12-
131
<library path="ceres_solver_plugin">
142
<class
153
name="solver_plugins::CeresSolver"
@@ -24,3 +12,15 @@
2412
<description> GTSAM Optimizer for karto </description>
2513
</class>
2614
</library> -->
15+
16+
<!-- <library path="spa_solver_plugin">
17+
<class type="solver_plugins::SpaSolver" base_class_type="karto::ScanSolver">
18+
<description> SPA Optimizer for karto </description>
19+
</class>
20+
</library> -->
21+
22+
<!-- <library path="g2O_solver_plugin">
23+
<class type="solver_plugins::G2OSolver" base_class_type="karto::ScanSolver">
24+
<description> G2O Optimizer for karto </description>
25+
</class>
26+
</library> -->

0 commit comments

Comments
 (0)