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

Hi, I want to use the message filter in this example , I tried to register callback from a class member function as in the following code:

asked 2019-12-30 00:05:54 -0500

Juan Carlos gravatar image
#include <sensor_msgs/LaserScan.h>
#include <nav_msgs/Odometry.h>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <ros/ros.h>

using namespace nav_msgs;
using namespace sensor_msgs;
using namespace message_filters;

class Data{

        public:
                void callback(const OdometryConstPtr& msg, const LaserScanConstPtr& dat);

        };

void Data::callback(const OdometryConstPtr& msg, const LaserScanConstPtr& dat){
        //pos1 = msg->pose.pose.orientation.w;
}

int main (int argc, char **argv){

        ros::init(argc, argv, "odome");
        ros::NodeHandle nh;

        message_filters::Subscriber<Odometry> odometria(nh, "/odom", 1);
        message_filters::Subscriber<LaserScan> laser(nh, "/scan", 1);

        Data data;

        TimeSynchronizer<Odometry, LaserScan> sync(odometria, laser, 10);
        sync.registerCallback(boost::bind(&Data::callback, &data,_1,_2));

        ros::spin();
        return 0;
}

and this its the error that show, sorry it's so long.

cd /home/juan/catkin_ws/build/gps_pos && /usr/bin/cmake -E cmake_link_script CMakeFiles/prueba.dir/link.txt --verbose=1
/usr/bin/c++   -O3 -DNDEBUG   CMakeFiles/prueba.dir/src/prueba.cpp.o  -o /home/juan/catkin_ws/devel/lib/gps_pos/prueba -rdynamic /opt/ros/kinetic/lib/libroscpp.so -lboost_filesystem -lboost_signals /opt/ros/kinetic/lib/librosconsole.so /opt/ros/kinetic/lib/librosconsole_log4cxx.so /opt/ros/kinetic/lib/librosconsole_backend_interface.so -llog4cxx -lboost_regex /opt/ros/kinetic/lib/libxmlrpcpp.so /opt/ros/kinetic/lib/libroscpp_serialization.so /opt/ros/kinetic/lib/librostime.so /opt/ros/kinetic/lib/libcpp_common.so -lboost_system -lboost_thread -lboost_chrono -lboost_date_time -lboost_atomic -lpthread -lconsole_bridge -Wl,-rpath,/opt/ros/kinetic/lib 
CMakeFiles/prueba.dir/src/prueba.cpp.o: En la función `message_filters::Connection message_filters::Signal9<nav_msgs::Odometry_<std::allocator<void> >, sensor_msgs::LaserScan_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>::addCallback<boost::shared_ptr<nav_msgs::Odometry_<std::allocator<void> > const> const&, boost::shared_ptr<sensor_msgs::LaserScan_<std::allocator<void> > const> const&, boost::shared_ptr<message_filters::NullType const> const&, boost::shared_ptr<message_filters::NullType const> const&, boost::shared_ptr<message_filters::NullType const> const&, boost::shared_ptr<message_filters::NullType const> const&, boost::shared_ptr<message_filters::NullType const> const&, boost::shared_ptr<message_filters::NullType const> const&, boost::shared_ptr<message_filters::NullType const> const&>(boost::function<void (boost::shared_ptr<nav_msgs::Odometry_<std::allocator<void> > const> const&, boost::shared_ptr<sensor_msgs::LaserScan_<std::allocator<void> > const> const&, boost::shared_ptr<message_filters::NullType const> const&, boost::shared_ptr<message_filters::NullType const> const&, boost::shared_ptr<message_filters::NullType const> const&, boost::shared_ptr<message_filters::NullType const> const&, boost::shared_ptr<message_filters::NullType const> const&, boost::shared_ptr<message_filters::NullType const> const&, boost::shared_ptr<message_filters::NullType const> const&)> const&)':
prueba.cpp:(.text._ZN15message_filters7Signal9IN8nav_msgs9Odometry_ISaIvEEEN11sensor_msgs10LaserScan_IS3_EENS_8NullTypeES8_S8_S8_S8_S8_S8_E11addCallbackIRKN5boost10shared_ptrIKS4_EERKNSC_IKS7_EERKNSC_IKS8_EESO_SO_SO_SO_SO_SO_EENS_10ConnectionERKNSB_8functionIFvT_T0_T1_T2_T3_T4_T5_T6_T7_EEE[_ZN15message_filters7Signal9IN8nav_msgs9Odometry_ISaIvEEEN11sensor_msgs10LaserScan_IS3_EENS_8NullTypeES8_S8_S8_S8_S8_S8_E11addCallbackIRKN5boost10shared_ptrIKS4_EERKNSC_IKS7_EERKNSC_IKS8_EESO_SO_SO_SO_SO_SO_EENS_10ConnectionERKNSB_8functionIFvT_T0_T1_T2_T3_T4_T5_T6_T7_EEE]+0x4d2): referencia a `message_filters::Connection::Connection(boost::function<void ()> const&)' sin definir
CMakeFiles/prueba.dir/src/prueba.cpp.o: En la función `message_filters::Synchronizer<message_filters::sync_policies::ExactTime<nav_msgs::Odometry_<std::allocator<void> >, sensor_msgs::LaserScan_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType> >::~Synchronizer()':
prueba.cpp:(.text._ZN15message_filters12SynchronizerINS_13sync_policies9ExactTimeIN8nav_msgs9Odometry_ISaIvEEEN11sensor_msgs10LaserScan_IS5_EENS_8NullTypeESA_SA_SA_SA_SA_SA_EEED2Ev[_ZN15message_filters12SynchronizerINS_13sync_policies9ExactTimeIN8nav_msgs9Odometry_ISaIvEEEN11sensor_msgs10LaserScan_IS5_EENS_8NullTypeESA_SA_SA_SA_SA_SA_EEED5Ev]+0x28): referencia a `message_filters::Connection::disconnect()' sin definir
CMakeFiles/prueba.dir/src/prueba.cpp.o: En la función `message_filters::Connection message_filters::SimpleFilter<nav_msgs::Odometry_<std::allocator<void> > >::registerCallback<ros::MessageEvent<nav_msgs::Odometry_<std::allocator<void> > const> const&>(boost::function<void (ros::MessageEvent<nav_msgs::Odometry_<std::allocator<void> > const> const&)> const&)':
prueba.cpp:(.text._ZN15message_filters12SimpleFilterIN8nav_msgs9Odometry_ISaIvEEEE16registerCallbackIRKN3ros12MessageEventIKS4_EEEENS_10ConnectionERKN5boost8functionIFvT_EEE[_ZN15message_filters12SimpleFilterIN8nav_msgs9Odometry_ISaIvEEEE16registerCallbackIRKN3ros12MessageEventIKS4_EEEENS_10ConnectionERKN5boost8functionIFvT_EEE]+0x310): referencia a `message_filters::Connection::Connection(boost::function<void ()> const&)' sin definir
CMakeFiles/prueba.dir/src/prueba.cpp.o: En la función `message_filters::Connection message_filters::SimpleFilter<sensor_msgs::LaserScan_<std::allocator<void> > >::registerCallback<ros::MessageEvent<sensor_msgs::LaserScan_<std::allocator<void> > const> const&> ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2019-12-31 08:07:11 -0500

Nikodem gravatar image

Are you sure that your CMakeLists.txt and package.xml are properly configured? I've tried compiling your code and it went completely fine (using "catkin build" command, ROS Kinetic).

In package.xml you should have "depend" fields for all needed packages.

My CMakeLists:

cmake_minimum_required(VERSION 2.8.3)
project(message_filtering)

find_package(catkin REQUIRED COMPONENTS
  message_filters
  nav_msgs
  roscpp
  sensor_msgs
)


catkin_package(
)

## Build ##

include_directories(
# include
  ${catkin_INCLUDE_DIRS}
)

 add_executable(filtering src/filtering.cpp)

 target_link_libraries(filtering
   ${catkin_LIBRARIES}
 )
edit flag offensive delete link more

Comments

Thanks you!, you are correct, forgot the nav_msgs in the CMakelist, thaks

Juan Carlos gravatar image Juan Carlos  ( 2020-01-03 18:44:24 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2019-12-30 00:05:06 -0500

Seen: 905 times

Last updated: Dec 31 '19