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
00031 #include <atlasmv.h>
00032
00033 #define BRK_TIME 1.0
00034
00035 void handler_vert_sign (const atlasmv_base::AtlasmvVertSignsCommandPtr& msg)
00036 {
00037 atlasmv_vert_signs=msg;
00038 }
00039
00040 void handler_lights(const atlasmv_base::AtlasmvLightsCommandPtr& msg)
00041 {
00042 atlasmv_lights=msg;
00043 }
00044
00045 void handler_motion(const atlasmv_base::AtlasmvMotionCommandPtr& msg)
00046 {
00047
00048
00049
00050
00051
00052
00053
00054 msg->speed=((msg->speed > atlasmv_details.max_forward_speed)?atlasmv_details.max_forward_speed:msg->speed);
00055 msg->speed=((msg->speed < atlasmv_details.max_backward_speed)?atlasmv_details.max_backward_speed:msg->speed);
00056
00057 msg->dir=((msg->dir > atlasmv_details.maximum_dir)?atlasmv_details.maximum_dir:msg->dir);
00058 msg->dir=((msg->dir < atlasmv_details.minimum_dir)?-atlasmv_details.minimum_dir:msg->dir);
00059
00060
00061
00062
00063
00064
00065
00066
00067
00068
00069
00070
00071
00072
00073
00074
00075
00076
00077
00078
00079
00080
00081 command_queue.push_msg(msg);
00082 }
00083
00089 void *des_thread_func(void *)
00090 {
00091 #define DES_VELOCITY_TYPE 1 //velocity can be 0 - mean value or 1 - instant
00092 c_timer timer_des;
00093 timer_des.tic(0);
00094
00095 double actual_speed;
00096 double new_speed;
00097
00098
00099 new_speed = 0.00;
00100 while(1)
00101 {
00102 timer_des.tic(9);
00103 timer_des.toc(0);
00104
00105 if( (!atlasmv->get_des_initialized()) )
00106 {
00107 printf("DES:error time:\n");
00108
00109 if(timer_des.get_toc(0)>0.1)
00110 {
00111 atlasmv->check_des();
00112 pthread_mutex_lock(&count_des_errors_mutex);
00113 count_des_errors++;
00114
00115 pthread_mutex_unlock(&count_des_errors_mutex);
00116 timer_des.tic(0);
00117 }
00118 }else{
00119 pthread_mutex_lock(&count_des_errors_mutex);
00120 count_des_errors=0;
00121 pthread_mutex_unlock(&count_des_errors_mutex);
00122 }
00123
00124
00125 pthread_mutex_lock(&command_mutex);
00126
00127 new_speed = atlasmv_motion->speed;
00128 cout<<"DES Speed :"<<new_speed<<endl;
00129 pthread_mutex_unlock(&command_mutex);
00130
00131
00132
00133 timer_des.tic(2);
00134 atlasmv->read_speed(DES_VELOCITY_TYPE);
00135 timer_des.toc(2);
00136 atlasmv->get_linear_speed(&actual_speed, NULL);
00137
00138
00139 speed_check = 0;
00140 if(new_speed <= 0.05)
00141 {
00142 pthread_mutex_lock(&speed_check_mutex);
00143 speed_check = 1;
00144 pthread_mutex_unlock(&speed_check_mutex);
00145 pthread_mutex_lock(&brake_check_mutex);
00146
00147 pthread_mutex_unlock(&brake_check_mutex);
00148
00149
00150
00151 }
00152 atlasmv->set_speed(&new_speed);
00153
00154 timer_des.toc(9);
00155 printf("DES:new-speed:%1.2f actual_speed:%1.2f.\n", new_speed, actual_speed);
00156
00157
00158 timer_des.run_sleep(9, 20);
00159
00160 }
00161
00162 return NULL;
00163 };
00164
00165
00171 void *dioc_thread_func(void *)
00172 {
00173 c_timer timer_dioc;
00174
00175 while(1)
00176 {
00177 timer_dioc.tic(9);
00178
00179 atlasmv->set_lights(*atlasmv_vert_signs,*atlasmv_lights);
00180 atlasmv->read_cross_sensor();
00181
00182 timer_dioc.toc(9);
00183 timer_dioc.run_sleep(9, 10);
00184
00185 }
00186
00187 return NULL;
00188 };
00189
00195 void *servos_thread_func(void *)
00196 {
00197 double actual_speed, req_speed;
00198 double new_brake=0;
00199 double pos0_brake=0.0;
00200 double new_dir, actual_dir;
00201 int num_pulses;
00202 c_timer timer_servos;
00203 req_speed=0.0;
00204 bool force_brake=false;
00205 atlasmv->read_brake(&pos0_brake, &num_pulses);
00206 atlasmv->set_min_pulse_brk(&num_pulses);
00207 int speed_now = 0;
00208
00209
00210 while(1)
00211 {
00212 timer_servos.tic(9);
00213
00214 pthread_mutex_lock(&command_mutex);
00215
00216 new_dir = atlasmv_motion->dir;
00217 cout<<"Dir: "<<atlasmv_motion->dir<<endl;
00218 req_speed = atlasmv_motion->speed;
00219
00220 pthread_mutex_unlock(&command_mutex);
00221
00222 atlasmv->get_linear_speed(&actual_speed, NULL);
00223
00224 if( (fabs(req_speed) < fabs(actual_speed)) )
00225 {
00226 if( fabs(req_speed-actual_speed) > atlasmv->get_brake_speed_dif() )
00227 {
00228 new_brake=1.0;
00229 }
00230 else{
00231 new_brake=0.0;
00232 }
00233 }else{
00234 new_brake=0.0;
00235 }
00236
00237
00238
00239 pthread_mutex_lock(&count_des_errors_mutex);
00240 int errs = count_des_errors;
00241 pthread_mutex_unlock(&count_des_errors_mutex);
00242
00243 if(force_brake==false && !atlasmv->get_des_initialized() && (!errs))
00244 {
00245 force_brake = true;
00246 timer_servos.tic(0);
00247
00248
00249
00250 }
00251
00252
00253 if( (!atlasmv->get_des_initialized()) && force_brake )
00254 {
00255
00256
00257 }
00258
00259 timer_servos.toc(0);
00260 if( timer_servos.get_toc(0) > atlasmv->get_brk_time_no_maxon() && force_brake)
00261 {
00262 force_brake = false;
00263 }
00264
00265 if(new_brake)
00266 {
00267 pthread_mutex_lock(&speed_check_mutex);
00268 speed_now = speed_check;
00269 pthread_mutex_unlock(&speed_check_mutex);
00270 pthread_mutex_lock(&brake_check_mutex);
00271 brake_check = 1;
00272 pthread_mutex_unlock(&brake_check_mutex);
00273 if(speed_now)
00274 printf("error 2.0 @ servos_thread\n");
00275 speed_now=0;
00276 }
00277 atlasmv->set_brake(&new_brake);
00278
00279 atlasmv->read_direction(&actual_dir);
00280
00281
00282
00283
00284 if( fabs(actual_dir - new_dir) > 0.0349/4.0)
00285 {
00286
00287 atlasmv->set_direction(&new_dir);
00288
00289 }else{
00290
00291
00292 atlasmv->set_direction(&actual_dir);
00293 }
00294 timer_servos.toc(9);
00295
00296
00297 timer_servos.run_sleep(9, 30);
00298 }
00299
00300 return NULL;
00301 };
00302
00303
00304 double map_linear(double in,std::vector<std::pair<double,double> >& cp)
00305 {
00306
00307
00308
00309 double out=NAN;
00310
00311 for(uint i=0;i<cp.size()-1;i++)
00312 {
00313 if( in >= cp[i].first && in <= cp[i+1].first)
00314 {
00315
00316 double m = (cp[i+1].second - cp[i].second)/(cp[i+1].first - cp[i].first);
00317 double b = cp[i+1].second -m*cp[i+1].first;
00318
00319 out=m*in+b;
00320 break;
00321 }
00322 }
00323
00324 return out;
00325 }
00326
00327
00328 int main(int argc, char **argv)
00329 {
00330
00331
00332
00333
00334
00335
00336
00337
00338
00339
00340
00341
00342
00343
00344
00345
00346
00347
00348 atlasmv_help(0);
00349
00350 atlasmv_details.com_servos = (char*)malloc(256*sizeof(char));
00351 atlasmv_details.com_des = (char*)malloc(256*sizeof(char));
00352 atlasmv_details.com_dioc = (char*)malloc(256*sizeof(char));
00353
00354 atlasmv_details.sleep_time = 1.0/atlasmv_details.cycle_freq;
00355
00356 atlasmv_base::AtlasmvMotionCommandPtr safety_command(new atlasmv_base::AtlasmvMotionCommand);
00357
00358 safety_command->lifetime=INFINITY;
00359 safety_command->priority=0;
00360 safety_command->speed=0;
00361 safety_command->dir=0;
00362
00363 atlasmv_status.reset(new atlasmv_base::AtlasmvStatus);
00364 atlasmv_vert_signs.reset(new atlasmv_base::AtlasmvVertSignsCommand);
00365 atlasmv_lights.reset(new atlasmv_base::AtlasmvLightsCommand);
00366
00367 atlasmv= new c_atlasmv(0);
00368
00370 ros::init(argc, argv, "atlasmv_base");
00371 ros::NodeHandle nh("~");
00372
00373 command_queue.push_msg(safety_command);
00374
00375 atlasmv_motion=command_queue.top_msg();
00376
00378 nh.param("max_forward_speed", atlasmv_details.max_forward_speed,4.0);
00379 nh.param("max_backward_speed", atlasmv_details.max_backward_speed,-1.);
00380 nh.param("brake_speed_dif", atlasmv_details.brake_speed_dif,0.25);
00381
00382 nh.param("servo_direction_id", atlasmv_details.servo_direction_id,0);
00383 nh.param("servo_brake_id", atlasmv_details.servo_brake_id,1);
00384
00385 if (nh.getParam("comport_servos", atlasmv_details.com_servos))
00386 ROS_INFO("comport_servos: %s", atlasmv_details.com_servos.c_str());
00387 else
00388 {
00389 ROS_ERROR("Failed to get critical param 'comport_servos'");
00390 return -1;
00391 }
00392
00393 if (nh.getParam("comport_DES", atlasmv_details.com_des))
00394 ROS_INFO("comport_DES: %s", atlasmv_details.com_des.c_str());
00395 else
00396 {
00397 ROS_ERROR("Failed to get critical param 'comport_DES'");
00398 return -1;
00399 }
00400
00401 if (nh.getParam("comport_dioc", atlasmv_details.com_dioc))
00402 ROS_INFO("comport_dioc: %s", atlasmv_details.com_dioc.c_str());
00403 else
00404 {
00405 atlasmv_details.com_dioc.clear();
00406 ROS_WARN("Failed to get param 'comport_dioc'");
00407 }
00408
00409 nh.param("length", atlasmv_details.length,0.8);
00410 nh.param("width", atlasmv_details.width,0.6);
00411 nh.param("wheelaxisdistance", atlasmv_details.wheelaxisdistance,0.49);
00412 nh.param("back_wheel_diam", atlasmv_details.back_wheel_diam,0.115);
00413 nh.param("maximum_dir", atlasmv_details.maximum_dir,0.355);
00414 nh.param("minimum_dir", atlasmv_details.minimum_dir,-0.38);
00415 nh.param("maximum_brk", atlasmv_details.maximum_brk,1.0);
00416 nh.param("minimum_brk", atlasmv_details.minimum_brk,0.0);
00417 nh.param("transmission_relation", atlasmv_details.transmission_relation,13.73);
00418 nh.param("min_pulse_brk", atlasmv_details.min_pulse_brk,1060);
00419 nh.param("max_pulse_brk", atlasmv_details.max_pulse_brk,1400);
00420 nh.param("min_pulse_dir", atlasmv_details.min_pulse_dir,930);
00421 nh.param("max_pulse_dir", atlasmv_details.max_pulse_dir,2000);
00422 nh.param("brk_time_no_maxon", atlasmv_details.brk_time_no_maxon,1.0);
00423
00424 nh.param("des_sys_config", atlasmv_details.sDES_sysparam.sys_config,49024);
00425 nh.param("des_enc_res", atlasmv_details.sDES_sysparam.enc_resolution,500);
00426 nh.param("des_max_rpm", atlasmv_details.sDES_sysparam.max_speed,13000);
00427 nh.param("des_max_cont_current", atlasmv_details.sDES_sysparam.max_cont_current,8000);
00428 nh.param("des_peak_current", atlasmv_details.sDES_sysparam.peak_current,25000);
00429 nh.param("des_speed_gain_p", atlasmv_details.sDES_sysparam.speed_reg_gain_p,554);
00430 nh.param("des_speed_gain_i", atlasmv_details.sDES_sysparam.speed_reg_gain_i,89);
00431
00432
00433 initialize_motion_model(&motion_model, 0, 0, 0, atlasmv_details.wheelaxisdistance);
00434
00435 atlasmv->set_atlasmv_details(&atlasmv_details);
00436
00437 int initialize = atlasmv->initialize_robot();
00438 if(!(initialize & 1))
00439 {
00440 if(initialize & 2)
00441 printf("\33[31mError with DIOC\33[0m\n");
00442
00443 if(initialize & 4)
00444 printf("\33[31mError with ServoAmplifier\33[0m\n");
00445
00446 if(initialize & 8)
00447 printf("\33[31mError with Servos\33[0m\n");
00448 }
00449
00450 des_iret = pthread_create(&des_thread, NULL, des_thread_func , NULL);
00451 servos_iret = pthread_create(&servos_thread, NULL, servos_thread_func , NULL);
00452 dioc_iret = pthread_create(&dioc_thread, NULL, dioc_thread_func , NULL);
00453
00454
00455
00456 ros::Subscriber sub_vert_sign = nh.subscribe("/atlasmv/base/vertical_signs", 1000, handler_vert_sign);
00457 ros::Subscriber sub_lights = nh.subscribe("/atlasmv/base/lights", 1000, handler_lights);
00458 ros::Subscriber sub_motion = nh.subscribe("/atlasmv/base/motion", 1000, handler_motion);
00459
00460 ros::Publisher pub_status=nh.advertise<atlasmv_base::AtlasmvStatus>("/atlasmv/base/status",1000);
00461
00462 ros::Rate LoopRate(30);
00463
00464 std::cout<<atlasmv_details<<endl;
00465
00466 std::cout<<"Start to spin"<<endl;
00467 timer.tic(1);
00468 while (ros::ok())
00469 {
00470 atlasmv_motion=command_queue.top_msg();
00471
00472
00473 atlasmv->update_robot_status(*atlasmv_status);
00474
00475
00476
00477
00478
00479
00480
00481
00482
00483
00484
00485
00486
00487
00488
00489
00490
00491
00492
00493 atlasmv_status->speed=(atlasmv_status->speed)*1.02;
00494
00495 update_motion_model(&motion_model, atlasmv_status->speed, atlasmv_status->dir);
00496 timer.toc(1);
00497 increment_motion_model(&motion_model, timer.get_toc(1));
00498
00499 timer.tic(1);
00500
00501 atlasmv_status->x = motion_model.X;
00502 atlasmv_status->y = motion_model.Y;
00503 atlasmv_status->orientation = motion_model.HA;
00504 atlasmv_status->distance_traveled = motion_model.S;
00505
00506
00507
00508
00509 atlasmv_status->header.stamp = ros::Time::now();
00510
00511
00512
00513 pub_status.publish(*atlasmv_status);
00514
00515 ros::spinOnce();
00516 LoopRate.sleep();
00517 }
00518 }
00519
00520
00530 int initialize_motion_model(t_motion_model*model,double X0,double Y0,double orientation,double wheelbase)
00531 {
00532 model->X=X0;
00533 model->Y=Y0;
00534 model->HA=orientation;
00535 model->L=wheelbase;
00536 model->S=0;
00537 model->R=NAN;
00538 return 0;
00539 }
00540
00548 int update_motion_model(t_motion_model*model,double velocity,double steering_angle)
00549 {
00550 model->V=velocity;
00551 model->SA=steering_angle;
00552 return 0;
00553 }
00554
00561 int increment_motion_model(t_motion_model*model,double dt)
00562 {
00563 double R=model->L/tan(model->SA);
00564 double S=model->V*dt;
00565 double dHA=S/R;
00566
00567 model->R=R;
00568 model->S+=S;
00569 model->HA+=dHA;
00570
00571 if(model->HA > 2*M_PI)
00572 model->HA-=2*M_PI;
00573 if(model->HA < -2*M_PI)
00574 model->HA+=2*M_PI;
00575
00576 double dXl=R*(sin(dHA));
00577 double dYl=R*(1-cos(dHA));
00578
00579 if(dHA==0)
00580 {
00581 dXl=S;
00582 dYl=0;
00583 }
00584
00585 model->X+=cos(model->HA)*dXl-sin(model->HA)*dYl;
00586 model->Y+=sin(model->HA)*dXl+cos(model->HA)*dYl;
00587 return 0;
00588 }
00589
00595 void atlasmv_help(bool help)
00596 {
00597 if(help)
00598 {
00599 std::cout<<"\33[36mATLASMV\33[033m\n";
00600 std::cout<<"command line options:\n";
00601 std::cout<<"* -debug:\n";
00602 std::cout<<" enter in debugging mode, display relevant information while running\n";
00603 std::cout<<" show msg frame sent/received from:\n";
00604 std::cout<<" DES servoamplifier, example:\n";
00605 std::cout<<" request DES version:\n";
00606 std::cout<<" sent: | OpCode | len-1 | data[0]| crc |\n";
00607 std::cout<<" | 0x1A | 0x00 | 0X0000 | 0x730c |\n";
00608 std::cout<<"\n";
00609 std::cout<<" received: | OpCode | len-1 | data[0]| data[1] | data[2] | data[3] | crc |\n";
00610 std::cout<<" | 0x03 | 0x03 | 0x1050 | 0x4101 | 0x00A1 | 0x0001 | 0x7902 |\n";
00611 std::cout<<"\n";
00612 std::cout<<" DIOC discrete I/O:\n";
00613 std::cout<<" prints received value and sent value\n";
00614 std::cout<<" Hitec 5890gs servos:\n";
00615 std::cout<<" print out the value when set new position and read actual position\n";
00616 std::cout<<"* -h or --help: help menu\n";
00617
00618 raise(SIGINT);
00619 }
00620 }