Project

General

Profile

Statistics
| Branch: | Revision:

root / scout / libscout / src / behaviors / WH_Robot.cpp @ 1905324e

History | View | Annotate | Download (5.03 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
}
12

    
13
WH_Robot::~WH_Robot()
14
{
15
  delete(nav_map);
16
}
17

    
18
Duration WH_Robot::get_worst_case_time(State start_state, State target_state)
19
{
20
  return nav_map->get_worst_case_time(start_state, target_state);
21
}
22

    
23
/** @brief Based on the given path, make
24
 *         the series of turns to follow this path,
25
 *         updating the current state in the navigation map as we do so   
26
 *  @param the Path to follow
27
 */
28
void WH_Robot::follow_path(Path path_to_follow){
29
  for(int i=0; i<path_to_follow.len; i++)
30
  {
31
    Turn t = path_to_follow.path[i];
32
    ROS_INFO("making turn %d", t);
33
    nav_map->update_state(t);
34
    switch(t)
35
    {
36
      case ISTRAIGHT:
37
        follow_line();
38
        break;
39
      case ILEFT:
40
        turn_left();
41
        follow_line();
42
        break;
43
      case IRIGHT:
44
        turn_right();
45
        follow_line();
46
        break;
47
      case IUTURN:
48
        u_turn();
49
        follow_line();
50
        break;
51
    }
52
  }  
53
}
54

    
55
int WH_Robot::exec_task()
56
{
57
  ROS_INFO("WH_robot: Executing a task");
58
  assert(curr_task != DEFAULT_TASK);
59
  
60
  // remember where you started doing this task so we know where to return
61
  State home_state = nav_map->get_state();
62
  ROS_INFO("WH_robot: starting from home state %d", (int)home_state);
63
  ROS_INFO("WH_robot: aiming for state %d", (int)curr_task->get_dest());
64
  Path new_path = nav_map->shortest_path(curr_task->get_dest());
65
  curr_task->set_path(new_path);
66

    
67
  follow_path(new_path);
68
   
69
  //TODO: forklift yaaaay
70

    
71
  int did_task_complete;
72

    
73
  srand(0xDEADBEEF);
74
  int error = rand() % 12;
75
  if(error < 6) //Fail with 1/2 probability
76
  {
77
    ROS_INFO("WH_robot: TASK COMPLETE!");
78
    did_task_complete = TASK_COMPLETED;
79
  }
80
  else
81
  {
82
    ROS_INFO("WH_robot: TASK FAILED!");
83
    did_task_complete = TASK_FAILED;
84
  }
85

    
86
  ROS_INFO("WH_robot: Now I am attempting to go home from state %d to state %d", 
87
        (int)nav_map->get_state(), (int)home_state);
88

    
89
  Path return_path = nav_map->shortest_path(home_state);
90
  curr_task->set_path(return_path);
91
  
92
  follow_path(return_path);
93

    
94
  return did_task_complete;
95
}
96

    
97
void WH_Robot::robot_callback(const std_msgs::String::ConstPtr& msg)
98
{
99
  std::cout << "robot callback called." << std::endl;
100
  if(msg->data.compare(0, 11, "REG_SUCCESS") == 0)
101
  {
102
    id = atoi(msg->data.substr(12).c_str());
103
    reg_failed = 0;
104
  }
105
  else if(msg->data.compare(0, 8, "SET_TASK") == 0)
106
  {
107
    ROS_INFO("WH_ROBOT: Setting robot task");
108
    char* string = (char*)msg->data.c_str();
109
    ROS_INFO("Set task string is: %s", string);
110
    char* data;
111
    data = strtok(string, " ");
112
    data = strtok(NULL, " ");
113
    int order_id = atoi(data);
114
    ROS_INFO("order Id: %d with string %s", order_id, data);
115

    
116
    data = strtok(NULL, " ");
117
    Address source = atoi(data);
118
    ROS_INFO("source: %d with string %s", source, data);
119

    
120
    data = strtok(NULL, " ");
121
    Address dest = atoi(data);
122
    ROS_INFO("dest: %d with string %s", dest, data);
123

    
124
    Time start_time = ros::Time::now();
125
    Path path;
126
    path.len = 0;
127
    path.path = NULL;
128
    Duration est_time(0);
129

    
130
    curr_task = new Order(order_id, source, dest, start_time, path, est_time);
131
  }
132
  else
133
  {
134
    ROS_INFO("I got a bad message: %s", msg->data.c_str());
135
  }
136
}
137

    
138
void WH_Robot::run ()
139
{
140
  ROS_INFO("A WH_Robot has been created");
141

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

    
145
  ROS_INFO("I am a robot. Registering with scheduler...");
146
  while(reg_failed && ok())
147
  {
148
    std_msgs::String msg;
149
    std::stringstream ss;
150
    ss << "REGISTER "<<name;
151
    msg.data = ss.str();
152
    robot_to_sched.publish(msg);
153

    
154
    spinOnce();
155
  }
156

    
157
  follow_line();
158

    
159
  while(ok())
160
  {
161
    ROS_INFO("WH_ROBOT: Running main loop");
162

    
163

    
164
      std_msgs::String msg;
165
      std::stringstream ss;
166
      ss << "GET_TASK "<<id;
167
      msg.data = ss.str();
168
      robot_to_sched.publish(msg);
169

    
170
    while(curr_task == DEFAULT_TASK && ok()){
171
      spinOnce();
172
    }
173

    
174
    int error = exec_task();
175
    if(error == TASK_COMPLETED)
176
    {
177
      std_msgs::String msg;
178
      std::stringstream ss;
179
      ss << "SUCCESS "<<curr_task->getid();
180
      msg.data = ss.str();
181
      robot_to_sched.publish(msg);
182
    }
183
    else //error == TASK_FAILED
184
    {
185
      std_msgs::String msg;
186
      std::stringstream ss;
187
      ss << "FAILED "<<curr_task->getid();
188
      msg.data = ss.str();
189
      robot_to_sched.publish(msg);
190
    }
191
    delete curr_task;
192
    curr_task = DEFAULT_TASK;
193

    
194
  }
195
}
196

    
197
void WH_Robot::set_task(Order order)
198
{
199
  curr_task = new Order(order.getid(), order.get_source(), order.get_dest(), 
200
      order.get_start_time(), order.get_path(), order.get_est_time()); 
201
  return;
202
}
203