Skip to content

Commit 2a72d3f

Browse files
authored
Fix SDL2 include path (#196)
The CMake functionality provided by SDL2 specifies that the include directory is the `SDL2` directory itself, not the parent directory thereof. On some systems, we're getting lucky because the SDL2 directory resides in a common include directory like `/usr/include`, so the include directory given by the SDL2 CMake functionality isn't used. Of course, on systems where this is not the case, the compiler fails to find the headers. Signed-off-by: Scott K Logan <[email protected]>
1 parent d8d8b02 commit 2a72d3f

File tree

3 files changed

+3
-3
lines changed

3 files changed

+3
-3
lines changed

joy/include/joy/joy.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@
3030
#ifndef JOY__JOY_HPP_
3131
#define JOY__JOY_HPP_
3232

33-
#include <SDL2/SDL.h>
33+
#include <SDL.h>
3434

3535
#include <rclcpp/rclcpp.hpp>
3636
#include <sensor_msgs/msg/joy.hpp>

joy/src/joy.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@
2727
* POSSIBILITY OF SUCH DAMAGE.
2828
*/
2929

30-
#include <SDL2/SDL.h>
30+
#include <SDL.h>
3131

3232
#include <rclcpp/rclcpp.hpp>
3333
#include <rclcpp_components/register_node_macro.hpp>

joy/src/joy_enumerate_devices.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@
2929

3030
// On Windows, we have to be sure that SDL doesn't generate its own main.
3131
#define SDL_MAIN_HANDLED
32-
#include <SDL2/SDL.h>
32+
#include <SDL.h>
3333

3434
#include <cstdio>
3535
#include <stdexcept>

0 commit comments

Comments
 (0)