Skip to content

Commit

Permalink
Fix ClassLoader warning
Browse files Browse the repository at this point in the history
ros.rosconsole_bridge.class_loader.ClassLoader: SEVERE WARNING!!!
Attempting to unload /opt/ros/one/lib//libprbt_manipulator_moveit_ikfast_plugin.so
while objects created by this library still exist in the heap!
You should delete your objects before destroying the ClassLoader. The library will NOT be unloaded.

We need to delete the RobotModelLoader after the RobotModel.
  • Loading branch information
rhaschke committed Dec 20, 2024
1 parent c53601d commit ce61fac
Show file tree
Hide file tree
Showing 11 changed files with 23 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,8 @@ class IntegrationTestCommandListManager : public testing::Test
protected:
// ros stuff
ros::NodeHandle ph_{ "~" };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(ROBOT_DESCRIPTION_STR).getModel() };
robot_model_loader::RobotModelLoader robot_model_loader_{ ROBOT_DESCRIPTION_STR };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader_.getModel() };
std::shared_ptr<pilz_industrial_motion_planner::CommandListManager> manager_;
planning_scene::PlanningScenePtr scene_;
planning_pipeline::PlanningPipelinePtr pipeline_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,8 @@ class GetSolverTipFrameIntegrationTest : public testing::Test
void SetUp() override;

protected:
robot_model::RobotModelConstPtr robot_model_{
robot_model_loader::RobotModelLoader(ROBOT_DESCRIPTION_PARAM).getModel()
};
robot_model_loader::RobotModelLoader robot_model_loader_{ ROBOT_DESCRIPTION_PARAM };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader_.getModel() };
};

void GetSolverTipFrameIntegrationTest::SetUp()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,8 @@ class IntegrationTestPlanComponentBuilder : public testing::Test

protected:
ros::NodeHandle ph_{ "~" };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(ROBOT_DESCRIPTION_STR).getModel() };
robot_model_loader::RobotModelLoader robot_model_loader_{ ROBOT_DESCRIPTION_STR };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader_.getModel() };
planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) };

std::string planning_group_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,8 @@ class CommandPlannerTest : public testing::TestWithParam<std::string>
protected:
// ros stuff
ros::NodeHandle ph_{ "~" };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(GetParam()).getModel() };
robot_model_loader::RobotModelLoader robot_model_loader_{ GetParam() };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader_.getModel() };

std::string planner_plugin_name_;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,8 @@ class PlanningContextLoadersTest : public ::testing::TestWithParam<std::vector<s

protected:
ros::NodeHandle ph_{ "~" };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(GetParam().back()).getModel() };
robot_model_loader::RobotModelLoader robot_model_loader_{ GetParam().back() };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader_.getModel() };

// Load the plugin
std::unique_ptr<pluginlib::ClassLoader<pilz_industrial_motion_planner::PlanningContextLoader>>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,8 @@ class TrajectoryBlenderTransitionWindowTest : public testing::TestWithParam<std:
protected:
// ros stuff
ros::NodeHandle ph_{ "~" };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(GetParam()).getModel() };
robot_model_loader::RobotModelLoader robot_model_loader_{ GetParam() };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader_.getModel() };
planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) };

std::unique_ptr<TrajectoryGenerator> lin_generator_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,8 @@ class TrajectoryFunctionsTestBase : public testing::TestWithParam<std::string>
protected:
// ros stuff
ros::NodeHandle ph_{ "~" };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(GetParam()).getModel() };
robot_model_loader::RobotModelLoader robot_model_loader_{ GetParam() };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader_.getModel() };
robot_state::RobotState robot_state_{ robot_model_ };
planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) };

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,8 @@ class TrajectoryGeneratorCIRCTest : public testing::TestWithParam<std::string>
protected:
// ros stuff
ros::NodeHandle ph_{ "~" };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(GetParam()).getModel() };
robot_model_loader::RobotModelLoader robot_model_loader_{ GetParam() };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader_.getModel() };
planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) };
std::unique_ptr<TrajectoryGeneratorCIRC> circ_;
// test data provider
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -144,10 +144,9 @@ class TrajectoryGeneratorCommonTest : public ::testing::Test
protected:
// ros stuff
ros::NodeHandle ph_{ "~" };
robot_model::RobotModelConstPtr robot_model_{
robot_model_loader::RobotModelLoader(!T::VALUE ? PARAM_MODEL_NO_GRIPPER_NAME : PARAM_MODEL_WITH_GRIPPER_NAME)
.getModel()
};
robot_model_loader::RobotModelLoader robot_model_loader_{ !T::VALUE ? PARAM_MODEL_NO_GRIPPER_NAME :
PARAM_MODEL_WITH_GRIPPER_NAME };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader_.getModel() };
planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) };

// trajectory generator
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -90,7 +90,8 @@ class TrajectoryGeneratorLINTest : public testing::TestWithParam<std::string>
protected:
// ros stuff
ros::NodeHandle ph_{ "~" };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(GetParam()).getModel() };
robot_model_loader::RobotModelLoader robot_model_loader_{ GetParam() };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader_.getModel() };
planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) };

// lin trajectory generator using model without gripper
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,8 @@ class TrajectoryGeneratorPTPTest : public testing::TestWithParam<std::string>
protected:
// ros stuff
ros::NodeHandle ph_{ "~" };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader::RobotModelLoader(GetParam()).getModel() };
robot_model_loader::RobotModelLoader robot_model_loader_{ GetParam() };
robot_model::RobotModelConstPtr robot_model_{ robot_model_loader_.getModel() };
planning_scene::PlanningSceneConstPtr planning_scene_{ new planning_scene::PlanningScene(robot_model_) };

// trajectory generator
Expand Down

0 comments on commit ce61fac

Please sign in to comment.