Revision a8987cda
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.h | ||
---|---|---|
39 | 39 |
#define _WIRELESS_RECEIVER_H_ |
40 | 40 |
|
41 | 41 |
#include <vector> |
42 |
#include <functional> |
|
42 | 43 |
#include <ros/ros.h> |
43 | 44 |
#include "messages/WirelessPacket.h" |
44 | 45 |
#include "constants.h" |
45 | 46 |
|
46 |
typedef void (*WirelessCallback)(std::vector<uint8_t>);
|
|
47 |
typedef std::function<void(std::vector<uint8_t>)> WirelessCallback;
|
|
47 | 48 |
|
48 | 49 |
class WirelessReceiver |
49 | 50 |
{ |
... | ... | |
59 | 60 |
ros::NodeHandle node; |
60 | 61 |
WirelessCallback callback; |
61 | 62 |
void receive(const ::messages::WirelessPacketConstPtr&); |
63 |
void dummy(std::vector<uint8_t> data); |
|
62 | 64 |
}; |
63 | 65 |
|
64 | 66 |
#endif |
Also available in: Unified diff