Node for visualing dish activity. More...
#include <dish_viz.h>
Public Member Functions | |
DataHandler () | |
Private Member Functions | |
void | burstCallback (const burst_calc::burst::ConstPtr &b) |
Callback for burst messages. | |
void | caCallback (const burst_calc::ca::ConstPtr &c) |
Callback for center of activity messages. | |
void | dishCallback (const neuro_recv::dish_state::ConstPtr &d) |
Callback for dish state messages. | |
void | getParams () |
Gets server parameters. | |
void | init () |
Initializes the node. | |
void | plotCa () |
Plots a center of activity on the visualizer. | |
void | rangesCallback (const burst_calc::ranges::ConstPtr &r) |
Callback for ranges messages. | |
void | run () |
Main spin loop. | |
void | updateMinMax (const neuro_recv::dish_state &d) |
Updates minimum and maximum values for each channel. | |
Private Attributes | |
ros::Subscriber | burst_sub_ |
ros::Subscriber | ca_sub_ |
std::queue< burst_calc::ca > | cas_ |
int | color_mode_ |
ros::Subscriber | dish_sub_ |
DishVisualizer | dviz_ |
int | loop_rate_ |
ros::NodeHandle | n_ |
std::queue < neuro_recv::dish_state > | queue_ |
ros::Subscriber | ranges_sub_ |
bool | start_ |
ros::ServiceClient | time_client_ |
Node for visualing dish activity.
This node receives dish states from a receiver node and then plots that activity on screen for the user to see. It also receives centers of activity from the CAT creator node and plots those as well. This node is in sync with the movements of the ARM.
Definition at line 31 of file dish_viz.h.
DataHandler::DataHandler | ( | ) | [inline] |
Definition at line 34 of file dish_viz.h.
void DataHandler::burstCallback | ( | const burst_calc::burst::ConstPtr & | b | ) | [private] |
Callback for burst messages.
This method is called automatically when the node receives a burst message. This should only happen once. This is just a signal to tell the visualizer to start playback.
r | the received message |
Definition at line 195 of file dish_viz.cpp.
void DataHandler::caCallback | ( | const burst_calc::ca::ConstPtr & | c | ) | [private] |
Callback for center of activity messages.
This method is called automatically when the node receives a CA message. The CA is pushed onto the display queue.
c | the received message |
Definition at line 181 of file dish_viz.cpp.
void DataHandler::dishCallback | ( | const neuro_recv::dish_state::ConstPtr & | d | ) | [private] |
Callback for dish state messages.
This method is called automatically when the node receives a dish state message. The minimum and maximum voltages are updated, and the dish state is pushed onto the display queue.
d | the received message |
Definition at line 166 of file dish_viz.cpp.
void DataHandler::getParams | ( | ) | [private] |
Gets server parameters.
Definition at line 48 of file dish_viz.cpp.
void DataHandler::init | ( | ) | [private] |
Initializes the node.
Gets server parameters, initializes the visualizer, initializes subscribers, and runs the spin loop.
Definition at line 16 of file dish_viz.cpp.
void DataHandler::plotCa | ( | ) | [private] |
Plots a center of activity on the visualizer.
Definition at line 99 of file dish_viz.cpp.
void DataHandler::rangesCallback | ( | const burst_calc::ranges::ConstPtr & | r | ) | [private] |
Callback for ranges messages.
This method is called automatically when the node receives a ranges message. This should only happen once. The range values are used for calculating the display colors of voltages on each channel.
r | the received message |
Definition at line 209 of file dish_viz.cpp.
void DataHandler::run | ( | ) | [private] |
Main spin loop.
Spins until the queue is empty, ROS shuts down, or Ctrl+C is pressed.
Definition at line 70 of file dish_viz.cpp.
void DataHandler::updateMinMax | ( | const neuro_recv::dish_state & | d | ) | [private] |
Updates minimum and maximum values for each channel.
This is a self-correcting feature of the visualizer, or else colors could become inaccurate the longer the node runs.
d | the dish state used for the update |
Definition at line 138 of file dish_viz.cpp.
ros::Subscriber DataHandler::burst_sub_ [private] |
Definition at line 50 of file dish_viz.h.
ros::Subscriber DataHandler::ca_sub_ [private] |
Definition at line 49 of file dish_viz.h.
std::queue<burst_calc::ca> DataHandler::cas_ [private] |
Definition at line 56 of file dish_viz.h.
int DataHandler::color_mode_ [private] |
Definition at line 58 of file dish_viz.h.
ros::Subscriber DataHandler::dish_sub_ [private] |
Definition at line 48 of file dish_viz.h.
DishVisualizer DataHandler::dviz_ [private] |
Definition at line 54 of file dish_viz.h.
int DataHandler::loop_rate_ [private] |
Definition at line 57 of file dish_viz.h.
ros::NodeHandle DataHandler::n_ [private] |
Definition at line 47 of file dish_viz.h.
std::queue<neuro_recv::dish_state> DataHandler::queue_ [private] |
Definition at line 55 of file dish_viz.h.
ros::Subscriber DataHandler::ranges_sub_ [private] |
Definition at line 51 of file dish_viz.h.
bool DataHandler::start_ [private] |
Definition at line 59 of file dish_viz.h.
ros::ServiceClient DataHandler::time_client_ [private] |
Definition at line 52 of file dish_viz.h.