Revision a8987cda
ID | a8987cda5e2c606b2aba534af5ee0edb027c69b3 |
Fixes to WirelessReceiver and wl_test
Changed receive callback to use std::function so we can use std::bind to
pass non-static member functions. There is still a weird problem where
WirelessReceiver::dummy gets called many times for each incoming packet
in wl_test.
scout/libscout/src/WirelessReceiver.cpp | ||
---|---|---|
45 | 45 |
* @param libscout_node Node handle of the ROS node used by libscout. |
46 | 46 |
**/ |
47 | 47 |
WirelessReceiver::WirelessReceiver(const ros::NodeHandle& libscout_node) |
48 |
: node(libscout_node) |
|
48 |
: node(libscout_node), callback(bind(&WirelessReceiver::dummy, this, _1))
|
|
49 | 49 |
{ |
50 | 50 |
sub = node.subscribe("/wireless/receive", QUEUE_SIZE, |
51 | 51 |
&WirelessReceiver::receive, this); |
... | ... | |
70 | 70 |
**/ |
71 | 71 |
void WirelessReceiver::receive(const ::messages::WirelessPacketConstPtr& packet) |
72 | 72 |
{ |
73 |
if (callback == NULL)
|
|
74 |
{
|
|
75 |
ROS_WARN("Warning: Ignored wireless packet."); |
|
76 |
}
|
|
77 |
else
|
|
78 |
{
|
|
79 |
(*callback)(packet->data);
|
|
80 |
}
|
|
73 |
callback(packet->data);
|
|
74 |
}
|
|
75 |
|
|
76 |
/**
|
|
77 |
* @brief The default callback function, to be overwritten by register_callback
|
|
78 |
*/
|
|
79 |
void WirelessReceiver::dummy(std::vector<uint8_t> data) {
|
|
80 |
ROS_WARN("Warning: Ignored wireless packet.");
|
|
81 | 81 |
} |
Also available in: Unified diff