1 #ifndef ROSOUT_PUBLISHER_ROS_H 2 #define ROSOUT_PUBLISHER_ROS_H 10 #include <rosgraph_msgs/Log.h> 31 Q_PLUGIN_METADATA(IID
"com.icarustechnology.PlotJuggler.StatePublisher" "../statepublisher.json")
37 virtual void updateState(
double current_time)
override;
38 virtual const char*
name()
const override {
return "RosoutPublisherROS"; }
41 virtual bool enabled()
const override {
return _enabled; }
43 virtual void play(
double interval)
override 49 virtual void setEnabled(
bool enabled)
override;
53 void onWindowClosed();
63 std::vector<const PlotDataAny *> findRosoutTimeseries();
64 void syncWithTableModel(
const std::vector<const PlotDataAny *> &logs_timeseries);
73 #endif // ROSOUT_PUBLISHER_ROS_H virtual void play(double interval) override
std::chrono::high_resolution_clock::time_point TimePoint
RosoutWindow * _log_window
int64_t _minimum_time_usec
rqt_console_plus::LogWidget * _log_widget
LogsTableModel * _tablemodel
virtual bool enabled() const override
void closeEvent(QCloseEvent *) override
virtual const char * name() const override