Project

General

Profile

Statistics
| Branch: | Revision:

scoutos / scout / libscout / src / behaviors / WH_Robot.cpp @ 58c19c15

History | View | Annotate | Download (4.79 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 Based on the given path, make
25
 *         the series of turns to follow this path,
26
 *         updating the current state in the navigation map as we do so   
27
 *  @param the Path to follow
28
 */
29
void WH_Robot::follow_path(Path path_to_follow){
30
  for(int i=0; i<path_to_follow.len; i++)
31
  {
32
    Turn t = path_to_follow.path[i];
33
    unsigned int curr_state = nav_map->get_state();
34

    
35
    ROS_INFO("making turn %d", t);
36

    
37
    nav_map->update_state(t);
38
    switch(t)
39
    {
40
      case ISTRAIGHT:
41
        turn_straight();
42
        follow_line();
43
        break;
44
      case ILEFT:
45
        turn_left();
46
        follow_line();
47
        break;
48
      case IRIGHT:
49
        if(9 <= curr_state && curr_state <= 12)
50
        {
51
          turn_straight();
52
          follow_line();
53
        }
54
        turn_right();
55
        follow_line();
56
        if(curr_state <= 4)
57
        {
58
          turn_straight();
59
          follow_line();
60
        }
61
        break;
62
      case IUTURN:
63
        u_turn();
64
        follow_line();
65
        break;
66
      case ISPOTTURN:
67
        spot_turn();
68
        follow_line();
69
        break;
70
    }
71
  }  
72
}
73

    
74
int WH_Robot::exec_task()
75
{
76
  assert(curr_task != DEFAULT_TASK);
77
  
78
  // remember where you started doing this task so we know where to return
79
  State home_state = nav_map->get_state();
80
  Path new_path = nav_map->shortest_path(curr_task->get_dest());
81
  curr_task->set_path(new_path);
82

    
83
  follow_path(new_path);
84
   
85
  //TODO: forklift yaaaay
86

    
87
  int did_task_complete;
88

    
89
  int error = rand() % 12;
90
  if(error < 9) //Fail with 1/4 probability
91
  {
92
    ROS_INFO("WH_robot: TASK COMPLETE!");
93
    did_task_complete = TASK_COMPLETED;
94
  }
95
  else
96
  {
97
    ROS_INFO("WH_robot: TASK FAILED!");
98
    did_task_complete = TASK_FAILED;
99
  }
100

    
101
  Path return_path = nav_map->shortest_path(home_state);
102
  curr_task->set_path(return_path);
103
  
104
  follow_path(return_path);
105

    
106
  return did_task_complete;
107
}
108

    
109
void WH_Robot::robot_callback(const std_msgs::String::ConstPtr& msg)
110
{
111
  if(msg->data.compare(0, 11, "REG_SUCCESS") == 0)
112
  {
113
    id = atoi(msg->data.substr(12).c_str());
114
    reg_failed = 0;
115
  }
116
  else if(msg->data.compare(0, 8, "SET_TASK") == 0)
117
  {
118
    char* string = (char*)msg->data.c_str();
119
    char* data;
120
    data = strtok(string, " ");
121

    
122
    data = strtok(NULL, " ");
123
    int order_id = atoi(data);
124

    
125
    data = strtok(NULL, " ");
126
    Address source = atoi(data);
127

    
128
    data = strtok(NULL, " ");
129
    Address dest = atoi(data);
130

    
131
    Time start_time = ros::Time::now();
132
    Path path;
133
    path.len = 0;
134
    path.path = NULL;
135
    Duration est_time(0);
136

    
137
    curr_task = new Order(order_id, source, dest, start_time, path, est_time);
138
  }
139
  else
140
  {
141
    ROS_INFO("I got a bad message: %s", msg->data.c_str());
142
  }
143
}
144

    
145
void WH_Robot::run ()
146
{
147
  ROS_INFO("A WH_Robot has been created");
148

    
149
  robot_to_sched = node.advertise<std_msgs::String>("robot_to_sched", 1000);
150
  sched_to_robot = node.subscribe(name + "_topic", 1000, &WH_Robot::robot_callback, this);
151

    
152
  ROS_INFO("I am a robot. Registering with scheduler...");
153
  while(reg_failed && ok())
154
  {
155
    std_msgs::String msg;
156
    std::stringstream ss;
157
    ss << "REGISTER "<<name;
158
    msg.data = ss.str();
159
    robot_to_sched.publish(msg);
160

    
161
    spinOnce();
162
  }
163

    
164
  follow_line();
165

    
166
  while(ok())
167
  {
168
    ROS_INFO("WH_ROBOT: Running main loop");
169

    
170

    
171
      std_msgs::String msg;
172
      std::stringstream ss;
173
      ss << "GET_TASK "<<id;
174
      msg.data = ss.str();
175
      robot_to_sched.publish(msg);
176

    
177
    while(curr_task == DEFAULT_TASK && ok()){
178
      spinOnce();
179
    }
180

    
181
    int error = exec_task();
182
    if(error == TASK_COMPLETED)
183
    {
184
      std_msgs::String msg;
185
      std::stringstream ss;
186
      ss << "SUCCESS "<<curr_task->getid();
187
      msg.data = ss.str();
188
      robot_to_sched.publish(msg);
189
    }
190
    else //error == TASK_FAILED
191
    {
192
      std_msgs::String msg;
193
      std::stringstream ss;
194
      ss << "FAILED "<<curr_task->getid();
195
      msg.data = ss.str();
196
      robot_to_sched.publish(msg);
197
    }
198
    delete curr_task;
199
    curr_task = DEFAULT_TASK;
200

    
201
  }
202
}
203

    
204
void WH_Robot::set_task(Order order)
205
{
206
  curr_task = new Order(order.getid(), order.get_source(), order.get_dest(), 
207
      order.get_start_time(), order.get_path(), order.get_est_time()); 
208
  return;
209
}
210