80 "[image_transport] Topics '%s' and '%s' do not appear to be synchronized. " 82 "\tImage messages received: %d\n" 83 "\tCameraInfo messages received: %d\n" 84 "\tSynchronized pairs: %d",
101 const std::string& base_topic, uint32_t queue_size,
108 std::string image_topic = info_nh.
resolveName(base_topic);
110 impl_->image_sub_.subscribe(image_it, image_topic, queue_size, transport_hints);
111 impl_->info_sub_ .subscribe(info_nh, info_topic, queue_size, transport_hints.
getRosHints());
114 impl_->sync_.registerCallback(boost::bind(callback, _1, _2));
126 if (
impl_)
return impl_->image_sub_.getTopic();
127 return std::string();
132 if (
impl_)
return impl_->info_sub_.getTopic();
133 return std::string();
140 if (
impl_)
return impl_->image_sub_.getNumPublishers();
146 if (
impl_)
return impl_->image_sub_.getTransport();
147 return std::string();
155 CameraSubscriber::operator
void*()
const 157 return (
impl_ &&
impl_->isValid()) ? (
void*)1 : (
void*)0;
std::string getTopic() const
Image subscription filter.
std::string getInfoTopic() const
Get the camera info topic.
#define ROS_WARN_NAMED(name,...)
std::string resolveName(const std::string &name, bool remap=true) const
Impl(uint32_t queue_size)
std::string getTransport() const
Returns the name of the transport being used.
message_filters::Subscriber< sensor_msgs::CameraInfo > info_sub_
message_filters::TimeSynchronizer< sensor_msgs::Image, sensor_msgs::CameraInfo > sync_
WallTimer createWallTimer(WallDuration period, void(T::*callback)(const WallTimerEvent &), T *obj, bool oneshot=false, bool autostart=true) const
std::string getCameraInfoTopic(const std::string &base_topic)
Form the camera info topic name, sibling to the base topic.
ros::WallTimer check_synced_timer_
SubscriberFilter image_sub_
void shutdown()
Unsubscribe the callback associated with this CameraSubscriber.
boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)> Callback
Stores transport settings for an image topic subscription.
void unsubscribe()
Force immediate unsubscription of this subscriber from its topic.
uint32_t getNumPublishers() const
Returns the number of publishers this subscriber is connected to.
Advertise and subscribe to image topics.
std::string getTopic() const
Get the base topic (on which the raw image is published).
void checkImagesSynchronized()
const ros::TransportHints & getRosHints() const
std::string getTopic() const
void increment(int *value)