Project

General

Profile

Revision 93cebb99

ID93cebb998b81dc98f54dac5728560ecc511c7224
Parent e99a72bf
Child 7327a8ed

Added by Yuyang Guo over 10 years ago

added BomControl class and to the scout sensor

View differences:

scout/scoutsim/src/scout.h
55 55
#include <messages/set_motors.h>
56 56
#include <messages/query_encoders.h>
57 57
#include <messages/query_linesensor.h>
58
#include <messages/query_boms.h>
58 59
#include <messages/sonar_distance.h>
59 60
#include <messages/sonar_toggle.h>
60 61
#include <messages/sonar_set_scan.h>
......
73 74
#define PI 3.14159265
74 75

  
75 76
#define NUM_LINESENSORS 8
77
#define NUM_BOMS 10
76 78

  
77 79
// Distance, pixels, from center of robot to the linesensors.
78 80
#define LNSNSR_D 20
......
121 123
                                         world_state state);
122 124
            void paint(wxDC& dc);
123 125
            void set_sonar_visual(bool on);
124
            void update_BOM(int bom_index,bool bom_value);
126
            void update_BOM(int bom_index, unsigned int bom_value,
127
                            unsigned int sender);
125 128

  
126 129
        private:
127 130
            float absolute_to_mps(int absolute_speed);
......
132 135
                                     messages::query_encoders::Response&);
133 136
            bool query_linesensor_callback(messages::query_linesensor::Request&,
134 137
                                     messages::query_linesensor::Response&);
138
            bool query_BOM_callback(messages::query_boms::Request&,
139
                                     messages::query_boms::Response&);
135 140
            bool handle_sonar_toggle(messages::sonar_toggle::Request  &req,
136 141
                                     messages::sonar_toggle::Response &res);
137 142
            bool handle_sonar_set_scan(messages::sonar_set_scan::Request  &req,
......
147 152
                              double robot_theta, wxMemoryDC& sonar_dc);
148 153
            void update_linesensor(const wxImage& lines_image, int x, int y,
149 154
                                   double theta);
155

  
150 156
            int old_front_dx;
151 157
            int old_front_dy;
152 158
            int old_back_dx;
......
196 202

  
197 203
            // A vector of the 8 linesensor readings
198 204
            std::vector<unsigned int> linesensor_readings;
205
            std::vector<unsigned int> BOM_readings;
206
            std::vector<unsigned int> BOM_senders;
199 207

  
200 208
            // Each scout has a unique id number, which is also displayed on its image.
201 209
            int scout_id;
......
211 219
            ros::ServiceServer set_pen_srv;
212 220
            ros::ServiceServer query_encoders_srv;
213 221
            ros::ServiceServer query_linesensor_srv;
222
            ros::ServiceServer query_BOM_srv;
214 223
            ros::ServiceServer toggle_sonar_srv;
215 224
            ros::ServiceServer set_sonar_srv;
216 225

  

Also available in: Unified diff