Skip to content

Commit

Permalink
test: fix tests for colcon
Browse files Browse the repository at this point in the history
  • Loading branch information
DavidPL1 committed Dec 5, 2024
1 parent 1042cbf commit 98ab8d3
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 1 deletion.
1 change: 1 addition & 0 deletions mujoco_ros/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -71,5 +71,6 @@ install(FILES
empty_world.xml
equality_world.xml
camera_world.xml
pendulum_world.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/test
)
16 changes: 15 additions & 1 deletion mujoco_ros/test/mujoco_env_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,21 @@ int main(int argc, char **argv)
{
::testing::InitGoogleTest(&argc, argv);
ros::init(argc, argv, "mujoco_env_test");
return RUN_ALL_TESTS();

// Uncomment to enable debug output (useful for debugging failing tests)
// ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug);
// ros::console::notifyLoggerLevelsChanged();

// Create spinner to communicate with ROS
ros::AsyncSpinner spinner(1);
spinner.start();
ros::NodeHandle nh;
int ret = RUN_ALL_TESTS();

// Stop spinner and shutdown ROS before returning
spinner.stop();
ros::shutdown();
return ret;
}

using namespace mujoco_ros;
Expand Down
2 changes: 2 additions & 0 deletions mujoco_ros/test/mujoco_ros_plugin_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,6 +162,8 @@ TEST_F(BaseEnvFixture, RenderCallback)
}
}

ASSERT_NE(test_plugin, nullptr) << "TestPlugin not found!";

// wait for render callback to be called
float seconds = 0;
while (!test_plugin->ran_render_cb.load() && seconds < 1.) {
Expand Down

0 comments on commit 98ab8d3

Please sign in to comment.