diff --git a/rosserial_rp2040/src/ros_lib/RP2040_Hardware_USB.h b/rosserial_rp2040/src/ros_lib/RP2040_Hardware_USB.h index 4b9059856..35ef8d0b3 100644 --- a/rosserial_rp2040/src/ros_lib/RP2040_Hardware_USB.h +++ b/rosserial_rp2040/src/ros_lib/RP2040_Hardware_USB.h @@ -39,10 +39,10 @@ #ifndef ROS_RP2040_Hardware_USB_H_ #define ROS_RP2040_Hardware_USB_H_ -class RP2040_Hardware +class RP2040_Hardware_USB { public: - RP2040_Hardware() {} + RP2040_Hardware_USB() {} // any initialization code necessary to use the serial port void init() diff --git a/rosserial_rp2040/src/ros_lib/ros.h b/rosserial_rp2040/src/ros_lib/ros.h index 865e13e28..c5a21b164 100644 --- a/rosserial_rp2040/src/ros_lib/ros.h +++ b/rosserial_rp2040/src/ros_lib/ros.h @@ -6,16 +6,16 @@ #define _ROS_H_ #include "ros/node_handle.h" - -#ifdef USE_USBCON #include "RP2040_Hardware.h" -#else #include "RP2040_Hardware_USB.h" -#endif namespace ros { + #ifdef USE_USBCON + typedef ros::NodeHandle_ NodeHandle; + #else typedef ros::NodeHandle_ NodeHandle; + #endif } -#endif +#endif \ No newline at end of file