Skip to content

Commit

Permalink
Expose the driver core as a ROS 2 component
Browse files Browse the repository at this point in the history
  • Loading branch information
cottsay committed Oct 23, 2019
1 parent 59d4134 commit 9cf9620
Show file tree
Hide file tree
Showing 5 changed files with 27 additions and 1 deletion.
6 changes: 6 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ find_package(ament_cmake REQUIRED)
find_package(diagnostic_msgs REQUIRED)
find_package(lifecycle_msgs REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(serial REQUIRED)
Expand All @@ -35,11 +36,16 @@ ament_target_dependencies(
"diagnostic_msgs"
"lifecycle_msgs"
"rclcpp"
"rclcpp_components"
"rclcpp_lifecycle"
"sensor_msgs"
"serial"
)

if(BUILD_SHARED_LIBS)
rclcpp_components_register_nodes(bno055 "bno055_driver::BNO055Driver")
endif()

# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(bno055 PRIVATE "BNO055_DRIVER_BUILDING_LIBRARY")
Expand Down
5 changes: 5 additions & 0 deletions include/bno055_driver/bno055_driver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,11 @@ namespace bno055_driver
class BNO055Driver : public rclcpp_lifecycle::LifecycleNode
{
public:
BNO055Driver();

BNO055_DRIVER_PUBLIC
explicit BNO055Driver(const rclcpp::NodeOptions & options);

explicit BNO055Driver(
const std::string & node_name, const rclcpp::NodeOptions & options = rclcpp::NodeOptions());

Expand Down
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
<depend>diagnostic_msgs</depend>
<depend>lifecycle_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>rclcpp_lifecycle</depend>
<depend>sensor_msgs</depend>
<depend>serial</depend>
Expand Down
14 changes: 14 additions & 0 deletions src/bno055_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,12 +19,26 @@
#include <string>
#include <vector>

#include "rclcpp_components/register_node_macro.hpp"

#define bytes_to_ushort(addr) (*reinterpret_cast<uint16_t *>(addr))
#define bytes_to_short(addr) (*reinterpret_cast<int16_t *>(addr))

RCLCPP_COMPONENTS_REGISTER_NODE(bno055_driver::BNO055Driver)

namespace bno055_driver
{

BNO055Driver::BNO055Driver()
: BNO055Driver("bno055_driver")
{
}

BNO055Driver::BNO055Driver(const rclcpp::NodeOptions & options)
: BNO055Driver("bno055_driver", options)
{
}

BNO055Driver::BNO055Driver(const std::string & node_name, const rclcpp::NodeOptions & options)
: rclcpp_lifecycle::LifecycleNode(node_name, options),
connection_rate_(4.0)
Expand Down
2 changes: 1 addition & 1 deletion src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ int main(int argc, char * argv[])
rclcpp::executors::SingleThreadedExecutor exe;

std::shared_ptr<bno055_driver::BNO055Driver> bno_node =
std::make_shared<bno055_driver::BNO055Driver>("bno055_driver");
std::make_shared<bno055_driver::BNO055Driver>();

exe.add_node(bno_node->get_node_base_interface());

Expand Down

0 comments on commit 9cf9620

Please sign in to comment.