Revision bb70c69d
ID | bb70c69d258a6ff4aea4f72361b0c82b7e27507d |
Fixed callback problem using std::bind
Still some TODO's.
vision/src/rviz_interactive_target.cpp | ||
---|---|---|
2 | 2 |
#include <string.h> |
3 | 3 |
#include <geometry_msgs/Quaternion.h> |
4 | 4 |
#include <interactive_markers/interactive_marker_server.h> |
5 |
#include <functional> |
|
5 | 6 |
|
6 | 7 |
using namespace std; |
7 | 8 |
using namespace visualization_msgs; |
8 | 9 |
|
9 | 10 |
/* TODO: |
10 | 11 |
* -replace the three MOVE_AXIS directions with one MOVE_AXIS and one MOVE_PLANE |
11 |
* -make it compile without needing class Callback |
|
12 | 12 |
* -have it constantly publish current position, instead of only publishing |
13 | 13 |
* when the marker is moved |
14 | 14 |
*/ |
... | ... | |
25 | 25 |
ros::Publisher pub; |
26 | 26 |
}; |
27 | 27 |
|
28 |
// boost should be able to do this, but... I could _not_ make it compile |
|
29 |
// so, I wrote my own |
|
30 |
template <class class_t, class arg_t> class Callback |
|
31 |
{ |
|
32 |
public: |
|
33 |
Callback(void (class_t::*cb)(arg_t), class_t* obj) : cb(cb), obj(obj) {} |
|
34 |
void operator()(arg_t arg) {(obj->*cb)(arg);} |
|
35 |
private: |
|
36 |
void (class_t::*cb)(arg_t); |
|
37 |
class_t* obj; |
|
38 |
}; |
|
39 |
|
|
40 | 28 |
Marker3DOF::Marker3DOF(interactive_markers::InteractiveMarkerServer& server) |
41 | 29 |
{ |
42 | 30 |
marker.header.frame_id = "/quadrotor"; |
... | ... | |
49 | 37 |
addControl("target_y", 0, 1, 0, 1); |
50 | 38 |
addControl("target_z", 0, 0, 1, 1); |
51 | 39 |
server.insert(marker); |
52 |
server.setCallback("target", Callback<Marker3DOF, const |
|
53 |
InteractiveMarkerFeedbackConstPtr&>(&Marker3DOF::processFeedback, this)); |
|
40 |
server.setCallback("target", bind(&Marker3DOF::processFeedback, this, _1)); |
|
54 | 41 |
server.applyChanges(); |
55 | 42 |
pub = nh.advertise<geometry_msgs::Point>("/v2v3_converter/target_3d", 100); |
56 | 43 |
} |
Also available in: Unified diff