Skip to content

Instantly share code, notes, and snippets.

@tdenewiler
Last active February 14, 2024 08:30
Show Gist options
  • Save tdenewiler/e2172f628e49ab633ef2786207793336 to your computer and use it in GitHub Desktop.
Save tdenewiler/e2172f628e49ab633ef2786207793336 to your computer and use it in GitHub Desktop.
ROS Synchronization Example
cmake_minimum_required(VERSION 2.8.3)
project(sync_example)
find_package(catkin REQUIRED COMPONENTS message_filters roscpp sensor_msgs)
catkin_package(
CATKIN_DEPENDS message_filters roscpp sensor_msgs
)
include_directories(${catkin_INCLUDE_DIRS})
add_executable(sync_example src/sync_example.cpp)
target_link_libraries(sync_example ${catkin_LIBRARIES})
<package format="2">
<name>sync_example</name>
<version>0.0.1</version>
<description>
Approximate time sync example.
</description>
<author>Thomas Denewiler</author>
<maintainer email="tdenewiler@gmail.com">Thomas Denewiler</maintainer>
<license>BSD</license>
<url>https://github.com/tdenewiler/sync_example</url>
<buildtool_depend>catkin</buildtool_depend>
<depend>message_filters</depend>
<depend>roscpp</depend>
<depend>sensor_msgs</depend>
</package>
#include <ros/ros.h>
#include <sensor_msgs/Image.h>
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
class Node
{
public:
Node()
{
sub_1_.subscribe(nh_, "in1", 1);
sub_2_.subscribe(nh_, "in2", 1);
sync_.reset(new Sync(MySyncPolicy(10), sub_1_, sub_2_));
sync_->registerCallback(boost::bind(&Node::callback, this, _1, _2));
}
void callback(const sensor_msgs::ImageConstPtr &in1, const sensor_msgs::ImageConstPtr &in2)
{
ROS_INFO("Synchronization successful");
}
private:
ros::NodeHandle nh_;
message_filters::Subscriber<sensor_msgs::Image> sub_1_;
message_filters::Subscriber<sensor_msgs::Image> sub_2_;
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> MySyncPolicy;
typedef message_filters::Synchronizer<MySyncPolicy> Sync;
boost::shared_ptr<Sync> sync_;
};
int main(int argc, char **argv)
{
ros::init(argc, argv, "synchronizer");
Node synchronizer;
ros::spin();
}
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment