Revision 9c0008d0
Fixed CliffsensorControl, now actually part of Behaviors
scout/libscout/CMakeLists.txt | ||
---|---|---|
29 | 29 |
#rosbuild_add_executable(example examples/example.cpp) |
30 | 30 |
#target_link_libraries(example ${PROJECT_NAME}) |
31 | 31 |
|
32 |
rosbuild_add_executable(libscout src/Behavior.cpp src/behaviors/draw_cw_circle.cpp src/behaviors/draw_ccw_circle.cpp src/BehaviorList.cpp src/BehaviorProcess.cpp src/MotorControl.cpp src/SonarControl.cpp src/HeadlightControl.cpp src/ButtonControl.cpp) |
|
32 |
rosbuild_add_executable(libscout src/Behavior.cpp src/behaviors/draw_cw_circle.cpp src/behaviors/draw_ccw_circle.cpp src/BehaviorList.cpp src/BehaviorProcess.cpp src/MotorControl.cpp src/SonarControl.cpp src/HeadlightControl.cpp src/ButtonControl.cpp src/CliffsensorControl.cpp) |
scout/libscout/manifest.xml | ||
---|---|---|
14 | 14 |
<depend package="headlights"/> |
15 | 15 |
<depend package="buttons"/> |
16 | 16 |
<depend package="sonar"/> |
17 |
<depend package="cliffsensor"/> |
|
17 | 18 |
|
18 | 19 |
</package> |
19 | 20 |
|
scout/libscout/src/Behavior.cpp | ||
---|---|---|
53 | 53 |
motors = new MotorControl(node, scoutname); |
54 | 54 |
buttons = new ButtonControl(node, scoutname); |
55 | 55 |
sonar = new SonarControl(node, scoutname); |
56 |
cliffsensor = new CliffsensorControl(node, scoutname); |
|
56 | 57 |
|
57 | 58 |
loop_rate = new ros::Rate(10); |
58 | 59 |
} |
scout/libscout/src/Behavior.h | ||
---|---|---|
43 | 43 |
#include "HeadlightControl.h" |
44 | 44 |
#include "ButtonControl.h" |
45 | 45 |
#include "SonarControl.h" |
46 |
#include "CliffsensorControl.h" |
|
46 | 47 |
#include "constants.h" |
47 | 48 |
|
48 | 49 |
class Behavior |
... | ... | |
64 | 65 |
MotorControl * motors; |
65 | 66 |
ButtonControl * buttons; |
66 | 67 |
SonarControl * sonar; |
68 |
CliffsensorControl * cliffsensor; |
|
67 | 69 |
|
68 | 70 |
// Wrappers for ROS functions |
69 | 71 |
bool ok(); |
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 |
|
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