Revision 9c0008d0
Fixed CliffsensorControl, now actually part of Behaviors
scout/libscout/src/CliffsensorControl.cpp | ||
---|---|---|
52 | 52 |
* starts and initializes the cliffsensors. It then subscribes to the |
53 | 53 |
* cliff_status_changed topics |
54 | 54 |
**/ |
55 |
CliffsensorControl::CliffsensorControl(const ros::NodeHandle& libscout_node) : node(libscout_node) |
|
55 |
CliffsensorControl::CliffsensorControl(const ros::NodeHandle& libscout_node, |
|
56 |
std::string scoutname) : node(libscout_node) |
|
56 | 57 |
{ |
57 | 58 |
/* Subscribe to the cliff_status_changed topic */ |
58 | 59 |
cliff_status_changed_sub = node.subscribe("cliff_status_changed", |
59 |
QUEUE_SIZE, changed_cliff_status);
|
|
60 |
QUEUE_SIZE, &CliffsensorControl::changed_cliff_status, this);
|
|
60 | 61 |
|
61 | 62 |
ros::spin(); |
62 | 63 |
} |
... | ... | |
72 | 73 |
*/ |
73 | 74 |
void CliffsensorControl::changed_cliff_status(const cliffsensor::cliff_status_changed::ConstPtr& msg) |
74 | 75 |
{ |
75 |
front_raw = msg.front_raw;
|
|
76 |
left_raw = msg.left_raw;
|
|
77 |
right_raw = msg.right_raw;
|
|
76 |
front_raw = msg->front_raw;
|
|
77 |
left_raw = msg->left_raw;
|
|
78 |
right_raw = msg->right_raw;
|
|
78 | 79 |
return; |
79 | 80 |
} |
80 | 81 |
|
Also available in: Unified diff