manager.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 ***************************************************************************************************/
32 #include "manager.h"
33 
34 namespace atlascar_base
35 {
36 
37 Manager::Manager(const ros::NodeHandle& nh)
38 :nh_(nh)
39 {}
40 
42 {}
43 
45 {
46  safety_command_.reset(new atlascar_base::ManagerCommand);
47 
48  //Set the safety message default values, this messages will never be removed from the list
49  safety_command_->lifetime=INFINITY;
50  safety_command_->priority=0;
51 
53 
54  //Push the safety message into the queue
56 }
57 
59 {
60  command_sub_ = nh_.subscribe("command", 1, &Manager::commandCallback, this);
61 
62  status_plc_sub_ = nh_.subscribe("plc_status", 1, &Manager::plcStatusCallback, this);
63  status_driver_sub_ = nh_.subscribe("driver_status", 1, &Manager::driverStatusCallback, this);
64  status_odometer_sub_ = nh_.subscribe("odometer_status", 1, &Manager::odometerStatusCallback, this);
65  status_gearbox_sub_ = nh_.subscribe("gearbox_status", 1, &Manager::gearboxStatusCallback, this);
66  status_throttle_sub_ = nh_.subscribe("throttle_status", 1, &Manager::throttleStatusCallback, this);
67 
68  status_pub_ = nh_.advertise<atlascar_base::ManagerStatus>("status", 1);
69 
70  command_plc_pub_ = nh_.advertise<atlascar_base::PlcCommand>("plc_command", 1);
71 
72  command_gearbox_pub_ = nh_.advertise<atlascar_base::GearboxCommand>("gearbox_command", 1);
73  command_throttle_pub_ = nh_.advertise<atlascar_base::ThrottleCommand>("throttle_command", 1);
74 }
75 
76 void Manager::toOutgoingMessages(const atlascar_base::ManagerCommandPtr& command)
77 {
78  gearbox_command_.gear=command->gear;
79  gearbox_command_.priority=command->priority;
80  gearbox_command_.lifetime=command->lifetime;
81 
82  gearbox_command_.header=command->header;
83 
84  plc_command_.clutch=command->clutch;
85  plc_command_.brake=command->brake;
86  plc_command_.steering_wheel=command->steering_wheel;
87  plc_command_.rpm=0;
88  plc_command_.lights_high=command->lights_high;
89  plc_command_.lights_medium=command->lights_medium;
90  plc_command_.lights_minimum=0;
91  plc_command_.lights_left=command->lights_left;
92  plc_command_.lights_right=command->lights_right;
93  plc_command_.lights_brake=command->lights_brake;
94  plc_command_.lights_reverse=command->lights_reverse;
95  plc_command_.lights_warning=command->lights_warning;
96  plc_command_.ignition=command->ignition;
97  plc_command_.emergency=command->emergency;
98  plc_command_.auto_ignition=command->auto_ignition;
99  plc_command_.auto_brake=command->auto_brake;
100  plc_command_.auto_direction=command->auto_direction;
101  plc_command_.auto_clutch=command->auto_clutch;
102 
103  plc_command_.priority=command->priority;
104  plc_command_.lifetime=command->lifetime;
105 
106  plc_command_.header=command->header;
107 
108  throttle_command_.throttle=command->throttle;
109  throttle_command_.mode=command->auto_throttle;
110  throttle_command_.priority=command->priority;
111  throttle_command_.lifetime=command->lifetime;
112  throttle_command_.header=command->header;
113 
114 }
115 
116 void Manager::commandCallback(const atlascar_base::ManagerCommandPtr& command)
117 {
118  command_queue_.push_msg(command);
119 }
120 
121 void Manager::plcStatusCallback(const atlascar_base::PlcStatusPtr& status)
122 {
123  status_.clutch = status->clutch;
124  status_.brake = status->brake;
125  status_.steering_wheel = status->steering_wheel;
126  status_.rpm = status->rpm;
127 
128  status_.lights_brake=status->lights_brake;
129  status_.lights_reverse=status->lights_reverse;
130  status_.lights_warning=status->lights_warning;
131 
132  status_.emergency=status->emergency;
133  status_.auto_ignition=status->auto_ignition;
134  status_.auto_brake=status->auto_brake;
135  status_.auto_direction=status->auto_direction;
136  status_.auto_clutch=status->auto_clutch;
137 }
138 
139 void Manager::driverStatusCallback(const human_driver_monitor::HumanDriverMonitorStatusPtr& status)
140 {
141  status_.lights_high=status->lights_high;
142  status_.lights_medium=status->lights_medium;
143  status_.lights_left=status->lights_left;
144  status_.lights_right=status->lights_right;
145  status_.lights_danger=status->lights_danger;
146 
147  status_.ignition=status->ignition;
148 
149  status_.horn=status->horn;
150 
151  status_.throttle_pressure=status->throttle_pressure;
152  status_.brake_pressure=status->brake_pressure;
153  status_.clutch_pressure=status->clutch_pressure;
154 }
155 
156 void Manager::odometerStatusCallback(const odometer::OdometerStatusPtr& status)
157 {
158  status_.velocity=status->velocity;
159  status_.count=status->count;
160  status_.pulses_sec=status->pulses_sec;
161  status_.revolutions_sec=status->revolutions_sec;
162 }
163 
164 void Manager::gearboxStatusCallback(const atlascar_base::GearboxStatusPtr& status)
165 {
166  status_.gear=status->gear;
167  status_.gearbox_status=status->status;
168 }
169 
170 void Manager::throttleStatusCallback(const atlascar_base::ThrottleStatusPtr& status)
171 {
172  status_.throttle=status->throttle;
173  status_.throttle_pedal=status->footPedal;
174  status_.auto_throttle=status->mode;
175 }
176 
178 {
179  double limit = 1.2;
180  double zero = 0.001;
181 
182  CarState new_state = current_state;
183 
184  if( abs(status_.velocity) < zero && abs(command_->velocity) < zero)
185  new_state = STOPPED;
186 
187  if( abs(status_.velocity) < limit && abs(command_->velocity) > limit)
188  new_state = STOPPED_TO_MOVING;
189 
190  if( abs(status_.velocity) > limit && abs(command_->velocity) > limit)
191  new_state = MOVING;
192 
193  if( abs(status_.velocity) > zero && abs(command_->velocity) < zero)
194  new_state = MOVING_TO_STOPPED;
195 
196  if(new_state != current_state && new_state == STOPPED_TO_MOVING)
197  stm_state = FIRST;
198 
199  if(new_state != current_state && new_state == MOVING_TO_STOPPED)
200  mts_state = FIRST;
201 
202  current_state = new_state;
203 
204  return current_state;
205 
206 }
207 
209 {
210  switch(mts_state)
211  {
212  //first stage
213  case FIRST:
214  throttle_command_.throttle = 0;
215  throttle_command_.mode = 1;
216  plc_command_.clutch=1;
217  plc_command_.auto_clutch=1;
218  plc_command_.brake=1;
219  plc_command_.auto_brake=1;
220 
221  break;
222  }
223 }
224 
226 {
227  switch(stm_state)
228  {
229  //first stage
230  case FIRST:
231  throttle_command_.throttle = 0;
232  throttle_command_.mode = 1;
233  plc_command_.clutch=1;
234  plc_command_.auto_clutch=1;
235  plc_command_.brake=1;
236  plc_command_.auto_brake=1;
237 
238  if (command_->velocity>0)
239  {
240  gearbox_command_.gear=1;
241 
242  //exit stage
243  if (status_.gear==1)
244  stm_state = SECOND;
245  }
246 
247  if (command_->velocity<0)
248  {
249  gearbox_command_.gear=6;
250 
251  //exit stage
252  if (status_.gear==6)
253  stm_state = SECOND;
254  }
255 
256  break;
257 
258  //second stage
259  case SECOND:
260  throttle_command_.throttle = 0.85;
261  throttle_command_.mode = 1;
262  plc_command_.clutch=0;
263  plc_command_.auto_clutch=1;
264  plc_command_.brake=0;
265  plc_command_.auto_brake = 1;
266 
267  break;
268 
269  default:
270  cout<<"Manager::stoppedToMoving::stm_state::default"<<endl;
271  }
272 }
273 
274 void Manager::stateManager(const atlascar_base::ManagerCommandPtr& command)
275 {
276  double increment = 0.01;
277 
279 
280  switch(current_state)
281  {
282  case UNKNOWN:
283  break;
284 
285  case INIT:
286  break;
287 
288  case STOPPED:
289  //stage
290  throttle_command_.throttle = 0;
291  throttle_command_.mode = 1;
292  plc_command_.clutch=1;
293  plc_command_.auto_clutch=1;
294  plc_command_.brake = 1;
295  plc_command_.auto_brake = 1;
296 
297  if (command_->parking==1)
298  gearbox_command_.gear=0;
299 
300  break;
301 
302  case STOPPED_TO_MOVING:
303  stoppedToMoving();
304 
305  break;
306 
307  case MOVING: //implementation of autonomous velocity control
308  //stage
309  throttle_command_.throttle=0.6;
310  throttle_command_.mode = 1;
311  plc_command_.clutch=0;
312  plc_command_.auto_clutch=1;
313  plc_command_.brake=0;
314  plc_command_.auto_brake = 1;
315 
316  break;
317 
318  case MOVING_TO_STOPPED:
319  movingToStopped();
320 
321  break;
322 
323  default:
324  cout<<"This state was not defined: "<<current_state<<endl;
325  };
326 }
327 
329 {
330  ros::Rate r(20);//Hz
331 
332  do
333  {
334  //Get top layer message, the command message that has the most priority and is still valid
335  command_=command_queue_.top_msg();
336 
337  if(command_->direct_control==1)//Direct command mode
338  {
339  //Put command message into outgoing messages
341 
342  //Publish all messages
346  }else if(command_->direct_control==2)//High command mode
347  {
348 
349 
351  plc_command_.auto_direction=1;
352  plc_command_.steering_wheel=command_->steering_wheel;
353  //Publish all messages
354 
355  plc_command_.priority=command_->priority;
356  plc_command_.lifetime=command_->lifetime;
357 
359 
360  gearbox_command_.priority=command_->priority;
361  gearbox_command_.lifetime=command_->lifetime;
362 
364 
365  throttle_command_.priority=command_->priority;
366  throttle_command_.lifetime=command_->lifetime;
367 
369  }
370 
371  //Publish the status message
372  status_.header.stamp = ros::Time::now();
373  status_.header.frame_id = "";
374  status_pub_.publish(status_);
375 
376  //Spin ros and sleep the desired amount
377  ros::spinOnce();
378  r.sleep();
379  }while(ros::ok());
380 }
381 
382 }
void loop()
Start main control loop.
Definition: manager.cpp:328
atlascar_base::GearboxCommand gearbox_command_
Gearbox command message.
Definition: manager.h:279
void movingToStopped()
Moving to Stopped.
Definition: manager.cpp:208
void setupMessaging()
Start ros message subscribing and advertising.
Definition: manager.cpp:58
CarState
Car state machine status.
Definition: manager.h:134
ros::Publisher command_throttle_pub_
Throttle command publisher.
Definition: manager.h:267
void toOutgoingMessages(const atlascar_base::ManagerCommandPtr &command)
Messages.
Definition: manager.cpp:76
Manager(const ros::NodeHandle &nh)
Class constructor.
Definition: manager.cpp:37
ros::Subscriber command_sub_
Ros command subscriber.
Definition: manager.h:249
atlascar_base::PlcCommand plc_command_
Plc command message.
Definition: manager.h:283
CarState current_state
Current state of state machine.
Definition: manager.h:243
~Manager()
Class destructor.
Definition: manager.cpp:41
void stateManager(const atlascar_base::ManagerCommandPtr &command)
State Manager.
Definition: manager.cpp:274
ros::Publisher command_plc_pub_
Plc command publisher.
Definition: manager.h:263
atlascar_base::ManagerStatus status_
Status message.
Definition: manager.h:277
ros::Publisher command_gearbox_pub_
Gearbox command publisher.
Definition: manager.h:265
ros::Subscriber status_gearbox_sub_
Gearbox status subscriber.
Definition: manager.h:257
atlascar_base::ThrottleCommand throttle_command_
Throttle command message.
Definition: manager.h:289
void gearboxStatusCallback(const atlascar_base::GearboxStatusPtr &status)
Gearbox status callback.
Definition: manager.cpp:164
TopicQueuePriority< atlascar_base::ManagerCommandPtr > command_queue_
Command queue holding class.
Definition: manager.h:269
void driverStatusCallback(const human_driver_monitor::HumanDriverMonitorStatusPtr &status)
Driver status callback.
Definition: manager.cpp:139
Manager class declaration.
ros::Subscriber status_odometer_sub_
Velocity status subscriber.
Definition: manager.h:255
void init()
Initialize the class.
Definition: manager.cpp:44
void throttleStatusCallback(const atlascar_base::ThrottleStatusPtr &status)
Throttle status callback.
Definition: manager.cpp:170
ros::Subscriber status_driver_sub_
Driver status subscriber.
Definition: manager.h:253
void odometerStatusCallback(const odometer::OdometerStatusPtr &status)
Velocity status callback.
Definition: manager.cpp:156
void stoppedToMoving()
Stopped to Moving.
Definition: manager.cpp:225
ros::Subscriber status_plc_sub_
Plc status subscriber.
Definition: manager.h:251
ros::Publisher status_pub_
Ros status publisher.
Definition: manager.h:261
void plcStatusCallback(const atlascar_base::PlcStatusPtr &status)
Plc status callback.
Definition: manager.cpp:121
ros::NodeHandle nh_
Ros node handler.
Definition: manager.h:247
sequentialState mts_state
Moving to stopped state.
Definition: manager.h:241
atlascar_base::ManagerCommandPtr safety_command_
Safety command message pointer.
Definition: manager.h:275
sequentialState stm_state
Stopped to moving state.
Definition: manager.h:239
atlascar_base::ManagerCommandPtr command_
Command message pointer.
Definition: manager.h:273
void commandCallback(const atlascar_base::ManagerCommandPtr &command)
Main command callback.
Definition: manager.cpp:116
ros::Subscriber status_throttle_sub_
Throttle status subscriber.
Definition: manager.h:259
CarState getCurrentState()
Check Current State.
Definition: manager.cpp:177


atlascar_base
Author(s): Jorge Almeida, Sérgio Pinho, Miguel Oliveira, Pedro Salvado, Andre Oliveira and Pedro Pinheiro
autogenerated on Mon Mar 2 2015 01:31:23