Skip to content

Commit

Permalink
build: suppress pluginlib caused clang-tidy errors
Browse files Browse the repository at this point in the history
  • Loading branch information
DavidPL1 committed Nov 8, 2024
1 parent 1f52f14 commit d15798f
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 3 deletions.
2 changes: 2 additions & 0 deletions mujoco_ros/src/plugin_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,8 +113,10 @@ bool registerPlugin(const std::string &nh_namespace, const XmlRpc::XmlRpcValue &

void initPluginLoader()
{
// NOLINTBEGIN(clang-analyzer-optin.cplusplus.VirtualCall)
plugin_loader_ptr_ =
std::make_unique<pluginlib::ClassLoader<mujoco_ros::MujocoPlugin>>("mujoco_ros", "mujoco_ros::MujocoPlugin");
// NOLINTEND(clang-analyzer-optin.cplusplus.VirtualCall)
}

void unloadPluginloader()
Expand Down
9 changes: 6 additions & 3 deletions mujoco_ros_control/src/mujoco_ros_control_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,18 +45,19 @@
#include <chrono>
#include <thread>

// clang-tidy complains about ROS_LOG in the pluginlib macros
// NOLINTBEGIN(clang-analyzer-optin.cplusplus.VirtualCall)
namespace mujoco_ros::control {

MujocoRosControlPlugin::~MujocoRosControlPlugin() = default;

bool MujocoRosControlPlugin::load(const mjModel *m, mjData *d)
{
ROS_INFO_STREAM_NAMED("mujoco_ros_control", "Loading mujoco_ros_control plugin ...");
ROS_INFO_NAMED("mujoco_ros_control", "Loading mujoco_ros_control plugin ...");

// Check that ROS has been initialized
if (!ros::isInitialized()) {
ROS_FATAL_STREAM_NAMED("mujoco_ros_control",
"A ROS node for Mujoco has not been initialized, unable to load plugin.");
ROS_FATAL_NAMED("mujoco_ros_control", "A ROS node for Mujoco has not been initialized, unable to load plugin.");
return false;
}

Expand Down Expand Up @@ -238,3 +239,5 @@ void MujocoRosControlPlugin::eStopCB(const std_msgs::BoolConstPtr &e_stop_active
} // namespace mujoco_ros::control

PLUGINLIB_EXPORT_CLASS(mujoco_ros::control::MujocoRosControlPlugin, mujoco_ros::MujocoPlugin)

// NOLINTEND(clang-analyzer-optin.cplusplus.VirtualCall)

0 comments on commit d15798f

Please sign in to comment.