Skip to content

Commit

Permalink
Merge pull request #3 from MarcTestier/ros2-devel
Browse files Browse the repository at this point in the history
Minor update to ROS 2 Bouncy
  • Loading branch information
bponsler committed Jul 30, 2018
2 parents 857361c + b546ba6 commit af128a8
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 4 deletions.
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
cmake_minimum_required(VERSION 3.5)
project(laser_proc)

# Support C++11
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11")
# Support C++14
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14")

## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
Expand Down
2 changes: 1 addition & 1 deletion src/LaserProcNodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,6 @@ class LaserProcNodelet : public rclcpp::Node

//#include <pluginlib/class_list_macros.h>
//PLUGINLIB_DECLARE_CLASS(laser_proc, LaserProcNodelet, laser_proc::LaserProcNodelet, nodelet::Nodelet);
#include "class_loader/class_loader_register_macro.h"
#include "class_loader/register_macro.hpp"
CLASS_LOADER_REGISTER_CLASS(laser_proc::LaserProcNodelet, rclcpp::Node);

2 changes: 1 addition & 1 deletion src/LaserProcROS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ LaserProcROS::LaserProcROS(rclcpp::Node::SharedPtr n, rclcpp::Node::SharedPtr pn
pub_ = laser_proc::LaserTransport::advertiseLaser(n, 10);

std::function<void(sensor_msgs::msg::MultiEchoLaserScan::ConstSharedPtr)> callback = std::bind(&LaserProcROS::scanCb, this, std::placeholders::_1);
sub_ = n->create_subscription<sensor_msgs::msg::MultiEchoLaserScan>("echoes", 10, callback);
sub_ = n->create_subscription<sensor_msgs::msg::MultiEchoLaserScan>("echoes", callback, 10);
}

LaserProcROS::~LaserProcROS(){
Expand Down

0 comments on commit af128a8

Please sign in to comment.