root / scout / libscout / src / behaviors / WH_Robot.cpp @ 5755691e
History | View | Annotate | Download (5.83 KB)
1 |
#include "WH_Robot.h" |
---|---|
2 |
#include "../helper_classes/Order.h" |
3 |
|
4 |
/** @Brief: warehouse robot constructor **/
|
5 |
WH_Robot::WH_Robot(std::string scoutname):line_follow(scoutname)
|
6 |
{ |
7 |
nav_map = new navigationMap(scoutname);
|
8 |
curr_task = DEFAULT_TASK; |
9 |
name = scoutname; |
10 |
reg_failed = 1;
|
11 |
srand(0xDEADBEEF);
|
12 |
} |
13 |
|
14 |
WH_Robot::~WH_Robot() |
15 |
{ |
16 |
delete(nav_map);
|
17 |
} |
18 |
|
19 |
Duration WH_Robot::get_worst_case_time(State start_state, State target_state) |
20 |
{ |
21 |
return nav_map->get_worst_case_time(start_state, target_state);
|
22 |
} |
23 |
|
24 |
/** @brief Drives from state 2 to the robot home base and goes to sleep for
|
25 |
* x seconds
|
26 |
*/
|
27 |
void WH_Robot::go_home(int x) |
28 |
{ |
29 |
unsigned int curr_state = nav_map->get_state(); |
30 |
if(curr_state != 2) |
31 |
{ |
32 |
ROS_WARN("Tried to go home from incorrect state %d", curr_state);
|
33 |
return;
|
34 |
} |
35 |
turn_straight(); |
36 |
follow_line(); |
37 |
turn_left(); |
38 |
follow_line(); |
39 |
Duration sleep_time(x); |
40 |
sleep_time.sleep(); |
41 |
return;
|
42 |
} |
43 |
|
44 |
void WH_Robot::leave_home()
|
45 |
{ |
46 |
unsigned int curr_state = nav_map->get_state(); |
47 |
if(curr_state != 2) |
48 |
{ |
49 |
ROS_WARN("Tried to go home from incorrect state %d", curr_state);
|
50 |
return;
|
51 |
} |
52 |
turn_straight(); |
53 |
follow_line(); |
54 |
nav_map->update_state(ISTRAIGHT); |
55 |
turn_left(); |
56 |
follow_line(); |
57 |
} |
58 |
|
59 |
/** @brief Based on the given path, make
|
60 |
* the series of turns to follow this path,
|
61 |
* updating the current state in the navigation map as we do so
|
62 |
* @param the Path to follow
|
63 |
*/
|
64 |
void WH_Robot::follow_path(Path path_to_follow){
|
65 |
for(int i=0; i<path_to_follow.len; i++) |
66 |
{ |
67 |
Turn t = path_to_follow.path[i]; |
68 |
unsigned int curr_state = nav_map->get_state(); |
69 |
|
70 |
nav_map->update_state(t); |
71 |
switch(t)
|
72 |
{ |
73 |
case ISTRAIGHT:
|
74 |
turn_straight(); |
75 |
follow_line(); |
76 |
if(curr_state == 2) |
77 |
{ |
78 |
turn_straight(); |
79 |
follow_line(); |
80 |
turn_straight(); |
81 |
follow_line(); |
82 |
} |
83 |
break;
|
84 |
case ILEFT:
|
85 |
turn_left(); |
86 |
follow_line(); |
87 |
break;
|
88 |
case IRIGHT:
|
89 |
if(9 <= curr_state && curr_state <= 12) |
90 |
{ |
91 |
turn_straight(); |
92 |
follow_line(); |
93 |
} |
94 |
turn_right(); |
95 |
follow_line(); |
96 |
if(curr_state <= 4) |
97 |
{ |
98 |
turn_straight(); |
99 |
follow_line(); |
100 |
} |
101 |
break;
|
102 |
case IUTURN:
|
103 |
u_turn(); |
104 |
follow_line(); |
105 |
break;
|
106 |
case ISPOTTURN:
|
107 |
spot_turn(); |
108 |
follow_line(); |
109 |
break;
|
110 |
} |
111 |
} |
112 |
} |
113 |
|
114 |
int WH_Robot::exec_task()
|
115 |
{ |
116 |
assert(curr_task != DEFAULT_TASK); |
117 |
|
118 |
// remember where you started doing this task so we know where to return
|
119 |
// State home_state = nav_map->get_state();
|
120 |
// For now, use state 2.
|
121 |
Path new_path = nav_map->shortest_path(curr_task->get_dest()); |
122 |
curr_task->set_path(new_path); |
123 |
|
124 |
follow_path(new_path); |
125 |
|
126 |
//TODO: forklift yaaaay
|
127 |
|
128 |
int did_task_complete;
|
129 |
|
130 |
int error = rand() % 12; |
131 |
if(error < 9) //Fail with 1/4 probability |
132 |
{ |
133 |
ROS_INFO("WH_robot: TASK COMPLETE!");
|
134 |
did_task_complete = TASK_COMPLETED; |
135 |
} |
136 |
else
|
137 |
{ |
138 |
ROS_INFO("WH_robot: TASK FAILED!");
|
139 |
did_task_complete = TASK_FAILED; |
140 |
} |
141 |
|
142 |
// For now use state 2 as home state
|
143 |
// Path return_path = nav_map->shortest_path(home_state);
|
144 |
Path return_path = nav_map->shortest_path(2);
|
145 |
curr_task->set_path(return_path); |
146 |
|
147 |
follow_path(return_path); |
148 |
|
149 |
return did_task_complete;
|
150 |
} |
151 |
|
152 |
void WH_Robot::robot_callback(const std_msgs::String::ConstPtr& msg) |
153 |
{ |
154 |
if(msg->data.compare(0, 11, "REG_SUCCESS") == 0) |
155 |
{ |
156 |
id = atoi(msg->data.substr(12).c_str());
|
157 |
reg_failed = 0;
|
158 |
} |
159 |
else if(msg->data.compare(0, 8, "SET_TASK") == 0) |
160 |
{ |
161 |
char* string = (char*)msg->data.c_str(); |
162 |
char* data;
|
163 |
data = strtok(string, " "); |
164 |
|
165 |
data = strtok(NULL, " "); |
166 |
int order_id = atoi(data);
|
167 |
|
168 |
data = strtok(NULL, " "); |
169 |
Address source = atoi(data); |
170 |
|
171 |
data = strtok(NULL, " "); |
172 |
Address dest = atoi(data); |
173 |
|
174 |
Time start_time = ros::Time::now(); |
175 |
Path path; |
176 |
path.len = 0;
|
177 |
path.path = NULL;
|
178 |
Duration est_time(0);
|
179 |
|
180 |
curr_task = new Order(order_id, source, dest, start_time, path, est_time);
|
181 |
} |
182 |
else
|
183 |
{ |
184 |
ROS_INFO("I got a bad message: %s", msg->data.c_str());
|
185 |
} |
186 |
} |
187 |
|
188 |
void WH_Robot::run ()
|
189 |
{ |
190 |
ROS_INFO("A WH_Robot has been created");
|
191 |
|
192 |
robot_to_sched = node.advertise<std_msgs::String>("robot_to_sched", 1000); |
193 |
sched_to_robot = node.subscribe(name + "_topic", 1000, &WH_Robot::robot_callback, this); |
194 |
|
195 |
ROS_INFO("I am a robot. Registering with scheduler...");
|
196 |
while(reg_failed && ok())
|
197 |
{ |
198 |
std_msgs::String msg; |
199 |
std::stringstream ss; |
200 |
ss << "REGISTER "<<name;
|
201 |
msg.data = ss.str(); |
202 |
robot_to_sched.publish(msg); |
203 |
|
204 |
spinOnce(); |
205 |
} |
206 |
|
207 |
follow_line(); |
208 |
|
209 |
while(ok())
|
210 |
{ |
211 |
ROS_INFO("WH_ROBOT: Running main loop");
|
212 |
|
213 |
|
214 |
std_msgs::String msg; |
215 |
std::stringstream ss; |
216 |
ss << "GET_TASK "<<id;
|
217 |
msg.data = ss.str(); |
218 |
robot_to_sched.publish(msg); |
219 |
|
220 |
while(curr_task == DEFAULT_TASK && ok()){
|
221 |
spinOnce(); |
222 |
} |
223 |
|
224 |
int error = exec_task();
|
225 |
|
226 |
/** Go to robot home base */
|
227 |
go_home(2);
|
228 |
leave_home(); |
229 |
|
230 |
if(error == TASK_COMPLETED)
|
231 |
{ |
232 |
std_msgs::String msg; |
233 |
std::stringstream ss; |
234 |
ss << "SUCCESS "<<curr_task->getid();
|
235 |
msg.data = ss.str(); |
236 |
robot_to_sched.publish(msg); |
237 |
} |
238 |
else //error == TASK_FAILED |
239 |
{ |
240 |
std_msgs::String msg; |
241 |
std::stringstream ss; |
242 |
ss << "FAILED "<<curr_task->getid();
|
243 |
msg.data = ss.str(); |
244 |
robot_to_sched.publish(msg); |
245 |
} |
246 |
delete curr_task;
|
247 |
curr_task = DEFAULT_TASK; |
248 |
|
249 |
} |
250 |
} |
251 |
|
252 |
void WH_Robot::set_task(Order order)
|
253 |
{ |
254 |
curr_task = new Order(order.getid(), order.get_source(), order.get_dest(),
|
255 |
order.get_start_time(), order.get_path(), order.get_est_time()); |
256 |
return;
|
257 |
} |
258 |
|