Revision 58c19c15
ID | 58c19c15b13ea81473e724302b2c64e055aaac82 |
better warehouse image (corresponds with lines now) and demo. Now only thing left is to implement home behavior.
scout/libscout/src/behaviors/WH_Robot.cpp | ||
---|---|---|
8 | 8 |
curr_task = DEFAULT_TASK; |
9 | 9 |
name = scoutname; |
10 | 10 |
reg_failed = 1; |
11 |
srand(0xDEADBEEF); |
|
11 | 12 |
} |
12 | 13 |
|
13 | 14 |
WH_Robot::~WH_Robot() |
... | ... | |
29 | 30 |
for(int i=0; i<path_to_follow.len; i++) |
30 | 31 |
{ |
31 | 32 |
Turn t = path_to_follow.path[i]; |
33 |
unsigned int curr_state = nav_map->get_state(); |
|
34 |
|
|
32 | 35 |
ROS_INFO("making turn %d", t); |
36 |
|
|
33 | 37 |
nav_map->update_state(t); |
34 | 38 |
switch(t) |
35 | 39 |
{ |
... | ... | |
42 | 46 |
follow_line(); |
43 | 47 |
break; |
44 | 48 |
case IRIGHT: |
49 |
if(9 <= curr_state && curr_state <= 12) |
|
50 |
{ |
|
51 |
turn_straight(); |
|
52 |
follow_line(); |
|
53 |
} |
|
45 | 54 |
turn_right(); |
46 | 55 |
follow_line(); |
56 |
if(curr_state <= 4) |
|
57 |
{ |
|
58 |
turn_straight(); |
|
59 |
follow_line(); |
|
60 |
} |
|
47 | 61 |
break; |
48 | 62 |
case IUTURN: |
49 | 63 |
u_turn(); |
50 | 64 |
follow_line(); |
51 | 65 |
break; |
66 |
case ISPOTTURN: |
|
67 |
spot_turn(); |
|
68 |
follow_line(); |
|
69 |
break; |
|
52 | 70 |
} |
53 | 71 |
} |
54 | 72 |
} |
55 | 73 |
|
56 | 74 |
int WH_Robot::exec_task() |
57 | 75 |
{ |
58 |
ROS_INFO("WH_robot: Executing a task"); |
|
59 | 76 |
assert(curr_task != DEFAULT_TASK); |
60 | 77 |
|
61 | 78 |
// remember where you started doing this task so we know where to return |
62 | 79 |
State home_state = nav_map->get_state(); |
63 |
ROS_INFO("WH_robot: starting from home state %d", (int)home_state); |
|
64 |
ROS_INFO("WH_robot: aiming for state %d", (int)curr_task->get_dest()); |
|
65 | 80 |
Path new_path = nav_map->shortest_path(curr_task->get_dest()); |
66 | 81 |
curr_task->set_path(new_path); |
67 | 82 |
|
... | ... | |
71 | 86 |
|
72 | 87 |
int did_task_complete; |
73 | 88 |
|
74 |
srand(0xDEADBEEF); |
|
75 | 89 |
int error = rand() % 12; |
76 |
if(error < 6) //Fail with 1/2 probability
|
|
90 |
if(error < 9) //Fail with 1/4 probability
|
|
77 | 91 |
{ |
78 | 92 |
ROS_INFO("WH_robot: TASK COMPLETE!"); |
79 | 93 |
did_task_complete = TASK_COMPLETED; |
... | ... | |
84 | 98 |
did_task_complete = TASK_FAILED; |
85 | 99 |
} |
86 | 100 |
|
87 |
ROS_INFO("WH_robot: Now I am attempting to go home from state %d to state %d", |
|
88 |
(int)nav_map->get_state(), (int)home_state); |
|
89 |
|
|
90 | 101 |
Path return_path = nav_map->shortest_path(home_state); |
91 | 102 |
curr_task->set_path(return_path); |
92 | 103 |
|
... | ... | |
97 | 108 |
|
98 | 109 |
void WH_Robot::robot_callback(const std_msgs::String::ConstPtr& msg) |
99 | 110 |
{ |
100 |
std::cout << "robot callback called." << std::endl; |
|
101 | 111 |
if(msg->data.compare(0, 11, "REG_SUCCESS") == 0) |
102 | 112 |
{ |
103 | 113 |
id = atoi(msg->data.substr(12).c_str()); |
... | ... | |
105 | 115 |
} |
106 | 116 |
else if(msg->data.compare(0, 8, "SET_TASK") == 0) |
107 | 117 |
{ |
108 |
ROS_INFO("WH_ROBOT: Setting robot task"); |
|
109 | 118 |
char* string = (char*)msg->data.c_str(); |
110 |
ROS_INFO("Set task string is: %s", string); |
|
111 | 119 |
char* data; |
112 | 120 |
data = strtok(string, " "); |
121 |
|
|
113 | 122 |
data = strtok(NULL, " "); |
114 | 123 |
int order_id = atoi(data); |
115 |
ROS_INFO("order Id: %d with string %s", order_id, data); |
|
116 | 124 |
|
117 | 125 |
data = strtok(NULL, " "); |
118 | 126 |
Address source = atoi(data); |
119 |
ROS_INFO("source: %d with string %s", source, data); |
|
120 | 127 |
|
121 | 128 |
data = strtok(NULL, " "); |
122 | 129 |
Address dest = atoi(data); |
123 |
ROS_INFO("dest: %d with string %s", dest, data); |
|
124 | 130 |
|
125 | 131 |
Time start_time = ros::Time::now(); |
126 | 132 |
Path path; |
Also available in: Unified diff