Skip to content

Commit

Permalink
include class_list_macros.hpp instead of h
Browse files Browse the repository at this point in the history
  • Loading branch information
lucasw committed Apr 14, 2024
1 parent 2650463 commit db21101
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion rviz_plugin_tutorials/src/imu_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,6 @@ void ImuDisplay::processMessage( const sensor_msgs::Imu::ConstPtr& msg )

// Tell pluginlib about this class. It is important to do this in
// global scope, outside our package's namespace.
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(rviz_plugin_tutorials::ImuDisplay,rviz::Display )
// END_TUTORIAL
2 changes: 1 addition & 1 deletion rviz_plugin_tutorials/src/plant_flag_tool.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -288,6 +288,6 @@ void PlantFlagTool::load( const rviz::Config& config )

} // end namespace rviz_plugin_tutorials

#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(rviz_plugin_tutorials::PlantFlagTool,rviz::Tool )
// END_TUTORIAL
2 changes: 1 addition & 1 deletion rviz_plugin_tutorials/src/teleop_panel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,6 +195,6 @@ void TeleopPanel::load( const rviz::Config& config )
// Tell pluginlib about this class. Every class which should be
// loadable by pluginlib::ClassLoader must have these two lines
// compiled in its .cpp file, outside of any namespace scope.
#include <pluginlib/class_list_macros.h>
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(rviz_plugin_tutorials::TeleopPanel,rviz::Panel )
// END_TUTORIAL

0 comments on commit db21101

Please sign in to comment.