00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <boost/algorithm/string/erase.hpp>
00031 #include <boost/foreach.hpp>
00032 #include <boost/shared_ptr.hpp>
00033
00034 #include <pluginlib/class_loader.h>
00035
00036 #include <image_transport/subscriber_plugin.h>
00037
00038 #include "rviz/validate_floats.h"
00039
00040 #include "rviz/image/image_display_base.h"
00041
00042 namespace rviz
00043 {
00044
00045 ImageDisplayBase::ImageDisplayBase() :
00046 Display()
00047 , it_(update_nh_)
00048 , sub_()
00049 , tf_filter_()
00050 , messages_received_(0)
00051 {
00052 topic_property_ = new RosTopicProperty("Image Topic", "",
00053 QString::fromStdString(ros::message_traits::datatype<sensor_msgs::Image>()),
00054 "sensor_msgs::Image topic to subscribe to.", this, SLOT( updateTopic() ));
00055
00056 transport_property_ = new EnumProperty("Transport Hint", "raw", "Preferred method of sending images.", this,
00057 SLOT( updateTopic() ));
00058
00059 connect(transport_property_, SIGNAL( requestOptions( EnumProperty* )), this,
00060 SLOT( fillTransportOptionList( EnumProperty* )));
00061
00062 queue_size_property_ = new IntProperty( "Queue Size", 2,
00063 "Advanced: set the size of the incoming message queue. Increasing this "
00064 "is useful if your incoming TF data is delayed significantly from your"
00065 " image data, but it can greatly increase memory usage if the messages are big.",
00066 this, SLOT( updateQueueSize() ));
00067 queue_size_property_->setMin( 1 );
00068
00069 transport_property_->setStdString("raw");
00070
00071 scanForTransportSubscriberPlugins();
00072
00073 }
00074
00075 ImageDisplayBase::~ImageDisplayBase()
00076 {
00077 unsubscribe();
00078 }
00079
00080 void ImageDisplayBase::incomingMessage(const sensor_msgs::Image::ConstPtr& msg)
00081 {
00082 if (!msg || context_->getFrameManager()->getPause() )
00083 {
00084 return;
00085 }
00086
00087 ++messages_received_;
00088 setStatus(StatusProperty::Ok, "Image", QString::number(messages_received_) + " images received");
00089
00090 emitTimeSignal( msg->header.stamp );
00091
00092 processMessage(msg);
00093 }
00094
00095
00096 void ImageDisplayBase::reset()
00097 {
00098 Display::reset();
00099 if (tf_filter_)
00100 tf_filter_->clear();
00101 messages_received_ = 0;
00102 }
00103
00104 void ImageDisplayBase::updateQueueSize()
00105 {
00106 uint32_t size = queue_size_property_->getInt();
00107 if (tf_filter_)
00108 tf_filter_->setQueueSize(size);
00109 }
00110
00111 void ImageDisplayBase::subscribe()
00112 {
00113 if (!isEnabled())
00114 {
00115 return;
00116 }
00117
00118 try
00119 {
00120
00121 tf_filter_.reset();
00122
00123 sub_.reset(new image_transport::SubscriberFilter());
00124
00125 if (!topic_property_->getTopicStd().empty() && !transport_property_->getStdString().empty() )
00126 {
00127 sub_->subscribe(it_, topic_property_->getTopicStd(), (uint32_t)queue_size_property_->getInt(),
00128 image_transport::TransportHints(transport_property_->getStdString()));
00129
00130 if (targetFrame_.empty())
00131 {
00132 sub_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, _1));
00133 }
00134 else
00135 {
00136 tf_filter_.reset( new tf::MessageFilter<sensor_msgs::Image>(*sub_, (tf::Transformer&)*(context_->getTFClient()), targetFrame_, (uint32_t)queue_size_property_->getInt(), update_nh_));
00137 tf_filter_->registerCallback(boost::bind(&ImageDisplayBase::incomingMessage, this, _1));
00138 }
00139 }
00140 setStatus(StatusProperty::Ok, "Topic", "OK");
00141 }
00142 catch (ros::Exception& e)
00143 {
00144 setStatus(StatusProperty::Error, "Topic", QString("Error subscribing: ") + e.what());
00145 }
00146 catch (image_transport::Exception& e)
00147 {
00148 setStatus( StatusProperty::Error, "Topic", QString("Error subscribing: ") + e.what());
00149 }
00150
00151 messages_received_ = 0;
00152 setStatus(StatusProperty::Warn, "Image", "No Image received");
00153 }
00154
00155 void ImageDisplayBase::unsubscribe()
00156 {
00157 tf_filter_.reset();
00158 sub_.reset(new image_transport::SubscriberFilter());
00159 }
00160
00161 void ImageDisplayBase::fixedFrameChanged()
00162 {
00163 if (tf_filter_)
00164 {
00165 tf_filter_->setTargetFrame(fixed_frame_.toStdString());
00166 reset();
00167 }
00168 }
00169
00170 void ImageDisplayBase::scanForTransportSubscriberPlugins()
00171 {
00172 pluginlib::ClassLoader<image_transport::SubscriberPlugin> sub_loader("image_transport",
00173 "image_transport::SubscriberPlugin");
00174
00175 BOOST_FOREACH( const std::string& lookup_name, sub_loader.getDeclaredClasses() )
00176 {
00177
00178
00179
00180
00181
00182 std::string transport_name = boost::erase_last_copy(lookup_name, "_sub");
00183 transport_name = transport_name.substr(lookup_name.find('/') + 1);
00184
00185
00186
00187
00188 try
00189 {
00190 boost::shared_ptr<image_transport::SubscriberPlugin> sub = sub_loader.createInstance(lookup_name);
00191 transport_plugin_types_.insert(transport_name);
00192 }
00193 catch (const pluginlib::LibraryLoadException& e)
00194 {
00195 }
00196 catch (const pluginlib::CreateClassException& e)
00197 {
00198 }
00199 }
00200 }
00201
00202 void ImageDisplayBase::updateTopic()
00203 {
00204 unsubscribe();
00205 reset();
00206 subscribe();
00207 context_->queueRender();
00208 }
00209
00210 void ImageDisplayBase::fillTransportOptionList(EnumProperty* property)
00211 {
00212 property->clearOptions();
00213
00214 std::vector<std::string> choices;
00215
00216 choices.push_back("raw");
00217
00218
00219 ros::master::V_TopicInfo topics;
00220 ros::master::getTopics(topics);
00221 ros::master::V_TopicInfo::iterator it = topics.begin();
00222 ros::master::V_TopicInfo::iterator end = topics.end();
00223 for (; it != end; ++it)
00224 {
00225
00226
00227
00228
00229
00230 const ros::master::TopicInfo& ti = *it;
00231 const std::string& topic_name = ti.name;
00232 const std::string& topic = topic_property_->getStdString();
00233
00234 if (topic_name.find(topic) == 0 && topic_name != topic && topic_name[topic.size()] == '/'
00235 && topic_name.find('/', topic.size() + 1) == std::string::npos)
00236 {
00237 std::string transport_type = topic_name.substr(topic.size() + 1);
00238
00239
00240
00241 if (transport_plugin_types_.find(transport_type) != transport_plugin_types_.end())
00242 {
00243 choices.push_back(transport_type);
00244 }
00245 }
00246 }
00247
00248 for (size_t i = 0; i < choices.size(); i++)
00249 {
00250 property->addOptionStd(choices[i]);
00251 }
00252 }
00253
00254 }