35 #ifndef ROSBAG_BAG_PLAYER_H 36 #define ROSBAG_BAG_PLAYER_H 57 typedef boost::function<void (const boost::shared_ptr<const T>&)>
Callback;
75 typedef boost::function<void (const MessageInstance&)>
Callback;
100 void register_callback(
const std::string &topic,
104 void unregister_callback(
const std::string &topic);
116 void set_playback_speed(
double scale);
135 std::map<std::string, boost::shared_ptr<BagCallback> >
cbs_;
146 cbs_[topic] = boost::make_shared<BagCallbackT<T> >(cb);
virtual void call(MessageInstance m)=0
BagCallbackT(Callback cb)
#define ROSBAG_STORAGE_DECL
boost::function< void(const boost::shared_ptr< const T > &)> Callback
std::map< std::string, boost::shared_ptr< BagCallback > > cbs_
boost::function< void(const MessageInstance &)> Callback
BagCallbackT(Callback cb)
void register_callback(const std::string &topic, typename BagCallbackT< T >::Callback f)
void call(MessageInstance m)
ros::Time last_message_time_
A class pointing into a bag file.
void call(MessageInstance m)
boost::shared_ptr< T > instantiate() const
Templated call to instantiate a message.