[Documentation] [TitleIndex] [WordIndex

  Show EOL distros: 

ros_comm: cpp_common | message_filters | perf_roscpp | rosbag | rosbagmigration | rosconsole | roscore_migration_rules | roscpp | roscpp_serialization | roscpp_traits | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostime | rostopic | roswtf | std_msgs | std_srvs | topic_tools | xmlrpcpp

Package Summary

A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.

ros_comm: message_filters | perf_roscpp | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

Package Summary

A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.

ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

Package Summary

A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.

  • Maintainer status: maintained
  • Maintainer: Dirk Thomas <dthomas AT osrfoundation DOT org>
  • Author: Josh Faust, Vijay Pradeep
  • License: BSD
  • Source: git https://github.com/ros/ros_comm.git (branch: groovy-devel)
ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

Package Summary

A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.

  • Maintainer status: maintained
  • Maintainer: Dirk Thomas <dthomas AT osrfoundation DOT org>
  • Author: Josh Faust, Vijay Pradeep
  • License: BSD
  • Source: git https://github.com/ros/ros_comm.git (branch: hydro-devel)
ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

Package Summary

A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.

  • Maintainer status: maintained
  • Maintainer: Dirk Thomas <dthomas AT osrfoundation DOT org>
  • Author: Josh Faust, Vijay Pradeep
  • License: BSD
  • Source: git https://github.com/ros/ros_comm.git (branch: indigo-devel)
ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

Package Summary

A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.

  • Maintainer status: maintained
  • Maintainer: Jacob Perron <jacob AT openrobotics DOT org>, Michael Carroll <michael AT openrobotics DOT org>, Shane Loretz <sloretz AT openrobotics DOT org>
  • Author: Josh Faust, Vijay Pradeep, Dirk Thomas <dthomas AT osrfoundation DOT org>
  • License: BSD
  • Source: git https://github.com/ros/ros_comm.git (branch: kinetic-devel)
ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

Package Summary

A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.

  • Maintainer status: maintained
  • Maintainer: Jacob Perron <jacob AT openrobotics DOT org>, Michael Carroll <michael AT openrobotics DOT org>, Shane Loretz <sloretz AT openrobotics DOT org>
  • Author: Josh Faust, Vijay Pradeep, Dirk Thomas <dthomas AT osrfoundation DOT org>
  • License: BSD
  • Source: git https://github.com/ros/ros_comm.git (branch: melodic-devel)
ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

Package Summary

A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.

  • Maintainer status: maintained
  • Maintainer: Michael Carroll <michael AT openrobotics DOT org>, Shane Loretz <sloretz AT openrobotics DOT org>
  • Author: Josh Faust, Vijay Pradeep, Dirk Thomas <dthomas AT osrfoundation DOT org>, Jacob Perron <jacob AT openrobotics DOT org>
  • License: BSD
  • Source: git https://github.com/ros/ros_comm.git (branch: noetic-devel)

Overview

message_filtersroscpprospy와 함께 사용하기 위한 유틸리티 라이브러리입니다. 일반적으로 사용되는 메시지 "필터링" 알고리즘으로 동 시간대 메시지를 수집합니다. 메시지 필터는 메시지가 도착하여 나중에 다시 사용될 수 있거나 사용 될 수 없는 것이 있습니다.

한 예시로, time synchronizer는 여러 자원에서 서로 다른 유형의 메시지를 수신하고, 동일한 타임스탬프로 각 자원에서 메시지를 수신한 경우에만 출력합니다.

Filter Pattern

모든 메시지 필터는 입력과 출력을 연결하기 위해 동일한 패턴을 사용합니다. 입력은 filter 생성자나connectInput()를 통해 연결하고, 출력은 registerCallback() 메소드를 통해 연결합니다. 입력 및 출력 유형은 필터별로 정의되므로 모든 필터가 직접 상호 연결될 수 있는 것은 아닙니다.

예를 들어 FooFilter의 출력이 BarFilter의 입력으로 들어가는 경우 두 필터 foo와 bar의 연결은 다음과 같습니다(C++):

   1 FooFilter foo;
   2 BarFilter bar(foo);

or:

   1 FooFilter foo;
   2 BarFilter bar;
   3 bar.connectInput(foo);

in Python:

   1 bar(foo)

   1 bar.connectInput(foo)

bar의 출려은 callback 함수에 다음과 같이 연결할 수 있습니다:

   1 bar.registerCallback(myCallback);

The signature of myCallback is dependent on the definition of BarFilter.

registerCallback()

RegisterCallbacks() 메소드를 사용하면 여러개의 callback을 사용할 수 있습니다. callback은 나열된 순서대로 호출 됩니다. C++

Subscriber

See also: C++ message_filters::Subscriber API docs Python message_filters.Subscriber

Subscriber filter 는 단순히 다른 filter에 자원을 제공하는 ROS subscription을 감싼 것입니다. Subscriber filter는 다른 filter의 출력에 연결할 수 없으며, ROS topic을 입력으로 사용합니다.

Connections

Input

Output

Example (C++)

   1 message_filters::Subscriber<std_msgs::UInt32> sub(nh, "my_topic", 1);
   2 sub.registerCallback(myCallback);

위 코드는 아래와 같이 쓸 수 있습니다:

   1 ros::Subscriber sub = nh.subscribe("my_topic", 1, myCallback);

Example (Python)

   1 sub = message_filters.Subscriber("pose_topic", robot_msgs.msg.Pose)
   2 sub.registerCallback(myCallback)

Time Synchronizer

See also: C++ message_filters::TimeSynchronizer API docs, Python message_filters.TimeSynchronizer

TimeSynchronizer filter는 수신 채널을 헤더에 포함된 타임스탬프로 동기화하여 동일한 수의 채널을 사용하는 단일 콜백 형태로 출력합니다. C++에서는 최대 9개의 채널을 동기화할 수 있도록 구현되었습니다.

Connections

Input

Output

Example (C++)

다음은 동기화 된 두 topic을 처리하는 ROS node입니다:

   1 #include <message_filters/subscriber.h>
   2 #include <message_filters/time_synchronizer.h>
   3 #include <sensor_msgs/Image.h>
   4 #include <sensor_msgs/CameraInfo.h>
   5 
   6 using namespace sensor_msgs;
   7 using namespace message_filters;
   8 
   9 void callback(const ImageConstPtr& image, const CameraInfoConstPtr& cam_info)
  10 {
  11   // Solve all of perception here...
  12 }
  13 
  14 int main(int argc, char** argv)
  15 {
  16   ros::init(argc, argv, "vision_node");
  17 
  18   ros::NodeHandle nh;
  19 
  20   message_filters::Subscriber<Image> image_sub(nh, "image", 1);
  21   message_filters::Subscriber<CameraInfo> info_sub(nh, "camera_info", 1);
  22   TimeSynchronizer<Image, CameraInfo> sync(image_sub, info_sub, 10);
  23   sync.registerCallback(boost::bind(&callback, _1, _2));
  24 
  25   ros::spin();
  26 
  27   return 0;
  28 }

(Note: In this particular case you could use the CameraSubscriber class from image_transport, which essentially wraps the filtering code above.)

Example (Python)

   1 import message_filters
   2 from sensor_msgs.msg import Image, CameraInfo
   3 
   4 def callback(image, camera_info):
   5   # Solve all of perception here...
   6 
   7 image_sub = message_filters.Subscriber('image', Image)
   8 info_sub = message_filters.Subscriber('camera_info', CameraInfo)
   9 
  10 ts = message_filters.TimeSynchronizer([image_sub, info_sub], 10)
  11 ts.registerCallback(callback)
  12 rospy.spin()

Time Sequencer

See also: C++ message_filters::TimeSequencer API docs

Python: 아직 TimeSequencer filter가 구현되지 않았음.

Time Sequencer filter는 헤더의 타임스탬프에 따라 메시지가 시간 순서대로 호출되도록 보장합니다. TimeSquencer는 메시지를 전달하기 전에 대기하는 지연 시간을 지정해, 메시지 callback에서 이 지연 시간 동안 메시지의 타임스탬프가 만료될 때까지 호출하지 않습니다. 그러나 적어도 지연시간이 만료된 메시지에 대해 callback을 호출하여 시간적 순서를 보장합니다. callback을 이미 호출한 메시지 이전에 메시지가 도착하면, 이 메시지를 버립니다.

Connections

Input

Output

Example (C++)

C++ 버전은 둘 다 update rate과 delay를 채택합니다. update rate은 sequencer가 전달될 준비가 된 메시지를 대기열에서 확인하는 빈도를 결정한다. 마지막 파라미터는 만료된 메시지드를 버리기 시작하기 전에 대기할 메시지의 수입니다.

   1 message_filters::Subscriber<std_msgs::String> sub(nh, "my_topic", 1);
   2 message_filters::TimeSequencer<std_msgs::String> seq(sub, ros::Duration(0.1), ros::Duration(0.01), 10);
   3 seq.registerCallback(myCallback);

Cache

See also: C++ message_filters::Cache API docs Python message_filters.Cache

message들의 time history를 보관합니다.

메시지 스트림을 고려해 가장 최근의 N개의 메시지는 링 버퍼에 캐시되며 이때부터 캐시의 시간 간격은 클라이언트에 의해 검색할 수 있습니다. 메시지의 타임스탬프는 header필드에서 결정됩니다.

메시지 유형에 헤더가 포함되어 있지 않으면, 캐시는 즉시 메시지를 출력 연결로 전달합니다.

Connections

Input

Output

In C++:

   1 message_filters::Subscriber<std_msgs::String> sub(nh, "my_topic", 1);
   2 message_filters::Cache<std_msgs::String> cache(sub, 100);
   3 cache.registerCallback(myCallback);

In Python:

   1 sub = message_filters.Subscriber('my_topic', sensor_msgs.msg.Image)
   2 cache = message_filters.Cache(sub, 100)

In this example, the Cache stores the last 100 messages received on my_topic, and myCallback is called on the addition of every new message. The user can then make calls like cache.getInterval(start, end) to extract part of the cache.

이 예에서 캐쉬는 my_topic에서 받은 마지막 100개의 메시지를 저장하고, my_callback은 각각의 새로운 메시지를 추가할 때마다 호출됩다. 사용자는 캐시의 일부를 추출하기 위해 "cache.getInterval(start, end)"와 같은 호출을 할 수 있습니다.

메시지 타입에 일반적으로 타임스탬프를 결정하는 데 사용되는 헤더 필드가 없고 "allow_headerless="로 구성된 경우사실 현재 ROS 시간이 메시지의 타임스탬프로 사용됩니다. 이는 현재 Python에서만 이용 가능합니다.

   1 sub = message_filters.Subscriber('my_int_topic', std_msgs.msg.Int32)
   2 cache = message_filters.Cache(sub, 100, allow_headerless=True)
   3 # the cache assigns current ROS time as each message's timestamp

Policy-Based Synchronizer [ROS 1.1+]

Synchronizer filter는 들어오는 채널들을 그들의 header에 있는 timestamps를 가지고 동기화하여, 같은 개수의 채널을 갖는 하나의 callback 함수에 출력합니다. C++은 최대 9개의 채널을 동기화할 수 있도록 구현되어있습니다.

Synchronizer filter는 채널을 동기화하는 policy에 따라 양식화 되었있습니다. 현재에는 두가지 policy:ExactTimeApproximateTime가 있습니다.

C++ Header: message_filters/synchronizer.h

Connections

Input

Output

ExactTime Policy

The message_filters::sync_policies::ExactTime policy requires messages to have exactly the same timestamp in order to match. Your callback is only called if a message has been received on all specified channels with the same exact timestamp. The timestamp is read from the header field of all messages (which is required for this policy).

C++ Header: message_filters/sync_policies/exact_time.h

Example (C++)

   1 #include <message_filters/subscriber.h>
   2 #include <message_filters/synchronizer.h>
   3 #include <message_filters/sync_policies/exact_time.h>
   4 #include <sensor_msgs/Image.h>
   5 #include <sensor_msgs/CameraInfo.h>
   6 
   7 using namespace sensor_msgs;
   8 using namespace message_filters;
   9 
  10 void callback(const ImageConstPtr& image, const CameraInfoConstPtr& cam_info)
  11 {
  12   // Solve all of perception here...
  13 }
  14 
  15 int main(int argc, char** argv)
  16 {
  17   ros::init(argc, argv, "vision_node");
  18 
  19   ros::NodeHandle nh;
  20   message_filters::Subscriber<Image> image_sub(nh, "image", 1);
  21   message_filters::Subscriber<CameraInfo> info_sub(nh, "camera_info", 1);
  22 
  23   typedef sync_policies::ExactTime<Image, CameraInfo> MySyncPolicy;
  24   // ExactTime takes a queue size as its constructor argument, hence MySyncPolicy(10)
  25   Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), image_sub, info_sub);
  26   sync.registerCallback(boost::bind(&callback, _1, _2));
  27 
  28   ros::spin();
  29 
  30   return 0;
  31 }

ApproximateTime Policy

The message_filters::sync_policies::ApproximateTime policy uses an adaptive algorithm to match messages based on their timestamp.

The timestamp is determined from the header field of the message (which is required).

If not all messages have a header field from which the timestamp could be determined, see below for a workaround.

C++ Header: message_filters/sync_policies/approximate_time.h

Example (C++)

   1 #include <message_filters/subscriber.h>
   2 #include <message_filters/synchronizer.h>
   3 #include <message_filters/sync_policies/approximate_time.h>
   4 #include <sensor_msgs/Image.h>
   5 
   6 using namespace sensor_msgs;
   7 using namespace message_filters;
   8 
   9 void callback(const ImageConstPtr& image1, const ImageConstPtr& image2)
  10 {
  11   // Solve all of perception here...
  12 }
  13 
  14 int main(int argc, char** argv)
  15 {
  16   ros::init(argc, argv, "vision_node");
  17 
  18   ros::NodeHandle nh;
  19   message_filters::Subscriber<Image> image1_sub(nh, "image1", 1);
  20   message_filters::Subscriber<Image> image2_sub(nh, "image2", 1);
  21 
  22   typedef sync_policies::ApproximateTime<Image, Image> MySyncPolicy;
  23   // ApproximateTime takes a queue size as its constructor argument, hence MySyncPolicy(10)
  24   Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), image1_sub, image2_sub);
  25   sync.registerCallback(boost::bind(&callback, _1, _2));
  26 
  27   ros::spin();
  28 
  29   return 0;
  30 }

If some messages are of a type that doesn't contain the header field, ApproximateTimeSynchronizer refuses by default adding such messages. However, its Python version can be constructed with allow_headerless=True, which uses current ROS time in place of any missing header.stamp field:

   1 import message_filters
   2 from std_msgs.msg import Int32, Float32
   3 
   4 def callback(mode, penalty):
   5   # The callback processing the pairs of numbers that arrived at approximately the same time
   6 
   7 mode_sub = message_filters.Subscriber('mode', Int32)
   8 penalty_sub = message_filters.Subscriber('penalty', Float32)
   9 
  10 ts = message_filters.ApproximateTimeSynchronizer([mode_sub, penalty_sub], 10, 0.1, allow_headerless=True)
  11 ts.registerCallback(callback)
  12 rospy.spin()

Chain [ROS 1.1+]

See also: C++ API Docs

The Chain filter allows you to dynamically chain together multiple single-input/single-output (simple) filters. As filters are added to it they are automatically connected together in the order they were added. It also allows you to retrieve added filters by index.

Chain is most useful for cases where you want to determine which filters to apply at runtime rather than compile-time.

Connections

Input

Output

Examples (C++)

Simple Example

   1 void myCallback(const MsgConstPtr& msg)
   2 {
   3 }
   4 
   5 Chain<Msg> c;
   6 c.addFilter(boost::shared_ptr<Subscriber<Msg> >(new Subscriber<Msg>));
   7 c.addFilter(boost::shared_ptr<TimeSequencer<Msg> >(new TimeSequencer<Msg>));
   8 c.registerCallback(myCallback);

Bare Pointers

It is possible to pass bare pointers in. These will not be automatically deleted when Chain is destructed.

   1 Chain<Msg> c;
   2 Subscriber<Msg> s;
   3 c.addFilter(&s);
   4 c.registerCallback(myCallback);

Retrieving a Filter

   1 Chain<Msg> c;
   2 size_t sub_index = c.addFilter(boost::shared_ptr<Subscriber<Msg> >(new Subscriber<Msg>));
   3 
   4 boost::shared_ptr<Subscriber<Msg> > sub = c.getFilter<Subscriber<Msg> >(sub_index);


2023-10-28 12:44