main.cpp
Go to the documentation of this file.
1 
28 #include <log_view/log_store.h>
29 #include <log_view/log_view.h>
30 #include <rosgraph_msgs/Log.h>
31 
32 #include <csignal>
33 
34 #include <ros/ros.h>
35 
36 void handleSigint(int sig);
37 
38 class LogViewer {
39  public:
40  static bool exit;
41 
43  logs_(std::make_shared<log_view::LogStore>()),
44  view_(logs_)
45  {
46 
47  }
48 
49  void run() {
50  bool connected = false;
51  view_.init();
52  while (!exit && !view_.exited()) {
53  bool master_status = ros::master::check();
54  view_.setConnected(master_status);
56  if (!connected && master_status) {
57  ros::start();
58  signal(SIGINT, handleSigint);
59  ros::NodeHandle node;
60  sub_ = node.subscribe("/rosout_agg", 10000, &LogViewer::handleMsg, this);
61  }
62  else if (connected && !master_status) {
63  ros::shutdown();
64  }
65  else if (connected && master_status) {
66  ros::spinOnce();
68  }
69 
70  connected = master_status;
71  view_.update();
72  }
73  view_.close();
74  }
75 
76  void handleMsg(const rosgraph_msgs::LogConstPtr& msg) {
77  logs_->addEntry(msg);
78  }
79 
80  private:
82 
85 };
86 bool LogViewer::exit = false;
87 
88 void handleSigint(int sig)
89 {
90  LogViewer::exit = true;
91 }
92 
93 int main(int argc, char **argv)
94 {
95  // prevent ncurses from pausing for 1 second on ESC key
96  char escape_var[] = "ESCDELAY=0";
97  putenv(escape_var);
99 
100  LogViewer log_viewer;
101  log_viewer.run();
102 
103  exit(0);
104 }
void handleMsg(const rosgraph_msgs::LogConstPtr &msg)
Definition: main.cpp:76
ros::Subscriber sub_
Definition: main.cpp:81
bool exited() const
Definition: log_view.cpp:112
ROSCPP_DECL bool check()
ROSCPP_DECL void start()
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char **argv)
Definition: main.cpp:93
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void setRosTime(const ros::Time &time)
Definition: log_view.cpp:120
std::shared_ptr< LogStore > LogStorePtr
Definition: log_store.h:55
void run()
Definition: main.cpp:49
log_view::LogStorePtr logs_
Definition: main.cpp:83
void handleSigint(int sig)
Definition: main.cpp:88
log_view::LogView view_
Definition: main.cpp:84
LogViewer()
Definition: main.cpp:42
static bool exit
Definition: main.cpp:40
static WallTime now()
void setConnected(bool connected)
Definition: log_view.cpp:116
void setSystemTime(const ros::WallTime &time)
Definition: log_view.cpp:124
static Time now()
ROSCPP_DECL void shutdown()
ROSCPP_DECL void spinOnce()


log_view
Author(s): Marc Alban
autogenerated on Thu Mar 4 2021 03:21:52