10 #include <QProgressDialog> 12 #include <QApplication> 16 #include <QFileDialog> 28 , _action_saveIntoRosbag(
nullptr)
46 _action_saveAny =
new QAction(QString(
"Store messages in memory for Re-publishing"));
47 connect(_action_saveAny, &QAction::triggered,
this, [
this]() {
49 settings.value(
"DataStreamROS/storemessagesInMemory", _action_saveAny->isChecked() );
51 _action_saveAny->setCheckable(
true );
54 bool store_msg = settings.value(
"DataStreamROS/storemessagesInMemory",
false).toBool();
55 _action_saveAny->setChecked( store_msg );
71 const auto&
md5sum = msg->getMD5Sum();
72 const auto&
datatype = msg->getDataType();
73 const auto&
definition = msg->getMessageDefinition();
81 std::vector<uint8_t>
buffer;
83 buffer.resize(msg->size());
121 std::lock_guard<std::mutex> lock(
mutex());
122 _parser->parseMessage(topic_name, buffer_view, msg_time);
124 catch (std::runtime_error& ex)
128 QMessageBox::warning(
nullptr, tr(
"Error"),
129 QString(
"rosbag::open thrown an exception:\n") +
131 "\nThis message will be shown only once.");
135 const std::string prefixed_topic_name =
_prefix + topic_name;
146 std::piecewise_construct,
147 std::forward_as_tuple(prefixed_topic_name),
148 std::forward_as_tuple(prefixed_topic_name,
PlotGroup::Ptr())).first;
150 PlotDataAny& user_defined_data = plot_pair->second;
159 const std::string
key = prefixed_topic_name + (
"/_MSG_INDEX_");
171 using namespace std::chrono;
172 milliseconds wait_time_ms(1000);
174 QProgressDialog progress_dialog;
175 progress_dialog.setLabelText(
"Collecting ROS topic samples to understand data layout. ");
176 progress_dialog.setRange(0, wait_time_ms.count());
177 progress_dialog.setAutoClose(
true);
178 progress_dialog.setAutoReset(
true);
180 progress_dialog.show();
182 auto start_time = system_clock::now();
184 while (system_clock::now() - start_time < (wait_time_ms))
187 int i = duration_cast<milliseconds>(system_clock::now() - start_time).
count();
188 progress_dialog.setValue(i);
189 QApplication::processEvents();
190 if (progress_dialog.wasCanceled())
196 if (progress_dialog.wasCanceled() ==
false)
198 progress_dialog.cancel();
206 auto ret = QMessageBox::warning(
nullptr, tr(
"Disconnected!"),
207 tr(
"The roscore master is not reachable anymore.\n\n" 208 "Do you want to try reconnecting to it? \n"),
209 tr(
"Stop Streaming"), tr(
"Try reconnect"),
nullptr);
224 _spinner = std::make_shared<ros::AsyncSpinner>(1);
237 QMessageBox::warning(
nullptr, tr(
"ROS Stopped"),
"The plugin will be stopped");
248 QMessageBox::warning(
nullptr, tr(
"Warning"), tr(
"Your buffer is empty. Nothing to save.\n"));
252 QFileDialog saveDialog;
253 saveDialog.setAcceptMode(QFileDialog::AcceptSave);
254 saveDialog.setDefaultSuffix(
"bag");
257 if (saveDialog.result() != QDialog::Accepted || saveDialog.selectedFiles().empty())
262 QString fileName = saveDialog.selectedFiles().first();
264 if (fileName.size() > 0)
270 const std::string& topicname =
it.first;
271 const auto& plotdata =
it.second;
274 if (!registered_msg_type){
279 msg.
morph(registered_msg_type->getMD5Sum(), registered_msg_type->getDataType(),
280 registered_msg_type->getMessageDefinition());
282 for (
int i = 0;
i < plotdata.size();
i++)
284 const auto& point = plotdata.at(
i);
285 const double msg_time = point.x;
286 const std::any& type_erased_buffer = point.y;
288 if (type_erased_buffer.type() !=
typeid(std::vector<uint8_t>))
294 std::vector<uint8_t> raw_buffer = std::any_cast<std::vector<uint8_t>>(type_erased_buffer);
305 args <<
"reindex" << fileName;
306 process.start(
"rosbag", args);
317 boost::function<void(const RosIntrospection::ShapeShifter::ConstPtr&)> callback;
343 std::lock_guard<std::mutex> lock(
mutex());
351 std::vector<std::pair<QString, QString>> all_topics;
356 all_topics.push_back(std::make_pair(QString(topic_info.name.c_str()), QString(topic_info.datatype.c_str())));
360 timer.setSingleShot(
false);
361 timer.setInterval(1000);
366 connect(&timer, &QTimer::timeout, [&]() {
372 all_topics.push_back({ QString::fromStdString(topic_info.name), QString::fromStdString(topic_info.datatype) });
377 int res = dialog.exec();
400 _spinner = std::make_shared<ros::AsyncSpinner>(1);
void topicCallback(const RosIntrospection::ShapeShifter::ConstPtr &msg, const std::string &topic_name)
void xmlLoadState(const QDomElement &parent_element)
void xmlSaveState(QDomDocument &doc, QDomElement &plugin_elem) const
virtual const std::vector< QAction * > & availableActions() override
void initByFullCallbackType(const std::string &_topic, uint32_t _queue_size, const boost::function< void(P)> &_callback, const boost::function< boost::shared_ptr< typename ParameterAdapter< P >::Message >(void)> &factory_fn=DefaultMessageCreator< typename ParameterAdapter< P >::Message >())
static void registerMessage(const std::string &topic_name, const std::string &md5sum, const std::string &datatype, const std::string &definition)
void updateTopicList(std::vector< std::pair< QString, QString >> topic_list)
std::shared_ptr< PlotGroup > Ptr
void extractInitialSamples()
The ShapeShifter class is a type erased container for ROS Messages. It can be used also to create gen...
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
static RosIntrospectionFactory & get()
std::vector< TopicInfo > V_TopicInfo
virtual void shutdown() override
std::unordered_map< std::string, PlotDataAny > _user_defined_buffers
void morph(const std::string &md5sum, const std::string &datatype_, const std::string &msg_def_)
std::vector< QAction * > _available_actions
std::unique_ptr< RosCompositeParser > _parser
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
TransportHints & tcpNoDelay(bool nodelay=true)
void read(Stream &stream)
virtual bool start(QStringList *selected_datasources) override
std::map< std::string, int > _msg_index
constexpr auto count() -> size_t
virtual bool xmlLoadState(const QDomElement &parent_element) override
TimeseriesMap::iterator addNumeric(const std::string &name, PlotGroup::Ptr group={})
static ros::NodeHandlePtr getNode()
TransportHints transport_hints
PlotDataMapRef & dataMap()
virtual ~DataStreamROS() override
QAction * _action_saveAny
void saveToSettings(QSettings &setting, QString prefix) const
typename PlotDataBase< double, Value >::Point Point
void pushBack(const Point &p) override
virtual bool xmlSaveState(QDomDocument &doc, QDomElement &parent_element) const override
static RosIntrospection::ShapeShifter * getShapeShifter(const std::string &topic_name)
AnySeriesMap user_defined
PJ::RosParserConfig getResult() const
virtual bool isRunning() const override
const char * definition()
void loadFromSettings(const QSettings &settings, QString prefix)
std::map< std::string, ros::Subscriber > _subscribers
std::shared_ptr< ros::AsyncSpinner > _spinner
QAction * _action_saveIntoRosbag