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 #ifndef _ATLASMV_H_
00033 #define _ATLASMV_H_
00034
00035 #define _DO_NOT_USE_OPENCV_ 0
00036 #define _DO_NOT_USE_CARMEN_ 0
00037
00038
00039
00040
00041
00042
00043 #include "c_atlasmv.h"
00044
00045 #include <pthread.h>
00046 #include <strings.h>
00047 #include <math.h>
00048 #include <queue>
00049 #include <vector>
00050 #include <atlasmv_base/AtlasmvLightsCommand.h>
00051 #include <atlasmv_base/AtlasmvVertSignsCommand.h>
00052 #include <atlasmv_base/AtlasmvMotionCommand.h>
00053 #include <atlasmv_base/AtlasmvStatus.h>
00054
00055 using namespace std;
00056
00057 template <class cmd_type>
00058 class command_queue_priority
00059 {
00060 typename std::map<int,cmd_type> message_map;
00061
00062 typename std::map<int,cmd_type>::iterator it;
00063
00064 public:
00065 void maintenance(void)
00066 {
00067 for(it=message_map.begin();it!=message_map.end();it++)
00068 if(ros::Time::now().toSec() > (*it).second->lifetime)
00069 message_map.erase(it);
00070 }
00071
00072 void push_msg(cmd_type msg)
00073 {
00074 msg->lifetime=ros::Time::now().toSec()+msg->lifetime;
00075
00076 it=message_map.find(msg->priority);
00077
00078 if(it==message_map.end())
00079 message_map[msg->priority]=msg;
00080 else
00081 {
00082 message_map.erase(it);
00083 message_map[msg->priority]=msg;
00084 }
00085 }
00086
00087 cmd_type top_msg(void)
00088 {
00089 maintenance();
00090
00091 int max_priority=-1;
00092 typename std::map<int,cmd_type>::iterator it_max;
00093
00094 for(it=message_map.begin();it!=message_map.end();it++)
00095 if((*it).second->priority > max_priority)
00096 {
00097 max_priority=(*it).second->priority;
00098 it_max=it;
00099 }
00100
00101 if(message_map.size())
00102 return (*it_max).second;
00103
00104 cmd_type null_ptr;
00105 return null_ptr;
00106 }
00107 };
00108
00109
00110 typedef struct
00111 {
00113 double X,Y;
00115 double V;
00117 double SA;
00119 double HA;
00121 double L;
00123 double S;
00125 double R;
00126 }t_motion_model;
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137 int main(int argc, char **argv);
00138 void atlasmv_shutdown_module(int x);
00139 void atlasmv_help(bool debug);
00140
00141
00142
00143
00144
00145 double percentage2real_velocity(double percentage);
00146 int increment_motion_model(t_motion_model*model,double dt);
00147 int update_motion_model(t_motion_model*model,double velocity,double steering_angle);
00148 int initialize_motion_model(t_motion_model*model,double X0,double Y0,double orientation,double wheelbase);
00149
00150
00151
00152
00153
00154
00155
00156
00157
00158
00159
00160
00161
00162
00163 pthread_t des_thread, dioc_thread, servos_thread;
00164 int des_iret, dioc_iret, servos_iret;
00165 pthread_mutex_t speed_mutex = PTHREAD_MUTEX_INITIALIZER;
00166 pthread_mutex_t dir_mutex = PTHREAD_MUTEX_INITIALIZER;
00167 pthread_mutex_t brk_mutex = PTHREAD_MUTEX_INITIALIZER;
00168 pthread_mutex_t dioc_mutex = PTHREAD_MUTEX_INITIALIZER;
00169 pthread_mutex_t command_mutex = PTHREAD_MUTEX_INITIALIZER;
00170 pthread_mutex_t count_des_errors_mutex;
00171 pthread_mutex_t speed_check_mutex;
00172 int speed_check;
00173 pthread_mutex_t brake_check_mutex;
00174 int brake_check;
00175 int count_des_errors;
00176
00177
00178 TYPE_atlasmv_public_params params;
00179 c_timer timer;
00180 t_motion_model motion_model;
00181
00182 double speed, dir, brake;
00183 char new_command_received;
00184
00185 atlasmv_base::AtlasmvStatusPtr atlasmv_status;
00186 atlasmv_base::AtlasmvMotionCommandPtr atlasmv_motion;
00187 atlasmv_base::AtlasmvVertSignsCommandPtr atlasmv_vert_signs;
00188 atlasmv_base::AtlasmvLightsCommandPtr atlasmv_lights;
00189
00190
00191
00192 TYPE_atlasmv_public_params atlasmv_details;
00193 c_atlasmv* atlasmv;
00194
00195 command_queue_priority<atlasmv_base::AtlasmvMotionCommandPtr> command_queue;
00196
00197 #endif