statepublisher_rostopic.cpp
Go to the documentation of this file.
2 #include "qnodedialog.h"
3 
5 #include <QDebug>
6 #include <QDialog>
7 #include <QFormLayout>
8 #include <QCheckBox>
9 #include <QLabel>
10 #include <QHBoxLayout>
11 #include <QVBoxLayout>
12 #include <QDialogButtonBox>
13 #include <QScrollArea>
14 #include <QPushButton>
15 #include <QSettings>
16 #include <QRadioButton>
17 #include <rosbag/bag.h>
18 #include <std_msgs/Header.h>
19 #include <unordered_map>
20 #include <rosgraph_msgs/Clock.h>
21 #include <QMessageBox>
23 
24 using namespace PJ;
25 
27  _enabled(false)
28 , _node(nullptr)
29 , _publish_clock(true)
30 {
31  QSettings settings;
32  _publish_clock = settings.value("TopicPublisherROS/publish_clock", true).toBool();
33 
34  _select_topics_to_publish = new QAction(QString("Select topics to be published"));
35  connect(_select_topics_to_publish, &QAction::triggered,
37 
39 }
40 
42 {
43  _enabled = false;
44 }
45 
46 const std::vector<QAction *> &TopicPublisherROS::availableActions()
47 {
48  return _available_actions;
49 }
50 
51 void TopicPublisherROS::setEnabled(bool to_enable)
52 {
53  if (!_node && to_enable)
54  {
56  }
57  _enabled = (to_enable && _node);
58 
59  if (_enabled)
60  {
61  filterDialog(true);
62 
63  if (!_tf_broadcaster)
64  {
65  _tf_broadcaster = std::make_unique<tf2_ros::TransformBroadcaster>();
66  }
68  {
69  _tf_static_broadcaster = std::make_unique<tf2_ros::StaticTransformBroadcaster>();
70  }
71 
72  _previous_play_index = std::numeric_limits<int>::max();
73 
74  if (_publish_clock)
75  {
76  _clock_publisher = _node->advertise<rosgraph_msgs::Clock>("/clock", 10, true);
77  }
78  else
79  {
81  }
82  }
83  else
84  {
85  _node.reset();
86  _publishers.clear();
88 
89  _tf_broadcaster.reset();
90  _tf_static_broadcaster.reset();
91 
92  emit closed();
93  }
94 }
95 
96 void TopicPublisherROS::filterDialog(bool autoconfirm)
97 {
98  auto all_topics = RosIntrospectionFactory::get().getTopicList();
99 
100  if (all_topics.empty()){
101  return;
102  }
103 
105 
106  std::map<std::string, QCheckBox*> checkbox;
107 
108  for (const auto& topic : all_topics)
109  {
110  auto cb = new QCheckBox(dialog);
111  auto filter_it = _topics_to_publish.find(*topic);
112  if (filter_it == _topics_to_publish.end())
113  {
114  cb->setChecked(true);
115  }
116  else
117  {
118  cb->setChecked(filter_it->second);
119  }
120  cb->setFocusPolicy(Qt::NoFocus);
121  dialog->ui()->formLayout->addRow(new QLabel(QString::fromStdString(*topic)), cb);
122  checkbox.insert(std::make_pair(*topic, cb));
123  connect(dialog->ui()->pushButtonSelect, &QPushButton::pressed, [cb]() { cb->setChecked(true); });
124  connect(dialog->ui()->pushButtonDeselect, &QPushButton::pressed, [cb]() { cb->setChecked(false); });
125  }
126 
127  if (!autoconfirm)
128  {
129  dialog->exec();
130  }
131 
132  if (autoconfirm || dialog->result() == QDialog::Accepted)
133  {
134  _topics_to_publish.clear();
135  for (const auto& it : checkbox)
136  {
137  _topics_to_publish.insert({ it.first, it.second->isChecked() });
138  }
139 
140  // remove already created publisher if not needed anymore
141  for (auto it = _publishers.begin(); it != _publishers.end(); /* no increment */)
142  {
143  const std::string& topic_name = it->first;
144  if (!toPublish(topic_name))
145  {
146  it = _publishers.erase(it);
147  }
148  else
149  {
150  it++;
151  }
152  }
153 
154  _publish_clock = dialog->ui()->radioButtonClock->isChecked();
155 
156  if (_enabled && _publish_clock)
157  {
158  _clock_publisher = _node->advertise<rosgraph_msgs::Clock>("/clock", 10, true);
159  }
160  else
161  {
163  }
164 
165  dialog->deleteLater();
166 
167  QSettings settings;
168  settings.setValue("TopicPublisherROS/publish_clock", _publish_clock);
169  }
170 }
171 
172 void TopicPublisherROS::broadcastTF(double current_time)
173 {
174  using StringPair = std::pair<std::string, std::string>;
175 
176  std::map<StringPair, geometry_msgs::TransformStamped> transforms;
177  std::map<StringPair, geometry_msgs::TransformStamped> static_transforms;
178 
179  for (const auto& data_it : _datamap->user_defined)
180  {
181  const std::string& topic_name = data_it.first;
182  const PlotDataAny& plot_any = data_it.second;
183 
184  if (!toPublish(topic_name))
185  {
186  continue; // Not selected
187  }
188 
189  if (topic_name != "/tf_static" && topic_name != "/tf")
190  {
191  continue;
192  }
193 
194  const PlotDataAny* tf_data = &plot_any;
195  int last_index = tf_data->getIndexFromX(current_time);
196  if (last_index < 0)
197  {
198  continue;
199  }
200 
201  auto transforms_ptr = (topic_name == "/tf_static") ? & static_transforms : &transforms;
202 
203  std::vector<uint8_t> raw_buffer;
204  // 2 seconds in the past (to be configurable in the future)
205  int initial_index = tf_data->getIndexFromX(current_time - 2.0);
206 
207  if (_previous_play_index < last_index && _previous_play_index > initial_index)
208  {
209  initial_index = _previous_play_index;
210  }
211 
212  for (size_t index = std::max(0, initial_index); index <= last_index; index++)
213  {
214  const std::any& any_value = tf_data->at(index).y;
215 
216  const bool isRosbagMessage = any_value.type() == typeid(rosbag::MessageInstance);
217 
218  if (!isRosbagMessage)
219  {
220  continue;
221  }
222 
223  const auto& msg_instance = std::any_cast<rosbag::MessageInstance>(any_value);
224 
225  raw_buffer.resize(msg_instance.size());
226  ros::serialization::OStream ostream(raw_buffer.data(), raw_buffer.size());
227  msg_instance.write(ostream);
228 
229  tf2_msgs::TFMessage tf_msg;
230  ros::serialization::IStream istream(raw_buffer.data(), raw_buffer.size());
231  ros::serialization::deserialize(istream, tf_msg);
232 
233  for (const auto& stamped_transform : tf_msg.transforms)
234  {
235  const auto& parent_id = stamped_transform.header.frame_id;
236  const auto& child_id = stamped_transform.child_frame_id;
237  StringPair trans_id = std::make_pair(parent_id, child_id);
238  auto it = transforms_ptr->find(trans_id);
239  if (it == transforms_ptr->end())
240  {
241  transforms_ptr->insert({ trans_id, stamped_transform });
242  }
243  else if (it->second.header.stamp <= stamped_transform.header.stamp)
244  {
245  it->second = stamped_transform;
246  }
247  }
248  }
249  // ready to broadacast
250  std::vector<geometry_msgs::TransformStamped> transforms_vector;
251  transforms_vector.reserve(transforms_ptr->size());
252 
253  const auto now = ros::Time::now();
254  for (auto& trans : *transforms_ptr)
255  {
256  if (!_publish_clock)
257  {
258  trans.second.header.stamp = now;
259  }
260  transforms_vector.emplace_back(std::move(trans.second));
261  }
262  if( transforms_vector.size() > 0)
263  {
264  if( transforms_ptr == &transforms ){
265  _tf_broadcaster->sendTransform(transforms_vector);
266  }
267  else{
268  _tf_static_broadcaster->sendTransform(transforms_vector);
269  }
270  }
271  }
272 }
273 
274 bool TopicPublisherROS::toPublish(const std::string& topic_name)
275 {
276  auto it = _topics_to_publish.find(topic_name);
277  if (it == _topics_to_publish.end())
278  {
279  return false;
280  }
281  else
282  {
283  return it->second;
284  }
285 }
286 
288 {
289  using namespace RosIntrospection;
290 
291  const auto& topic_name = msg_instance.getTopic();
293 
294  if (!shapeshifted)
295  {
296  return; // Not registered, just skip
297  }
298 
299  std::vector<uint8_t> raw_buffer;
300  raw_buffer.resize(msg_instance.size());
301  ros::serialization::OStream ostream(raw_buffer.data(), raw_buffer.size());
302  msg_instance.write(ostream);
303 
304  if (!_publish_clock)
305  {
306  const ROSMessageInfo* msg_info = RosIntrospectionFactory::parser().getMessageInfo(topic_name);
307  if (msg_info && msg_info->message_tree.croot()->children().size() >= 1)
308  {
309  const auto& first_field = msg_info->message_tree.croot()->child(0)->value();
310  if (first_field->type().baseName() == "std_msgs/Header")
311  {
312  std_msgs::Header msg;
313  ros::serialization::IStream is(raw_buffer.data(), raw_buffer.size());
315  msg.stamp = ros::Time::now();
316  ros::serialization::OStream os(raw_buffer.data(), raw_buffer.size());
318  }
319  }
320  }
321 
322  ros::serialization::IStream istream(raw_buffer.data(), raw_buffer.size());
323  shapeshifted->read(istream);
324 
325  auto publisher_it = _publishers.find(topic_name);
326  if (publisher_it == _publishers.end())
327  {
328  auto res = _publishers.insert({ topic_name, shapeshifted->advertise(*_node, topic_name, 10, true) });
329  publisher_it = res.first;
330  }
331 
332  const ros::Publisher& publisher = publisher_it->second;
333  publisher.publish(*shapeshifted);
334 }
335 
336 void TopicPublisherROS::updateState(double current_time)
337 {
338  if (!_enabled || !_node)
339  return;
340 
341  if (!ros::master::check())
342  {
343  QMessageBox::warning(nullptr, tr("Disconnected!"),
344  "The roscore master cannot be detected.\n"
345  "The publisher will be disabled.");
346  emit closed();
347  return;
348  }
349 
350  //-----------------------------------------------
351  broadcastTF(current_time);
352  //-----------------------------------------------
353 
354  auto data_it = _datamap->user_defined.find("plotjuggler::rosbag1::consecutive_messages");
355  if (data_it != _datamap->user_defined.end())
356  {
357  const PlotDataAny& continuous_msgs = data_it->second;
358  _previous_play_index = continuous_msgs.getIndexFromX(current_time);
359  // qDebug() << QString("u: %1").arg( current_index ).arg(current_time, 0, 'f', 4 );
360  }
361 
362  for (const auto& data_it : _datamap->user_defined)
363  {
364  const std::string& topic_name = data_it.first;
365  const PlotDataAny& plot_any = data_it.second;
366  if (!toPublish(topic_name))
367  {
368  continue; // Not selected
369  }
370 
372 
373  if (shapeshifter->getDataType() == "tf/tfMessage" || shapeshifter->getDataType() == "tf2_msgs/TFMessage")
374  {
375  continue;
376  }
377 
378  int last_index = plot_any.getIndexFromX(current_time);
379  if (last_index < 0)
380  {
381  continue;
382  }
383 
384  const auto& any_value = plot_any.at(last_index).y;
385 
386  if (any_value.type() == typeid(rosbag::MessageInstance))
387  {
388  const auto& msg_instance = std::any_cast<rosbag::MessageInstance>(any_value);
389  publishAnyMsg(msg_instance);
390  }
391  }
392 
393  if (_publish_clock)
394  {
395  rosgraph_msgs::Clock clock;
396  try
397  {
398  clock.clock.fromSec(current_time);
399  _clock_publisher.publish(clock);
400  }
401  catch (...)
402  {
403  qDebug() << "error: " << current_time;
404  }
405  }
406 }
407 
408 void TopicPublisherROS::play(double current_time)
409 {
410  if (!_enabled || !_node)
411  return;
412 
413  if (!ros::master::check())
414  {
415  QMessageBox::warning(nullptr, tr("Disconnected!"),
416  "The roscore master cannot be detected.\n"
417  "The publisher will be disabled.");
418  emit closed();
419  return;
420  }
421 
422  auto data_it = _datamap->user_defined.find("plotjuggler::rosbag1::consecutive_messages");
423  if (data_it == _datamap->user_defined.end())
424  {
425  return;
426  }
427  const PlotDataAny& continuous_msgs = data_it->second;
428  int current_index = continuous_msgs.getIndexFromX(current_time);
429 
430  if (_previous_play_index > current_index)
431  {
432  _previous_play_index = current_index;
433  updateState(current_time);
434  return;
435  }
436  else
437  {
438  const PlotDataAny& consecutive_msg = data_it->second;
439  for (int index = _previous_play_index + 1; index <= current_index; index++)
440  {
441  const auto& any_value = consecutive_msg.at(index).y;
442  if (any_value.type() == typeid(rosbag::MessageInstance))
443  {
444  const auto& msg_instance = std::any_cast<rosbag::MessageInstance>(any_value);
445 
446  if (!toPublish(msg_instance.getTopic()))
447  {
448  continue; // Not selected
449  }
450 
451  // qDebug() << QString("p: %1").arg( index );
452  publishAnyMsg(msg_instance);
453 
454  if (_publish_clock)
455  {
456  rosgraph_msgs::Clock clock;
457  clock.clock = msg_instance.getTime();
458  _clock_publisher.publish(clock);
459  }
460  }
461  }
462  _previous_play_index = current_index;
463  }
464 }
PublisherSelectDialog::ui
Ui::PublisherSelect * ui()
Definition: publisher_select_dialog.h:28
RosIntrospection::ShapeShifter::read
void read(Stream &stream)
ros::master::check
ROSCPP_DECL bool check()
ros::serialization::OStream
PJ::TimeseriesBase
qnodedialog.h
ros::Publisher
ros::serialization::deserialize
void deserialize(Stream &stream, boost::array< T, N > &t)
statepublisher_rostopic.h
RosIntrospection::details::Tree::croot
const TreeNode< T > * croot() const
TopicPublisherROS::filterDialog
void filterDialog(bool autoconfirm)
Definition: statepublisher_rostopic.cpp:96
TopicPublisherROS::_tf_broadcaster
std::shared_ptr< tf2_ros::TransformBroadcaster > _tf_broadcaster
Definition: statepublisher_rostopic.h:58
rosbag::MessageInstance
RosIntrospectionFactory::get
static RosIntrospectionFactory & get()
Definition: shape_shifter_factory.hpp:37
TopicPublisherROS::_clock_publisher
ros::Publisher _clock_publisher
Definition: statepublisher_rostopic.h:61
rosbag::MessageInstance::write
void write(Stream &stream) const
ros_introspection.hpp
TopicPublisherROS::_enabled
bool _enabled
Definition: statepublisher_rostopic.h:52
TopicPublisherROS::availableActions
const std::vector< QAction * > & availableActions() override
Definition: statepublisher_rostopic.cpp:46
TopicPublisherROS::broadcastTF
void broadcastTF(double current_time)
Definition: statepublisher_rostopic.cpp:172
msg
msg
ros::serialization::IStream
PJ::StatePublisher::closed
void closed()
bag.h
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
TopicPublisherROS::_node
ros::NodeHandlePtr _node
Definition: statepublisher_rostopic.h:54
RosIntrospection::ROSMessageInfo::message_tree
MessageTree message_tree
TopicPublisherROS::_tf_static_broadcaster
std::shared_ptr< tf2_ros::StaticTransformBroadcaster > _tf_static_broadcaster
Definition: statepublisher_rostopic.h:59
RosIntrospectionFactory::parser
static RosIntrospection::Parser & parser()
Definition: shape_shifter_factory.hpp:20
RosIntrospectionFactory::getTopicList
static std::vector< const std::string * > getTopicList()
Definition: shape_shifter_factory.hpp:67
PublisherSelectDialog
Definition: publisher_select_dialog.h:15
topic
topic
ros::Publisher::shutdown
void shutdown()
TopicPublisherROS::TopicPublisherROS
TopicPublisherROS()
Definition: statepublisher_rostopic.cpp:26
RosIntrospection::ShapeShifter::advertise
ros::Publisher advertise(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, bool latch=false, const ros::SubscriberStatusCallback &connect_cb=ros::SubscriberStatusCallback()) const
TopicPublisherROS::updateState
virtual void updateState(double current_time) override
Definition: statepublisher_rostopic.cpp:336
RosIntrospection::Parser::getMessageInfo
const ROSMessageInfo * getMessageInfo(const std::string &msg_identifier) const
RosIntrospection::ShapeShifter::getDataType
std::string const & getDataType() const
TopicPublisherROS::~TopicPublisherROS
virtual ~TopicPublisherROS() override
Definition: statepublisher_rostopic.cpp:41
PJ::TimeseriesBase::getIndexFromX
int getIndexFromX(double x) const
RosIntrospection
rosbag::MessageInstance::size
uint32_t size() const
publisher_select_dialog.h
TopicPublisherROS::_publish_clock
bool _publish_clock
Definition: statepublisher_rostopic.h:56
TopicPublisherROS::_topics_to_publish
std::unordered_map< std::string, bool > _topics_to_publish
Definition: statepublisher_rostopic.h:65
arg_id_kind::index
@ index
TopicPublisherROS::setEnabled
virtual void setEnabled(bool enabled) override
Definition: statepublisher_rostopic.cpp:51
TopicPublisherROS::publishAnyMsg
void publishAnyMsg(const rosbag::MessageInstance &msg_instance)
Definition: statepublisher_rostopic.cpp:287
PJ
TopicPublisherROS::_previous_play_index
int _previous_play_index
Definition: statepublisher_rostopic.h:71
RosIntrospection::ShapeShifter
TopicPublisherROS::_publishers
std::map< std::string, ros::Publisher > _publishers
Definition: statepublisher_rostopic.h:50
PJ::PlotDataMapRef::user_defined
AnySeriesMap user_defined
StringPair
std::pair< std::string, std::string > StringPair
rosbag::MessageInstance::getTopic
std::string const & getTopic() const
ros::serialization::serialize
void serialize(Stream &stream, const boost::array< T, N > &t)
TopicPublisherROS::play
virtual void play(double interval) override
Definition: statepublisher_rostopic.cpp:408
TopicPublisherROS::_available_actions
std::vector< QAction * > _available_actions
Definition: statepublisher_rostopic.h:73
PlotDataBase< double, Value >::at
Point & at(size_t index)
RosIntrospection::ROSMessageInfo
RosManager::getNode
static ros::NodeHandlePtr getNode()
Definition: qnodedialog.cpp:135
nullptr
#define nullptr
PJ::StatePublisher::_datamap
const PlotDataMapRef * _datamap
TopicPublisherROS::_select_topics_to_publish
QAction * _select_topics_to_publish
Definition: statepublisher_rostopic.h:63
RosIntrospectionFactory::getShapeShifter
static RosIntrospection::ShapeShifter * getShapeShifter(const std::string &topic_name)
Definition: shape_shifter_factory.hpp:60
ros::Time::now
static Time now()
TopicPublisherROS::toPublish
bool toPublish(const std::string &topic_name)
Definition: statepublisher_rostopic.cpp:274


plotjuggler_ros
Author(s): Davide Faconti
autogenerated on Sat May 24 2025 02:24:01