Skip to content

Commit 8eab79a

Browse files
Disable camera publishing if GLFW fails to initialize (#25)
Signed-off-by: Paul Gesel <[email protected]> Co-authored-by: Paul Gesel <[email protected]>
1 parent 1ff34f9 commit 8eab79a

File tree

1 file changed

+6
-1
lines changed

1 file changed

+6
-1
lines changed

src/mujoco_cameras.cpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -131,6 +131,12 @@ void MujocoCameras::register_cameras(const hardware_interface::HardwareInfo& har
131131
void MujocoCameras::init()
132132
{
133133
// Start the rendering thread process
134+
if (!glfwInit())
135+
{
136+
RCLCPP_WARN(node_->get_logger(), "Failed to initialize GLFW. Disabling camera publishing.");
137+
publish_images_ = false;
138+
return;
139+
}
134140
publish_images_ = true;
135141
rendering_thread_ = std::thread(&MujocoCameras::update_loop, this);
136142
}
@@ -150,7 +156,6 @@ void MujocoCameras::close()
150156
void MujocoCameras::update_loop()
151157
{
152158
// We create an offscreen context specific to this process for managing camera rendering.
153-
glfwInit();
154159
glfwWindowHint(GLFW_VISIBLE, GLFW_FALSE);
155160
GLFWwindow* window = glfwCreateWindow(1, 1, "", NULL, NULL);
156161
glfwMakeContextCurrent(window);

0 commit comments

Comments
 (0)