Skip to content

Commit

Permalink
Revert "Allowed for the ros library to be included in multiple headers."
Browse files Browse the repository at this point in the history
This reverts commit ab7e4fb.
  • Loading branch information
PaulTervoort committed Jan 17, 2023
1 parent ab7e4fb commit c26ad99
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 7 deletions.
4 changes: 2 additions & 2 deletions rosserial_rp2040/src/ros_lib/RP2040_Hardware_USB.h
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down
10 changes: 5 additions & 5 deletions rosserial_rp2040/src/ros_lib/ros.h
Original file line number Diff line number Diff line change
Expand Up @@ -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_<RP2040_Hardware_USB> NodeHandle;
#else
typedef ros::NodeHandle_<RP2040_Hardware> NodeHandle;
#endif
}

#endif
#endif

0 comments on commit c26ad99

Please sign in to comment.