ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

error: ‘_1’ was not declared in this scope

asked 2020-09-05 11:14:38 -0500

mirella melo gravatar image

updated 2020-09-05 19:30:03 -0500

Hi.

I'm trying to use boost bind in my ROS 2 package. But I'm getting the following error when building with Colcon build:

error:‘_1’ was not declared in this scope

error:‘ _2’ was not declared in this scope

Here is my C++ code:

 #include <functional>
 #include <memory>
 #include "rclcpp/rclcpp.hpp"
 #include "std_msgs/msg/string.hpp"
 #include <message_filters/subscriber.h>
 #include <message_filters/synchronizer.h>
 #include <message_filters/sync_policies/approximate_time.h>
 #include <message_filters/time_synchronizer.h>
 #include "boost/bind/bind.hpp"
 #include <functional>

 void callback(const std_msgs::msg::String::SharedPtr& st_1, 
      const std_msgs::msg::String::SharedPtr& st_2) {
         // Callback function...
 }

 int main(int argc, char** argv){
     rclcpp::init(argc, argv);
     auto node = rclcpp::Node::make_shared("my_node");

     message_filters::Subscriber<std_msgs::msg::String> st_1(node, "st_1");
     message_filters::Subscriber<std_msgs::msg::String> st_2(node, "st_2");
     message_filters::TimeSynchronizer<std_msgs::msg::String, std_msgs::msg::String> sync(st_1, st_2, 10);
     sync.registerCallback(boost::bind(&callback, _1, _2));

    rclcpp::spin(node);

    return 0;
 }

CMakeFile:

 cmake_minimum_required(VERSION 3.5)
 project(project)

 # Default to C99
 if(NOT CMAKE_C_STANDARD)
     set(CMAKE_C_STANDARD 99)
 endif()

 # Default to C++14
 if(NOT CMAKE_CXX_STANDARD)
    set(CMAKE_CXX_STANDARD 14)
 endif()

 if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
      add_compile_options(-Wall -Wextra -Wpedantic)
 endif()

 # find dependencies
 find_package(ament_cmake REQUIRED)
 find_package(rclcpp REQUIRED)
 find_package(std_msgs REQUIRED)
 find_package(message_filters REQUIRED)
 find_package(Boost REQUIRED COMPONENTS 
      system
      filesystem 
      date_time 
      thread
 )

 if(BUILD_TESTING)
     find_package(ament_lint_auto REQUIRED)
     ament_lint_auto_find_test_dependencies()
 endif()

 add_executable(sub src/subscriber.cpp)
 ament_target_dependencies(sub rclcpp std_msgs message_filters)
 target_include_directories(sub PRIVATE ${Boost_INCLUDE_DIRS})
 target_link_libraries(sub ${Boost_LIBRARIES})

 install(TARGETS
     sub
 DESTINATION lib/${PROJECT_NAME})

 ament_package()

Any help is welcome! Thanks!

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
0

answered 2020-09-06 13:09:00 -0500

mirella melo gravatar image

updated 2020-09-06 13:09:39 -0500

As follows the changes I did in order to make it work:

Callback function:

  void callback(const std::shared_ptr<const std_msgs::msg::String_<std::allocator<void>>>& st_1,
               const std::shared_ptr<const std_msgs::msg::String_<std::allocator<void>>>& st_2){
  }

Main funcion:

   sync.registerCallback(boost::bind(&callback, boost::placeholders::_1, boost::placeholders::_2));
edit flag offensive delete link more
2

answered 2020-09-06 07:17:13 -0500

updated 2020-09-06 07:18:39 -0500

You can use std::placeholders::_1. Reference: https://en.cppreference.com/w/cpp/uti....

This wasn't specifically asked, but will throw it out there anyway. In place of boost::bind(), you can use std::bind()

edit flag offensive delete link more

Comments

Thank you for answering me! Instead of using std, I kept with bind (I had tried your suggestion, but the usage is slightly different, got me confused, and I had new errors). Finally, I had some success with that. I'll let it as an answer as well. What is confusing me now is that:

const std_msgs::msg::String::SharedPtr& supposed to be the same as

const std::shared_ptr<std_msgs::msg::String_<std::allocator<void>>>&

But the callback function only works with this extra 'const':

const std::shared_ptr<const std_msgs::msg::String_<std::allocator<void>>>&

Trying to figure out this... Thanks once more!

mirella melo gravatar image mirella melo  ( 2020-09-06 13:05:40 -0500 )edit

Sorry, I should have been more complete in my answer. Out of curiosity, why do you want to use the boost library when this particular case can all be completed using the standard library?

surfertas gravatar image surfertas  ( 2020-09-06 18:26:24 -0500 )edit

There is no specific reason... I was just following the tutorials. But after looking further, I found some differences between them here.

mirella melo gravatar image mirella melo  ( 2020-09-07 15:15:35 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2020-09-05 11:14:38 -0500

Seen: 3,537 times

Last updated: Sep 06 '20