Revision 7ac5e9bc
ROS scheduler/whrobot behavior needs to be debugged
scout/libscout/src/behaviors/WH_Robot.cpp | ||
---|---|---|
4 | 4 |
/** @Brief: warehouse robot constructor **/ |
5 | 5 |
WH_Robot::WH_Robot(std::string scoutname):Behavior(scoutname, "WH_Robot") |
6 | 6 |
{ |
7 |
ROS_INFO("WH_ROBOT: Creating a WH_Robot..."); |
|
8 | 7 |
nav_map = new navigationMap(scoutname); |
9 | 8 |
curr_task = DEFAULT_TASK; |
10 | 9 |
name = scoutname; |
11 | 10 |
reg_failed = 1; |
12 | 11 |
|
13 |
robot_to_sched = n.advertise<std_msgs::String>(name + "_topic", 1000); |
|
14 |
sched_to_robot = n.subscribe("sched_to_robot", 1000, msg_callback); |
|
15 |
|
|
16 |
while(reg_failed) |
|
17 |
{ |
|
18 |
std_msgs::String msg; |
|
19 |
std::stringstream ss; |
|
20 |
ss << "REGISTER "<<name; |
|
21 |
msg.data = ss.str(); |
|
22 |
robot_to_sched.publish(msg); |
|
23 |
} |
|
24 |
|
|
25 |
ROS_INFO("WH_Robot: I am a created WH robot"); |
|
12 |
robot_to_sched = node.advertise<std_msgs::String>("robot_to_sched", 1000); |
|
13 |
sched_to_robot = node.subscribe(name + "_topic", 1000, &WH_Robot::robot_callback, this); |
|
14 |
ROS_INFO("A WH_Robot has been created"); |
|
26 | 15 |
} |
27 | 16 |
|
28 | 17 |
WH_Robot::~WH_Robot() |
... | ... | |
54 | 43 |
} |
55 | 44 |
} |
56 | 45 |
|
57 |
void WH_Robot::msg_callback(const std_msgs::String::ConstPtr& msg)
|
|
46 |
void WH_Robot::robot_callback(const std_msgs::String::ConstPtr& msg)
|
|
58 | 47 |
{ |
59 | 48 |
if(msg->data.compare(0, 11, "REG_SUCCESS") == 0) |
60 | 49 |
{ |
50 |
id = atoi(msg->data.substr(12).c_str()); |
|
61 | 51 |
reg_failed = 0; |
62 | 52 |
} |
63 | 53 |
else if(msg->data.compare(0, 8, "SET_TASK") == 0) |
64 | 54 |
{ |
65 |
char* string = msg->data.c_str(); |
|
55 |
char* string = (char*)msg->data.c_str();
|
|
66 | 56 |
char* data; |
67 | 57 |
data = strtok(string, " "); |
68 |
int id = atoi(data); |
|
58 |
int order_id = atoi(data);
|
|
69 | 59 |
data = strtok(string, " "); |
70 | 60 |
Address source = atoi(data); |
71 | 61 |
data = strtok(string, " "); |
72 | 62 |
Address dest = atoi(data); |
73 | 63 |
Time start_time = ros::Time::now(); |
74 |
Path path = NULL; |
|
64 |
Path path; |
|
65 |
path.len = 0; |
|
66 |
path.path = NULL; |
|
75 | 67 |
Duration est_time(0); |
76 | 68 |
|
77 |
curr_task = new Order(id, source, dest, start_time, path, est_time); |
|
69 |
curr_task = new Order(order_id, source, dest, start_time, path, est_time);
|
|
78 | 70 |
} |
79 | 71 |
else |
80 | 72 |
{ |
81 |
ROS_INFO("I got a bad message: %s", msg->data); |
|
73 |
ROS_INFO("I got a bad message: %s", msg->data.c_str());
|
|
82 | 74 |
} |
83 | 75 |
} |
84 | 76 |
|
85 | 77 |
void WH_Robot::run () |
86 | 78 |
{ |
79 |
ROS_INFO("I am a robot. Registering with scheduler..."); |
|
80 |
while(reg_failed) |
|
81 |
{ |
|
82 |
std_msgs::String msg; |
|
83 |
std::stringstream ss; |
|
84 |
ss << "REGISTER "<<name; |
|
85 |
msg.data = ss.str(); |
|
86 |
robot_to_sched.publish(msg); |
|
87 |
|
|
88 |
spinOnce(); |
|
89 |
} |
|
87 | 90 |
|
88 | 91 |
while(ok()) |
89 | 92 |
{ |
... | ... | |
96 | 99 |
msg.data = ss.str(); |
97 | 100 |
robot_to_sched.publish(msg); |
98 | 101 |
|
102 |
spinOnce(); |
|
99 | 103 |
|
100 | 104 |
while(curr_task == DEFAULT_TASK) |
101 | 105 |
continue; |
... | ... | |
104 | 108 |
{ |
105 | 109 |
|
106 | 110 |
|
107 |
ss << "SUCCESS "<<curr_task->id;
|
|
111 |
ss << "SUCCESS "<<curr_task->getid();
|
|
108 | 112 |
msg.data = ss.str(); |
109 | 113 |
robot_to_sched.publish(msg); |
110 | 114 |
|
... | ... | |
114 | 118 |
{ |
115 | 119 |
|
116 | 120 |
|
117 |
ss << "FAILED "<<curr_task->id;
|
|
121 |
ss << "FAILED "<<curr_task->getid();
|
|
118 | 122 |
msg.data = ss.str(); |
119 | 123 |
robot_to_sched.publish(msg); |
120 | 124 |
|
Also available in: Unified diff