00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00032 #include "manager.h"
00033
00034 namespace atlascar_base
00035 {
00036
00037 Manager::Manager(const ros::NodeHandle& nh)
00038 :nh_(nh)
00039 {}
00040
00041 Manager::~Manager()
00042 {}
00043
00044 void Manager::init()
00045 {
00046 safety_command_.reset(new atlascar_base::ManagerCommand);
00047
00048
00049 safety_command_->lifetime=INFINITY;
00050 safety_command_->priority=0;
00051
00052
00053 command_queue_.push_msg(safety_command_);
00054 }
00055
00056 void Manager::setupMessaging()
00057 {
00058 command_sub_ = nh_.subscribe("command", 1, &Manager::commandCallback, this);
00059
00060 status_plc_sub_ = nh_.subscribe("plc_status", 1, &Manager::plcStatusCallback, this);
00061 status_driver_sub_ = nh_.subscribe("driver_status", 1, &Manager::driverStatusCallback, this);
00062 status_odometer_sub_ = nh_.subscribe("odometer_status", 1, &Manager::odometerStatusCallback, this);
00063 status_gearbox_sub_ = nh_.subscribe("gearbox_status", 1, &Manager::gearboxStatusCallback, this);
00064 status_throttle_sub_ = nh_.subscribe("throttle_status", 1, &Manager::throttleStatusCallback, this);
00065
00066 status_pub_ = nh_.advertise<atlascar_base::ManagerStatus>("status", 1);
00067
00068 command_plc_pub_ = nh_.advertise<atlascar_base::PlcCommand>("plc_command", 1);
00069
00070 command_gearbox_pub_ = nh_.advertise<atlascar_base::GearboxCommand>("gearbox_command", 1);
00071 command_throttle_pub_ = nh_.advertise<atlascar_base::ThrottleCommand>("throttle_command", 1);
00072 }
00073
00074 void Manager::toOutgoingMessages(const atlascar_base::ManagerCommandPtr& command)
00075 {
00076 gearbox_command_.gear=command->gear;
00077 gearbox_command_.priority=command->priority;
00078 gearbox_command_.lifetime=command->lifetime;
00079
00080 gearbox_command_.header=command->header;
00081
00082 plc_command_.clutch=command->clutch;
00083 plc_command_.brake=command->brake;
00084 plc_command_.steering_wheel=command->steering_wheel;
00085 plc_command_.rpm=0;
00086 plc_command_.lights_high=command->lights_high;
00087 plc_command_.lights_medium=command->lights_medium;
00088 plc_command_.lights_minimum=0;
00089 plc_command_.lights_left=command->lights_left;
00090 plc_command_.lights_right=command->lights_right;
00091 plc_command_.lights_brake=command->lights_brake;
00092 plc_command_.lights_reverse=command->lights_reverse;
00093 plc_command_.lights_warning=command->lights_warning;
00094 plc_command_.ignition=command->ignition;
00095 plc_command_.emergency=command->emergency;
00096 plc_command_.auto_ignition=command->auto_ignition;
00097 plc_command_.auto_brake=command->auto_brake;
00098 plc_command_.auto_direction=command->auto_direction;
00099 plc_command_.auto_clutch=command->auto_clutch;
00100 plc_command_.priority=command->priority;
00101 plc_command_.lifetime=command->lifetime;
00102
00103 plc_command_.header=command->header;
00104
00105 throttle_command_.throttle=command->throttle;
00106 throttle_command_.mode=command->auto_throttle;
00107 throttle_command_.priority=command->priority;
00108 throttle_command_.lifetime=command->lifetime;
00109
00110 throttle_command_.header=command->header;
00111 }
00112
00113 void Manager::commandCallback(const atlascar_base::ManagerCommandPtr& command)
00114 {
00115 command_queue_.push_msg(command);
00116
00117
00118 command_=command_queue_.top_msg();
00119
00120 toOutgoingMessages(command_);
00121
00122
00123 command_plc_pub_.publish(plc_command_);
00124 command_gearbox_pub_.publish(gearbox_command_);
00125 command_throttle_pub_.publish(throttle_command_);
00126 }
00127
00128 void Manager::plcStatusCallback(const atlascar_base::PlcStatusPtr& status)
00129 {
00130 status_.clutch = status->clutch;
00131 status_.brake = status->brake;
00132 status_.steering_wheel = status->steering_wheel;
00133 status_.rpm = status->rpm;
00134
00135 status_.lights_brake=status->lights_brake;
00136 status_.lights_reverse=status->lights_reverse;
00137 status_.lights_warning=status->lights_warning;
00138
00139 status_.emergency=status->emergency;
00140 status_.auto_ignition=status->auto_ignition;
00141 status_.auto_brake=status->auto_brake;
00142 status_.auto_direction=status->auto_direction;
00143 status_.auto_clutch=status->auto_clutch;
00144 }
00145
00146 void Manager::driverStatusCallback(const human_driver_monitor::HumanDriverMonitorStatusPtr& status)
00147 {
00148 status_.lights_high=status->lights_high;
00149 status_.lights_medium=status->lights_medium;
00150 status_.lights_left=status->lights_left;
00151 status_.lights_right=status->lights_right;
00152 status_.lights_danger=status->lights_danger;
00153
00154 status_.ignition=status->ignition;
00155
00156 status_.horn=status->horn;
00157
00158 status_.throttle_pressure=status->throttle_pressure;
00159 status_.brake_pressure=status->brake_pressure;
00160 status_.clutch_pressure=status->clutch_pressure;
00161 }
00162
00163 void Manager::odometerStatusCallback(const odometer::OdometerStatusPtr& status)
00164 {
00165 status_.velocity=status->velocity;
00166 }
00167
00168 void Manager::gearboxStatusCallback(const atlascar_base::GearboxStatusPtr& status)
00169 {
00170 status_.gear=status->gear;
00171 status_.gearbox_status=status->status;
00172 }
00173
00174 void Manager::throttleStatusCallback(const atlascar_base::ThrottleStatusPtr& status)
00175 {
00176 status_.throttle=status->throttle;
00177 status_.throttle_pedal=status->footPedal;
00178 status_.auto_throttle=status->mode;
00179 }
00180
00181 void Manager::stateManager(const atlascar_base::ManagerCommandPtr& command)
00182 {
00183
00184 }
00185
00186 void Manager::loop()
00187 {
00188 ros::Rate r(20);
00189
00190 do
00191 {
00192
00193 command_=command_queue_.top_msg();
00194
00195 if(command_->direct_control==1)
00196 {
00197
00198 toOutgoingMessages(command_);
00199
00200
00201 command_plc_pub_.publish(plc_command_);
00202 command_gearbox_pub_.publish(gearbox_command_);
00203 command_throttle_pub_.publish(throttle_command_);
00204 }else if(command_->direct_control==2)
00205 {
00206 stateManager(command_);
00207
00208
00209 command_plc_pub_.publish(plc_command_);
00210 command_gearbox_pub_.publish(gearbox_command_);
00211 command_throttle_pub_.publish(throttle_command_);
00212 }
00213
00214
00215 status_.header.stamp = ros::Time::now();
00216 status_.header.frame_id = "";
00217 status_pub_.publish(status_);
00218
00219
00220 ros::spinOnce();
00221 r.sleep();
00222 }while(ros::ok());
00223 }
00224
00225 }