publisher_ros2.cpp
Go to the documentation of this file.
1 #include "publisher_ros2.h"
2 
3 #include <QDebug>
4 #include <QDialog>
5 #include <QFormLayout>
6 #include <QCheckBox>
7 #include <QLabel>
8 #include <QHBoxLayout>
9 #include <QVBoxLayout>
10 #include <QDialogButtonBox>
11 #include <QScrollArea>
12 #include <QPushButton>
13 #include <QSettings>
14 #include <QRadioButton>
15 #include <unordered_map>
16 #include <QMessageBox>
17 #include <tf2_ros/qos.hpp>
18 #include <rosbag2_cpp/types.hpp>
19 #include <rmw/rmw.h>
20 #include <rmw/types.h>
22 
24 {
25  _context = std::make_shared<rclcpp::Context>();
26  _context->init(0, nullptr);
27 
28  auto exec_args = rclcpp::ExecutorOptions();
29  exec_args.context = _context;
30  _executor = std::make_unique<rclcpp::executors::MultiThreadedExecutor>(exec_args, 2);
31 
32  _select_topics_to_publish = new QAction(QString("Select topics to be published"));
33  connect(_select_topics_to_publish, &QAction::triggered,
35 
37 }
38 
40 {
41  _enabled = false;
42 }
43 
44 const std::vector<QAction*> &TopicPublisherROS2::availableActions()
45 {
46  return _available_actions;
47 }
48 
50 {
51  if( !_node )
52  {
53  return;
54  }
55  for (const auto& info : _topics_info)
56  {
57  auto to_publish = _topics_to_publish.find(info.topic_name);
58  if( to_publish == _topics_to_publish.end() || to_publish->second == false )
59  {
60  continue; // no publish
61  }
62 
63  auto publisher_it = _publishers.find(info.topic_name);
64  if (publisher_it == _publishers.end())
65  {
66  _publishers.insert({ info.topic_name, GenericPublisher::create(*_node, info.topic_name, info.type) });
67  }
68  }
69 
70  // remove already created publishers if not needed anymore
71  for (auto it = _publishers.begin(); it != _publishers.end(); /* no increment */)
72  {
73  auto to_publish = _topics_to_publish.find(it->first);
74  if( to_publish == _topics_to_publish.end() || to_publish->second == false )
75  {
76  it = _publishers.erase(it);
77  }
78  else{
79  it++;
80  }
81  }
82 }
83 
84 void TopicPublisherROS2::setEnabled(bool to_enable)
85 {
86  if (!_node && to_enable)
87  {
88  auto node_opts = rclcpp::NodeOptions();
89  node_opts.context(_context);
90  _node = std::make_shared<rclcpp::Node>("plotjuggler", node_opts);
91  _executor->add_node(_node);
92  }
93  _enabled = (to_enable && _node);
94 
95  if (_enabled)
96  {
97  auto metadata_it = _datamap->user_defined.find("plotjuggler::rosbag2_cpp::topics_metadata");
98  if (metadata_it == _datamap->user_defined.end())
99  {
100  return;
101  }
102  // I stored it in a one point timeseries... shoot me
103  const auto any_metadata = metadata_it->second[0].y;
104  _topics_info = std::any_cast<std::vector<TopicInfo>>(any_metadata);
105 
106  // select all the topics by default
107  for(const auto& info: _topics_info)
108  {
109  _topics_to_publish.insert( {info.topic_name, true} );
110  }
111 
113 
114  if (!_tf_broadcaster)
115  {
116  _tf_broadcaster = std::make_unique<tf2_ros::TransformBroadcaster>(*_node);
117  }
119  {
120  _tf_static_broadcaster = std::make_unique<tf2_ros::StaticTransformBroadcaster>(*_node);
121  }
122 
123  _previous_play_index = std::numeric_limits<int>::max();
124  }
125  else
126  {
127  _node.reset();
128  _publishers.clear();
129  _tf_broadcaster.reset();
130  _tf_static_broadcaster.reset();
131  }
132 }
133 
135 {
136  auto metadata_it = _datamap->user_defined.find("plotjuggler::rosbag2_cpp::topics_metadata");
137  if (metadata_it != _datamap->user_defined.end())
138  {
139  // I stored it in a one point timeseries... shoot me
140  const auto any_metadata = metadata_it->second[0].y;
141  _topics_info = std::any_cast<std::vector<TopicInfo>>(any_metadata);
142  }
143 
145  dialog->setAttribute(Qt::WA_DeleteOnClose);
146  dialog->ui()->radioButtonClock->setHidden(true);
147  dialog->ui()->radioButtonHeaderStamp->setHidden(true);
148 
149  std::map<std::string, QCheckBox*> checkbox;
150 
151  for (const TopicInfo& info : _topics_info)
152  {
153  const std::string topic_name = info.topic_name;
154  auto cb = new QCheckBox(dialog);
155  auto filter_it = _topics_to_publish.find(topic_name);
156  if (filter_it == _topics_to_publish.end())
157  {
158  cb->setChecked(true);
159  }
160  else
161  {
162  cb->setChecked(filter_it->second);
163  }
164  cb->setFocusPolicy(Qt::NoFocus);
165  dialog->ui()->formLayout->addRow(new QLabel(QString::fromStdString(topic_name)), cb);
166  checkbox.insert(std::make_pair(topic_name, cb));
167  connect(dialog->ui()->pushButtonSelect, &QPushButton::pressed, [cb]() { cb->setChecked(true); });
168  connect(dialog->ui()->pushButtonDeselect, &QPushButton::pressed, [cb]() { cb->setChecked(false); });
169  }
170 
171  dialog->exec();
172 
173  if (dialog->result() == QDialog::Accepted)
174  {
175  _topics_to_publish.clear();
176  for (const auto& it : checkbox)
177  {
178  _topics_to_publish.insert({ it.first, it.second->isChecked() });
179  }
180 
182  }
183 }
184 
185 constexpr long NSEC_PER_SEC = 1000000000;
186 
187 rcutils_time_point_value_t Convert(const builtin_interfaces::msg::Time& stamp)
188 {
189  return stamp.nanosec + NSEC_PER_SEC*stamp.sec;
190 }
191 
192 builtin_interfaces::msg::Time Convert(const rcutils_time_point_value_t& time_stamp)
193 {
194  builtin_interfaces::msg::Time stamp;
195  stamp.sec = static_cast<int32_t>(time_stamp / NSEC_PER_SEC);
196  stamp.nanosec = static_cast<int32_t>(time_stamp - (NSEC_PER_SEC * stamp.sec));
197  return stamp;
198 }
199 
200 void TopicPublisherROS2::broadcastTF(double current_time)
201 {
202  using StringPair = std::pair<std::string, std::string>;
203 
204  std::map<StringPair, geometry_msgs::msg::TransformStamped> transforms;
205  std::map<StringPair, geometry_msgs::msg::TransformStamped> static_transforms;
206 
207  for (const auto& data_it : _datamap->user_defined)
208  {
209  const std::string& topic_name = data_it.first;
210  const PJ::PlotDataAny& plot_any = data_it.second;
211 
212  if (topic_name != "/tf_static" && topic_name != "/tf")
213  {
214  continue;
215  }
216 
217  const PJ::PlotDataAny* tf_data = &plot_any;
218  int last_index = tf_data->getIndexFromX(current_time);
219  if (last_index < 0)
220  {
221  continue;
222  }
223 
224  auto transforms_ptr = (topic_name == "/tf_static") ? & static_transforms : &transforms;
225 
226  std::vector<uint8_t> raw_buffer;
227  // 2 seconds in the past (to be configurable in the future)
228  int initial_index = tf_data->getIndexFromX(current_time - 2.0);
229 
230  if (_previous_play_index < last_index && _previous_play_index > initial_index)
231  {
232  initial_index = _previous_play_index;
233  }
234 
235  for (size_t index = std::max(0, initial_index); index <= last_index; index++)
236  {
237  const std::any& any_value = tf_data->at(index).y;
238 
239  const bool isRosbagMessage = (any_value.type() == typeid(MessageRefPtr));
240 
241  if (!isRosbagMessage)
242  {
243  continue;
244  }
245 
246  const auto& msg_instance = std::any_cast<MessageRefPtr>(any_value);
247 
248  auto tf_type_support = rosidl_typesupport_cpp::get_message_type_support_handle<tf2_msgs::msg::TFMessage>();
249  tf2_msgs::msg::TFMessage tf_msg;
250  if ( RMW_RET_OK != rmw_deserialize(msg_instance->serialized_data.get(), tf_type_support, &tf_msg) )
251  {
252  throw std::runtime_error("failed to deserialize TF message");
253  }
254 
255  for (const auto& stamped_transform : tf_msg.transforms)
256  {
257  const auto& parent_id = stamped_transform.header.frame_id;
258  const auto& child_id = stamped_transform.child_frame_id;
259  StringPair trans_id = std::make_pair(parent_id, child_id);
260  auto it = transforms_ptr->find(trans_id);
261  if (it == transforms_ptr->end())
262  {
263  transforms_ptr->insert({ trans_id, stamped_transform });
264  }
265  else if (Convert(it->second.header.stamp) <=
266  Convert(stamped_transform.header.stamp))
267  {
268  it->second = stamped_transform;
269  }
270  }
271  }
272 
273  // ready to broadacast
274  std::vector<geometry_msgs::msg::TransformStamped> transforms_vector;
275  transforms_vector.reserve(transforms_ptr->size());
276 
277  rcutils_time_point_value_t time_stamp;
278  int error = rcutils_system_time_now(&time_stamp);
279 
280  if (error != RCUTILS_RET_OK)
281  {
282  qDebug() << "Error getting current time. Error:" << rcutils_get_error_string().str;
283  }
284 
285  for (auto& trans : *transforms_ptr)
286  {
287  trans.second.header.stamp = Convert( time_stamp );
288  transforms_vector.emplace_back(std::move(trans.second));
289  }
290  if( transforms_ptr == &transforms ){
291  _tf_broadcaster->sendTransform(transforms_vector);
292  }
293  else{
294  _tf_static_broadcaster->sendTransform(transforms_vector);
295  }
296  }
297 
298 }
299 
300 
301 void TopicPublisherROS2::updateState(double current_time)
302 {
303  if (!_enabled || !_node)
304  {
305  return;
306  }
307 
308  //-----------------------------------------------
309  broadcastTF(current_time);
310  //-----------------------------------------------
311 
312  auto data_it = _datamap->user_defined.find("plotjuggler::rosbag2_cpp::consecutive_messages");
313  if (data_it != _datamap->user_defined.end())
314  {
315  const PJ::PlotDataAny& continuous_msgs = data_it->second;
316  _previous_play_index = continuous_msgs.getIndexFromX(current_time);
317  }
318 
319  for (const auto& data_it : _datamap->user_defined)
320  {
321  const std::string& topic_name = data_it.first;
322  const PJ::PlotDataAny& plot_any = data_it.second;
323 
324  if (topic_name == "/tf" || topic_name == "tf_static")
325  {
326  continue;
327  }
328 
329  auto publisher_it = _publishers.find(topic_name);
330  if (publisher_it == _publishers.end())
331  {
332  continue;
333  }
334 
335  int last_index = plot_any.getIndexFromX(current_time);
336  if (last_index < 0)
337  {
338  continue;
339  }
340 
341  const auto& any_value = plot_any.at(last_index).y;
342 
343  if (any_value.type() == typeid(MessageRefPtr))
344  {
345  const auto& msg_instance = std::any_cast<MessageRefPtr>(any_value);
346  publisher_it->second->publish(msg_instance->serialized_data);
347  }
348  }
349 }
350 
351 void TopicPublisherROS2::play(double current_time)
352 {
353  if (!_enabled || !_node){
354  return;
355  }
356 
357  auto data_it = _datamap->user_defined.find("plotjuggler::rosbag2_cpp::consecutive_messages");
358  if (data_it == _datamap->user_defined.end())
359  {
360  return;
361  }
362  const PJ::PlotDataAny& continuous_msgs = data_it->second;
363  int current_index = continuous_msgs.getIndexFromX(current_time);
364 
365  if (_previous_play_index > current_index)
366  {
367  _previous_play_index = current_index;
368  updateState(current_time);
369  return;
370  }
371  else
372  {
373  const PJ::PlotDataAny& consecutive_msg = data_it->second;
374  for (int index = _previous_play_index + 1; index <= current_index; index++)
375  {
376  const auto& any_value = consecutive_msg.at(index).y;
377  if (any_value.type() == typeid(MessageRefPtr))
378  {
379  const auto& msg_instance = std::any_cast<MessageRefPtr>(any_value);
380 
381  auto publisher_it = _publishers.find(msg_instance->topic_name);
382  if (publisher_it == _publishers.end())
383  {
384  continue;
385  }
386 
387  publisher_it->second->publish(msg_instance->serialized_data);
388  }
389  }
390  _previous_play_index = current_index;
391  }
392 }
393 
PublisherSelectDialog::ui
Ui::PublisherSelect * ui()
Definition: publisher_select_dialog.h:28
TopicPublisherROS2::setEnabled
void setEnabled(bool enabled) override
Definition: publisher_ros2.cpp:84
TopicPublisherROS2::~TopicPublisherROS2
virtual ~TopicPublisherROS2() override
Definition: publisher_ros2.cpp:39
TopicPublisherROS2::_available_actions
std::vector< QAction * > _available_actions
Definition: publisher_ros2.h:80
PJ::TimeseriesBase
TopicPublisherROS2::TopicPublisherROS2
TopicPublisherROS2()
Definition: publisher_ros2.cpp:23
TopicPublisherROS2::filterDialog
void filterDialog()
Definition: publisher_ros2.cpp:134
index
std::size_t index
TopicPublisherROS2::_enabled
bool _enabled
Definition: publisher_ros2.h:63
MessageRefPtr
std::shared_ptr< rosbag2_storage::SerializedBagMessage > MessageRefPtr
Definition: publisher_ros2.h:21
TopicPublisherROS2::_node
std::shared_ptr< rclcpp::Node > _node
Definition: publisher_ros2.h:61
error
error
publisher_ros2.h
GenericPublisher::create
static std::shared_ptr< GenericPublisher > create(rclcpp::Node &node, const std::string &topic_name, const std::string &topic_type)
Definition: generic_publisher.h:48
TopicPublisherROS2::updateState
void updateState(double current_time) override
Definition: publisher_ros2.cpp:301
TopicPublisherROS2::availableActions
const std::vector< QAction * > & availableActions() override
Definition: publisher_ros2.cpp:44
PublisherSelectDialog
Definition: publisher_select_dialog.h:15
TopicPublisherROS2::_topics_info
std::vector< TopicInfo > _topics_info
Definition: publisher_ros2.h:78
TopicPublisherROS2::_select_topics_to_publish
QAction * _select_topics_to_publish
Definition: publisher_ros2.h:70
NSEC_PER_SEC
constexpr long NSEC_PER_SEC
Definition: publisher_ros2.cpp:185
TopicPublisherROS2::broadcastTF
void broadcastTF(double current_time)
Definition: publisher_ros2.cpp:200
it
iterator it
TopicPublisherROS2::_previous_play_index
int _previous_play_index
Definition: publisher_ros2.h:76
TopicPublisherROS2::_context
std::shared_ptr< rclcpp::Context > _context
Definition: publisher_ros2.h:59
PJ::TimeseriesBase::getIndexFromX
int getIndexFromX(double x) const
Convert
rcutils_time_point_value_t Convert(const builtin_interfaces::msg::Time &stamp)
Definition: publisher_ros2.cpp:187
TopicPublisherROS2::play
void play(double interval) override
Definition: publisher_ros2.cpp:351
TopicPublisherROS2::_tf_static_broadcaster
std::shared_ptr< tf2_ros::StaticTransformBroadcaster > _tf_static_broadcaster
Definition: publisher_ros2.h:66
publisher_select_dialog.h
TopicPublisherROS2::_topics_to_publish
std::unordered_map< std::string, bool > _topics_to_publish
Definition: publisher_ros2.h:72
TopicPublisherROS2::updatePublishers
void updatePublishers()
Definition: publisher_ros2.cpp:49
TopicPublisherROS2::_tf_broadcaster
std::shared_ptr< tf2_ros::TransformBroadcaster > _tf_broadcaster
Definition: publisher_ros2.h:65
PJ::PlotDataMapRef::user_defined
AnySeriesMap user_defined
TopicInfo
Definition: ros2_parser.h:12
TopicPublisherROS2::_executor
std::unique_ptr< rclcpp::executors::MultiThreadedExecutor > _executor
Definition: publisher_ros2.h:60
StringPair
std::pair< std::string, std::string > StringPair
TopicPublisherROS2::_publishers
std::unordered_map< std::string, std::shared_ptr< GenericPublisher > > _publishers
Definition: publisher_ros2.h:68
PlotDataBase< double, Value >::at
Point & at(size_t index)
nullptr
#define nullptr
PJ::StatePublisher::_datamap
const PlotDataMapRef * _datamap


plotjuggler_ros
Author(s): Davide Faconti
autogenerated on Wed Feb 21 2024 03:22:56