roscpp message_filters Approximate Time - compiling error
Hi
I try to synchronize two topics with the Approximate Time class of the message_filters package. I started with the package-example code from the documentation and adapted it to my purpose. Here is my code
#include "ros/ros.h"
#include "std_msgs/String.h"
#include "stdio.h"
#include "sensor_msgs/Imu.h"
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
using namespace message_filters;
using namespace sensor_msgs;
void sync_cb(const Imu::ConstPtr& imuptr1, const Imu::ConstPtr& imuptr2){
ROS_INFO("Works!");
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "imu_error_detection_node");
static ros::NodeHandle nh;
//Time-Synchronizer
message_filters::Subscriber<Imu> imu_sync_1_sub(nh, "fcu1/mavros/imu/data",1);
message_filters::Subscriber<Imu> imu_sync_2_sub(nh, "fcu2/mavros/imu/data",1);
typedef sync_policies::ApproximateTime<Imu, Imu> MySyncPolicy;
Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), imu_sync_1_sub, imu_sync_2_sub);
sync.registerCallback(boost::bind(&sync_cb, _1, _2));
ros::spin();
return 0;
}
I get the following error.
CMakeFiles/imu_error_detection_node.dir/src/imu_error_detection_node.cpp.o:-1: In function `message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::Imu_<std::allocator<void> >, sensor_msgs::Imu_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType> >::disconnectAll()':
/opt/ros/kinetic/include/message_filters/synchronizer.h:351: error: undefined reference to `message_filters::Connection::disconnect()'
My CmakeLists.txt File looks like this (without outcommented lines):
cmake_minimum_required(VERSION 2.8.3)
project(px4_data_observer)
find_package(catkin REQUIRED COMPONENTS
roscpp
)
catkin_package(
)
include_directories(
# include
${catkin_INCLUDE_DIRS}
)
add_executable(imu_error_detection_node src/imu_error_detection_node.cpp)
target_link_libraries(imu_error_detection_node ${catkin_LIBRARIES})
add_dependencies(imu_error_detection_node PX4_data_observer_generate_messages_cpp)
I searched for a long time but I can not find the mistake. Do you have any ideas? Best regards and thank you in advice
The error you post appears to be a linker error, so including the snippet of code is good, but your
CMakeLists.txt
is more important in this case.Thx for the hint. I add my CMakeLists.txt-File