state_machine.cpp
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
35 #ifndef _STATE_MACHINE_CPP_
36 #define _STATE_MACHINE_CPP_
37 
38 #include "follow_pedestrian.h"
39 
40 void state_machine(void)
41 {
42 
43 
44  a_h = (((double)rand())/(double)RAND_MAX);
45 
46 
47 
48 
50  //if (status.CONTROL_CAR_SPEED)
51 
52  //sprintf(text,"%s",status.CONTROL_CAR_SPEED?"CAR SPEED AUTOMATIC CONTROL (press A to change)":"CAR SPEED MANUAL CONTROL (press A to change)");
53  //draw_text_on_glwindow(t_viewpoint.glwindow.width/2, t_viewpoint.glwindow.height-20,text);
54 
55  //sprintf(text,"(press R to abort tracking)");
56  //draw_text_on_glwindow(t_viewpoint.glwindow.width/2, t_viewpoint.glwindow.height-20*2,text);
57 
58  //sprintf(text,"%s",do_execute_tutorial?"Tutorial On (press t to change)":"Tutorial Off (press t to change)");
59  //draw_text_on_glwindow(t_viewpoint.glwindow.width/2, t_viewpoint.glwindow.height-20*3,text);
60 
61 
62 
63  //sprintf(text,"Direction: %f",hc.direction);
64  //draw_text_on_glwindow(10, t_viewpoint.glwindow.height-60,text);
65  //sprintf(text,"Speed: %f",hc.speed);
66  //draw_text_on_glwindow(10, t_viewpoint.glwindow.height-75,text);
67 
68  //sprintf(text,"Lights: Left %s Right %s Max %s Med %s ",hc.lights_left?"On":"Off",hc.lights_right?"On":"Off",hc.lights_high?"On":"Off",hc.lights_medium?"On":"Off");
69  //draw_text_on_glwindow(10, t_viewpoint.glwindow.height-90,text);
70 
71 
73 
74  //if (status.state==TRACKING || status.state==TRACKING_NOT_SAFE) //if were tracking someone, lets draw it
75  //{
76  //}
77 
78  printf("status.target_found=%d\n",status.target_found);
79  printf("status.last_id=%d\n",status.last_id);
80 
82  status.target_found=false;
83  int should_move=false;
84  double dist_to_target=1000;
85 
86 
87 
88  print_status(&status);
92  switch(status.state)
93  {
95  case INITIALISE:
96 
99 
101  //bring the ptu to home position
102  foveationcontrol_home();
103 
104  //setting up the high command message
105  status.direction = DIRECTION_IN_FRONT;
106 // set_high_command_msg_direction_speed(command_msg, status.direction, SPEED_STOP);
107 // set_high_command_msg_lights(command_msg, LIGHT_OFF, LIGHT_OFF, LIGHT_OFF, LIGHT_OFF, LIGHT_ON);
108 
109 
111  status.previous_state=INITIALISE; //unconditional transition to searching state
112  status.state=SEARCHING;
114  //none here
115 
116  break;
118  case SEARCHING:
119 
122  if (status.previous_state!=SEARCHING) //update start of SEARCHING state tic
123  {
124  status.tic_searching=ros::Time::now();
125  }
126 
128  //search for a target
129  status.target_found = search_for_new_target(&targets, &status,&search_area);
130  printf("status.target_found=%d\n",status.target_found);
131  status.last_id=status.target_id;
132 
133  play_sound(4, 10);
134  foveationcontrol_sweeping();
135 
136  //setting up the high command message
137 // status.direction = command_msg.steering_wheel;
138 // set_high_command_msg_direction_speed(command_msg, status.direction, SPEED_STOP);
139 // set_high_command_msg_lights(command_msg, LIGHT_OFF, LIGHT_OFF, LIGHT_OFF, LIGHT_OFF, LIGHT_ON);
140 
142  if(status.target_found && !is_safe_using_lasers()) //if a target but safe zone not clear we transit to TRACKING_NOT_SAFE
143  {
144  status.previous_state=SEARCHING;
145  status.state=TRACKING_NOT_SAFE;
147  play_sound(2, 10);
148  }
149  else if(status.target_found) //if a target is found we transit to tracking
150  {
151  status.previous_state=SEARCHING;
152  status.state=TRACKING;
154  play_sound(0, -1);
155  }
156  break;
158  case TRACKING:
159  if (status.previous_state!=TRACKING) //update start of SEARCHING state tic
162  {
163  status.tic_tracking=ros::Time::now();
164  }
165 
167  foveationcontrol(&status);//do foveationcontrol
168  status.target_found=get_new_target_information(&targets, &status);
169 
170  //setting up the high command message
171  play_sound(1, 15);
172 
173  //send pedestrian marker
174 
175 
176  status.direction = atan2(status.current_y,status.current_x);
177 // set_high_command_msg_direction_speed(command_msg, status.direction, SPEED_MOVE_SLOW);
178 // set_high_command_msg_lights(command_msg, LIGHT_OFF, LIGHT_ON, LIGHT_OFF, LIGHT_OFF, LIGHT_ON);
179 
181  if(status.reset_tracking==true)//user ordered a reset of tracking
182  {
183  status.previous_state=TRACKING;
184  status.state=SEARCHING;
185  status.reset_tracking = false;
187  play_sound(5, -1);
188  }
189  else if(status.target_found==false || status.current_x<3.0)//target was lost
190  {
191  status.previous_state=TRACKING;
192  status.state=TARGET_LOST;
194  play_sound(5, -1);
195 
196  }else if (!is_safe_using_lasers())
197  {
198  status.previous_state=TRACKING;
199  status.state=TRACKING_NOT_SAFE;
201  if (dist_to_target<6)
202  play_sound(6, -1);
203  else
204  play_sound(2, -1);
205  }
206  break;
208  case TRACKING_NOT_SAFE:
209  if (status.previous_state!=TRACKING_NOT_SAFE) //update start of SEARCHING state tic
212  {
213  status.tic_tracking_not_safe=ros::Time::now();
214  }
215 
217  status.target_found = get_new_target_information(&targets, &status);
218  foveationcontrol(&status);//do foveationcontrol
219 
220  if (status.target_found)
221  {
222  dist_to_target = sqrt(pow(status.current_x-2.7,2) + pow(status.current_y,2));
223  printf("status.target_id=%d\n",status.target_id);
224  printf("dist_to_target=%f\n",dist_to_target);
225  if (dist_to_target<4)
226  play_sound(6, 10);
227  else
228  play_sound(2, 10);
229  }
230 
231 
232  //setting up the high command message
233  status.direction = atan2(status.current_y,status.current_x);
234 // set_high_command_msg_direction_speed(command_msg, status.direction, SPEED_STOP);
235 // set_high_command_msg_lights(command_msg, LIGHT_OFF, LIGHT_ON, LIGHT_ON, LIGHT_ON, LIGHT_ON);
236 
238  if(status.reset_tracking==true)//user ordered a reset of tracking
239  {
240  status.previous_state=TRACKING_NOT_SAFE;
241  status.state=SEARCHING;
242  status.reset_tracking = false;
244 
245  }
246  else if(status.target_found==false || status.current_x<3.0)//target was lost
247  {
248  status.previous_state=TRACKING_NOT_SAFE;
249  status.state=TARGET_LOST;
251  play_sound(5, -1);
252 
253  }
254  else if (is_safe_using_lasers())
255  {
256  int tmp = status.previous_state;
257  status.previous_state=TRACKING_NOT_SAFE;
258  status.state=TRACKING;
260  if (tmp!=SEARCHING)
261  {
262  play_sound(3, -1);
263  }
264  else
265  {
266  }
267  }
268 
269  break;
271  case TARGET_LOST:
272 
275 
277  foveationcontrol_home();
278 
279  //setting up the high command message
280 // set_high_command_msg_direction_speed(command_msg, command_msg.steering_wheel, SPEED_STOP);
281 // set_high_command_msg_lights(command_msg, LIGHT_OFF, LIGHT_OFF, LIGHT_OFF, LIGHT_OFF, LIGHT_ON);
282 
283 
285  status.previous_state=TARGET_LOST;
286  status.state=SEARCHING; //unconditional transition to SEARCHING
287 
288 
289  break;
291  default:
292 
294  ROS_ERROR("WARNING DANGER unknown state in state machine abort demonstration");
295  //setting up the high command message
296 // set_high_command_msg_direction_speed(command_msg, command_msg.steering_wheel, SPEED_STOP);
297 // set_high_command_msg_lights(command_msg, LIGHT_OFF, LIGHT_OFF, LIGHT_OFF, LIGHT_OFF, LIGHT_ON);
298  break;
299  }
300 
301  //if (!status.CONTROL_CAR_SPEED)
302  //{
303  //hc.speed = SPEED_STOP;
304  //}
305 
306 // command_msg.header.stamp = ros::Time::now();
307 // command_pub.publish(command_msg);
308 }
309 
310 
311 #endif
#define DIRECTION_IN_FRONT
void state_machine(void)
Planar scan generator.


follow_pedestrian
Author(s): Miguel Oliveira, Jorge Almeida
autogenerated on Mon Mar 2 2015 01:31:38