Revision 9c0008d0
ID | 9c0008d04908747e904f4af7a5819eba03b9f7f1 |
Fixed CliffsensorControl, now actually part of Behaviors
scout/libscout/src/CliffsensorControl.h | ||
---|---|---|
38 | 38 |
#ifndef _CLIFFSENSOR_H_ |
39 | 39 |
#define _CLIFFSENSOR_H_ |
40 | 40 |
|
41 |
#include "cliffsensor/query_cliff.h" |
|
42 |
#include "cliffsensor/cliff_status_changed.h" |
|
41 |
#include <cliffsensor/query_cliff.h> |
|
42 |
#include <cliffsensor/cliff_status_changed.h> |
|
43 |
#include "constants.h" |
|
43 | 44 |
|
44 | 45 |
#define CLIFF_DETECTED 0x0 |
45 | 46 |
#define NO_CLIFF 0x1 |
... | ... | |
47 | 48 |
class CliffsensorControl |
48 | 49 |
{ |
49 | 50 |
public: |
50 |
CliffsensorControl::CliffsensorControl(const ros::NodeHandle& libscout_node) ;
|
|
51 |
CliffsensorControl(const ros::NodeHandle& libscout_node, std::string scoutname);
|
|
51 | 52 |
|
52 | 53 |
/** @brief Responds to topic to change cliff sensor status. **/ |
53 |
void changed_cliff_status(const cliffsensor::cliff_status_changed::ConstPtr& msg); |
|
54 |
void changed_cliff_status( |
|
55 |
const cliffsensor::cliff_status_changed::ConstPtr& msg); |
|
54 | 56 |
|
55 | 57 |
int get_front_raw(); |
56 | 58 |
int get_left_raw(); |
... | ... | |
60 | 62 |
private: |
61 | 63 |
/* Cliffsensor state variables |
62 | 64 |
*/ |
63 |
int front_raw; /**< The current raw value data of the front cliffsensor. */ |
|
64 |
int left_raw; /**< The current raw value data of the left cliffsensor. */ |
|
65 |
int right_raw; /**< The current raw value data of the right cliffsensor. */ |
|
65 |
int front_raw; /**< The current raw value |
|
66 |
data of the front cliffsensor. */ |
|
67 |
int left_raw; /**< The current raw value data of |
|
68 |
the left cliffsensor. */ |
|
69 |
int right_raw; /**< The current raw value data of |
|
70 |
the right cliffsensor. */ |
|
66 | 71 |
|
67 | 72 |
ros::Subscriber cliff_status_changed_sub; |
68 |
|
|
69 |
} |
|
73 |
ros::NodeHandle node; |
|
74 |
};
|
|
70 | 75 |
|
71 | 76 |
#endif |
Also available in: Unified diff