Skip to content

Commit

Permalink
rviz panel working when rviz2 supports it
Browse files Browse the repository at this point in the history
  • Loading branch information
SteveMacenski committed Oct 8, 2019
1 parent 13b790e commit 96f46d7
Show file tree
Hide file tree
Showing 4 changed files with 46 additions and 44 deletions.
49 changes: 26 additions & 23 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,8 @@ set(dependencies
std_srvs
builtin_interfaces
rviz_common
rviz_rendering
rviz_default_plugins
#interactive_markers
)

Expand All @@ -55,7 +57,7 @@ set(libraries
sync_slam_toolbox
async_slam_toolbox
toolbox_common
SlamToolboxPlugin
#SlamToolboxPlugin
ceres_solver_plugin
)

Expand Down Expand Up @@ -95,27 +97,28 @@ rosidl_generate_interfaces(${PROJECT_NAME}
DEPENDENCIES builtin_interfaces geometry_msgs std_msgs action_msgs nav_msgs
)

set(CMAKE_AUTOMOC ON)
find_package(Qt5 ${rviz_QT_VERSION} REQUIRED Core Widgets)
set(QT_LIBRARIES Qt5::Widgets Qt5::Core)
macro(qt_wrap_ui)
qt5_wrap_ui(${ARGN})
endmacro()
macro(qt_wrap_cpp)
qt5_wrap_cpp(${ARGN})
endmacro()

#### rviz Plugin TODO port to ROS2
qt_wrap_cpp(MOC_FILES rviz_plugin/slam_toolbox_rviz_plugin.h)
set(SOURCE_FILES rviz_plugin/slam_toolbox_rviz_plugin.cpp )
set(HEADER_FILES rviz_plugin/slam_toolbox_rviz_plugin.h )
add_library(SlamToolboxPlugin ${SOURCE_FILES} ${HEADER_FILES})
ament_target_dependencies(SlamToolboxPlugin
${dependencies}
)
target_link_libraries(SlamToolboxPlugin karto ${rviz_DEFAULT_PLUGIN_LIBRARIES} ${QT_LIBRARIES})
rosidl_target_interfaces(SlamToolboxPlugin ${PROJECT_NAME} "rosidl_typesupport_cpp")
pluginlib_export_plugin_description_file(rviz_common rviz_plugins.xml)
#set(CMAKE_AUTOMOC ON)
#find_package(Qt5 ${rviz_QT_VERSION} REQUIRED Core Widgets)
#set(QT_LIBRARIES Qt5::Widgets Qt5::Core)
#macro(qt_wrap_ui)
# qt5_wrap_ui(${ARGN})
#endmacro()
#macro(qt_wrap_cpp)
# qt5_wrap_cpp(${ARGN})
#endmacro()

#### rviz Plugin
#qt_wrap_cpp(MOC_FILES rviz_plugin/slam_toolbox_rviz_plugin.h)
#set(SOURCE_FILES rviz_plugin/slam_toolbox_rviz_plugin.cpp )
#set(HEADER_FILES rviz_plugin/slam_toolbox_rviz_plugin.h )
#add_library(SlamToolboxPlugin ${SOURCE_FILES} ${HEADER_FILES})
#ament_target_dependencies(SlamToolboxPlugin
# ${dependencies}
#)
#target_link_libraries(SlamToolboxPlugin karto ${rviz_DEFAULT_PLUGIN_LIBRARIES} ${QT_LIBRARIES})
#rosidl_target_interfaces(SlamToolboxPlugin ${PROJECT_NAME} "rosidl_typesupport_cpp")
#target_compile_definitions(SlamToolboxPlugin PUBLIC "PLUGINLIB__DISABLE_BOOST_FUNCTIONS")
#pluginlib_export_plugin_description_file(slam_toolbox rviz_plugins.xml)

#### Ceres Plugin
add_library(ceres_solver_plugin solvers/ceres_solver.cpp)
Expand Down Expand Up @@ -194,7 +197,7 @@ install(DIRECTORY config
DESTINATION share
)

install(FILES solver_plugins.xml rviz_plugins.xml
install(FILES solver_plugins.xml #rviz_plugins.xml
DESTINATION share
)

Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@

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

# Introduction
Expand Down
15 changes: 7 additions & 8 deletions rviz_plugins.xml
Original file line number Diff line number Diff line change
@@ -1,9 +1,8 @@
<library path="libSlamToolboxPlugin">
<class name="slam_toolbox::SlamToolboxPlugin"
type="slam_toolbox::SlamToolboxPlugin"
base_class_type="rviz::Panel">
<description>
Panel to assist in Mapping and SLAM with the slam_toolbox
</description>
</class>
<library path="SlamToolboxPlugin">
<class
name="slam_toolbox::SlamToolboxPlugin"
type="slam_toolbox::SlamToolboxPlugin"
base_class_type="rviz_common::Panel">
<description> Panel to assist in Mapping and SLAM with the slam_toolbox </description>
</class>
</library>
24 changes: 12 additions & 12 deletions solver_plugins.xml
Original file line number Diff line number Diff line change
@@ -1,15 +1,3 @@
<!-- <library path="spa_solver_plugin">
<class type="solver_plugins::SpaSolver" base_class_type="karto::ScanSolver">
<description> SPA Optimizer for karto </description>
</class>
</library> -->

<!-- <library path="g2O_solver_plugin">
<class type="solver_plugins::G2OSolver" base_class_type="karto::ScanSolver">
<description> G2O Optimizer for karto </description>
</class>
</library> -->

<library path="ceres_solver_plugin">
<class
name="solver_plugins::CeresSolver"
Expand All @@ -24,3 +12,15 @@
<description> GTSAM Optimizer for karto </description>
</class>
</library> -->

<!-- <library path="spa_solver_plugin">
<class type="solver_plugins::SpaSolver" base_class_type="karto::ScanSolver">
<description> SPA Optimizer for karto </description>
</class>
</library> -->

<!-- <library path="g2O_solver_plugin">
<class type="solver_plugins::G2OSolver" base_class_type="karto::ScanSolver">
<description> G2O Optimizer for karto </description>
</class>
</library> -->

0 comments on commit 96f46d7

Please sign in to comment.