00001 #include "tibi_dabo_pitch_estimator_alg_node.h"
00002 #include <stdio.h>
00003 #include <string.h>
00004 #include <cmath>
00005
00006
00007 TibiDaboPitchEstimatorAlgNode::TibiDaboPitchEstimatorAlgNode(void) :
00008 algorithm_base::IriBaseAlgorithm<TibiDaboPitchEstimatorAlgorithm>(),
00009 result_lines_(Line_unknown_state),
00010 security_distance_(0.5),
00011 reg_line_(0.05)
00012 {
00013
00014
00015
00016
00017 this->front_laser_filtrado_publisher_ = this->public_node_handle_.advertise<sensor_msgs::LaserScan>("front_laser_filtrado", 100);
00018 this->rear_laser_filtrado_publisher_ = this->public_node_handle_.advertise<sensor_msgs::LaserScan>("rear_laser_filtrado", 100);
00019 this->MarkerArray_lines_publisher_ = this->public_node_handle_.advertise<visualization_msgs::MarkerArray>("MarkerArray_lines", 100);
00020
00021
00022 this->rear_laser_subscriber_ = this->public_node_handle_.subscribe("rear_laser", 100, &TibiDaboPitchEstimatorAlgNode::rear_laser_callback, this);
00023 this->front_laser_subscriber_ = this->public_node_handle_.subscribe("front_laser", 100, &TibiDaboPitchEstimatorAlgNode::front_laser_callback, this);
00024 this->pitch_subscriber_ = this->public_node_handle_.subscribe("pitch", 100, &TibiDaboPitchEstimatorAlgNode::pitch_callback, this);
00025 this->laser_subscriber_ = this->public_node_handle_.subscribe("laser", 100, &TibiDaboPitchEstimatorAlgNode::laser_callback, this);
00026
00027
00028
00029
00030
00031
00032
00033
00034 }
00035
00036 TibiDaboPitchEstimatorAlgNode::~TibiDaboPitchEstimatorAlgNode(void)
00037 {
00038
00039 }
00040
00041 void TibiDaboPitchEstimatorAlgNode::mainNodeThread(void)
00042 {
00043
00044
00045 this->alg_.lock();
00046
00047 result_=reg_line_.linear_regression(laser_,a1,b1,a2,b2,error);
00048
00049
00050 switch(result_){
00051
00052 case Claser_linear_regression::One_line:
00053
00054
00055 result_lines_ = One_line_state ;
00056 line_node(a1,b1,a2,b2,result_lines_);
00057
00058 break;
00059
00060 case Claser_linear_regression::Two_lines:
00061
00062
00063 result_lines_ = Two_lines_state ;
00064 line_node(a1,b1,a2,b2,result_lines_);
00065
00066 break;
00067
00068 case Claser_linear_regression::Line_partial:
00069
00070
00071 result_lines_ = Line_partial_state ;
00072 line_node(a1,b1,a2,b2,result_lines_);
00073
00074 break;
00075
00076 case Claser_linear_regression::Line_unknown:
00077
00078
00079 result_lines_ = Line_unknown_state ;
00080 line_node(a1,b1,a2,b2,result_lines_);
00081
00082 break;
00083
00084 }
00085
00086 this->alg_.unlock();
00087
00088
00089
00090
00091
00092
00093
00094
00095
00096
00097
00098 this->MarkerArray_lines_publisher_.publish(this->MarkerArray_msg_);
00099 }
00100
00101
00102 void TibiDaboPitchEstimatorAlgNode::pitch_callback(const iri_segway_rmp_msgs::SegwayRMP200Status::ConstPtr& msg)
00103 {
00104
00105
00106
00107 this->alg_.lock();
00108 this->pitch_mutex_.enter();
00109
00110 pitch=msg->pitch_angle;
00111
00112
00113 this->alg_.unlock();
00114 this->pitch_mutex_.exit();
00115 }
00116 void TibiDaboPitchEstimatorAlgNode::laser_callback(const sensor_msgs::LaserScan::ConstPtr& msg)
00117 {
00118
00119
00120 this->laser_mutex_.enter();
00121
00122
00123 this->alg_.lock();
00124 laser_.clear();
00125 double angle = msg->angle_max;
00126 unsigned int max_i = (unsigned int) ( ( angle - 40.0*PI/180 ) / msg->angle_increment );
00127
00128 for( unsigned int i = msg->ranges.size()-1; i > max_i ; --i )
00129 {
00130
00131 laser_.push_back( Cpoint(msg->ranges[i] * cos(angle)-0.25,0.84-msg->ranges[i] * sin(angle)) );
00132 angle -= msg->angle_increment;
00133
00134 }
00135
00136 this->alg_.unlock();
00137
00138 this->laser_mutex_.exit();
00139
00140 }
00141
00142
00143
00144
00145 void TibiDaboPitchEstimatorAlgNode::front_laser_callback(const sensor_msgs::LaserScan::ConstPtr& msg)
00146 {
00147
00148
00149
00150
00151 this->laser_mutex_.enter();
00152 this->alg_.lock();
00153
00154 double distance_intersection_=60,distance_point_laser_=0;
00155
00156 LaserScan_front_msg_=*msg;
00157
00158 for( unsigned int i =0; i < msg->ranges.size()-1 ; ++i )
00159 {
00160
00161 double inicial_point_x = 0.28;
00162 double inicial_point_y =0.44;
00163
00164 double intersection_y = (0.44-b1)/a1+0.28 ;
00165 double intersection_x = b1+0.44 ;
00166
00167 if(a1>0){
00168
00169 distance_intersection_=sqrt((inicial_point_x-intersection_x)*(inicial_point_x-intersection_x)+(inicial_point_y-intersection_y)*(inicial_point_y-intersection_y));
00170 distance_point_laser_=msg->ranges[i];
00171
00172 }
00173
00174 if(distance_intersection_< distance_point_laser_+security_distance_){
00175
00176 LaserScan_front_msg_.ranges[i]=0.0;
00177
00178 }
00179
00180 }
00181
00182 this->front_laser_filtrado_publisher_.publish(this->LaserScan_front_msg_);
00183
00184
00185
00186
00187 double angle = msg->angle_min;
00188
00189 for( unsigned int i =0 ; i < msg->ranges.size()-1 ; ++i )
00190 {
00191
00192 front_laser_point_x=msg->ranges[i] * cos(angle)-0.28;
00193 front_laser_point_y=0.44-msg->ranges[i] * sin(angle);
00194 marker_point_front_laser_node(front_laser_point_x,front_laser_point_y);
00195
00196 angle += msg->angle_increment;
00197
00198 }
00199
00200
00201
00202
00203 this->alg_.unlock();
00204
00205 this->laser_mutex_.exit();
00206
00207 }
00208
00209
00210
00211 void TibiDaboPitchEstimatorAlgNode::rear_laser_callback(const sensor_msgs::LaserScan::ConstPtr& msg)
00212 {
00213
00214
00215
00216
00217 this->laser_mutex_.enter();
00218 this->alg_.lock();
00219
00220 double distance_intersection_=60,distance_point_laser_=0;
00221
00222 LaserScan_rear_msg_=*msg;
00223
00224 for( unsigned int i =0; i < msg->ranges.size()-1 ; ++i )
00225 {
00226
00227 double inicial_point_x = 0.28;
00228 double inicial_point_y =0.44;
00229
00230
00231
00232 if(a1<0){
00233
00234 double intersection_y = (0.44-b1)/(-a1)+0.28 ;
00235 double intersection_x = b1+0.44 ;
00236
00237 distance_intersection_=sqrt((inicial_point_x-intersection_x)*(inicial_point_x-intersection_x)+(inicial_point_y-intersection_y)*(inicial_point_y-intersection_y));
00238 distance_point_laser_=msg->ranges[i];
00239
00240 }
00241
00242 if(distance_intersection_< distance_point_laser_+security_distance_){
00243
00244 LaserScan_rear_msg_.ranges[i]=0.0;
00245
00246 }
00247
00248 }
00249
00250 this->rear_laser_filtrado_publisher_.publish(this->LaserScan_rear_msg_);
00251
00252
00253
00254
00255 double angle = msg->angle_min;
00256
00257 for( unsigned int i =0 ; i < msg->ranges.size()-1 ; ++i )
00258 {
00259
00260 front_laser_point_x=msg->ranges[i] * cos(angle)-0.28;
00261 front_laser_point_y=0.44-msg->ranges[i] * sin(angle);
00262 marker_point_front_laser_node(front_laser_point_x,front_laser_point_y);
00263
00264 angle += msg->angle_increment;
00265
00266 }
00267
00268
00269
00270
00271
00272 this->alg_.unlock();
00273
00274 this->laser_mutex_.exit();
00275
00276
00277 }
00278
00279
00280
00281
00282 void TibiDaboPitchEstimatorAlgNode::line_node(double& a1,double& b1,double& a2,double& b2, res_lines result_lines_)
00283 {
00284
00285 line_marker_.points.clear();
00286 line_marker2_.points.clear();
00287 arrow_marker3_.points.clear();
00288 arrow_marker4_.points.clear();
00289 intersection_marker5_.points.clear();
00290
00291
00292 geometry_msgs::Point ros_point;
00293 line_marker_.id=0;
00294 line_marker_.header.frame_id = "/dabo/base_link";
00295 line_marker_.header.stamp = ros::Time();
00296 line_marker_.ns = "line floor";
00297 line_marker_.type = visualization_msgs::Marker::LINE_STRIP;
00298 line_marker_.action = visualization_msgs::Marker::ADD;
00299 line_marker_.lifetime = ros::Duration(1.0f);
00300 line_marker_.points.reserve(2);
00301
00302 if ( line_marker_.points.size() <2)
00303 {
00304 ros_point.x = -10;
00305 ros_point.z =a1*ros_point.x+b1;
00306 ros_point.y = 0;
00307 line_marker_.points.push_back(ros_point);
00308 ros_point.x = 10;
00309 ros_point.z=a1*ros_point.x+b1;
00310 ros_point.y = 0;
00311 line_marker_.points.push_back(ros_point);
00312 }
00313
00314 line_marker_.scale.x = 0.05;
00315 line_marker_.color.a = 1.0;
00316 line_marker_.color.r = 0.0;
00317 line_marker_.color.g = 1.0;
00318 line_marker_.color.b = 0.0;
00319
00320
00321 geometry_msgs::Point ros_point2;
00322 line_marker2_.id=1;
00323 line_marker2_.header.frame_id = "/dabo/base_link";
00324 line_marker2_.header.stamp = ros::Time();
00325 line_marker2_.ns = "line wall";
00326 line_marker2_.type = visualization_msgs::Marker::LINE_STRIP;
00327 line_marker2_.action = visualization_msgs::Marker::ADD;
00328 line_marker2_.lifetime = ros::Duration(3.0f);
00329 line_marker2_.points.reserve(2);
00330
00331 if ( line_marker2_.points.size()<2)
00332 {
00333 ros_point2.x =0;
00334 ros_point2.z =a2*0+b2;
00335 ros_point2.y =0;
00336 line_marker2_.points.push_back(ros_point2);
00337
00338 ros_point2.x =50;
00339 ros_point2.z =a2*50+b2;
00340 ros_point2.y =0;
00341 line_marker2_.points.push_back(ros_point2);
00342 }
00343
00344 line_marker2_.scale.x = 0.05;
00345 line_marker2_.color.a = 1.0;
00346 line_marker2_.color.r = 0.0;
00347 line_marker2_.color.g = 0.0;
00348 line_marker2_.color.b = 1.0;
00349
00350
00351 geometry_msgs::Point ros_point3;
00352 arrow_marker3_.id=3;
00353 arrow_marker3_.header.frame_id = "/dabo/base_link";
00354 arrow_marker3_.header.stamp = ros::Time();
00355 arrow_marker3_.ns = "my_pitch";
00356 arrow_marker3_.type = visualization_msgs::Marker::ARROW;
00357 arrow_marker3_.action = visualization_msgs::Marker::ADD;
00358 arrow_marker3_.lifetime = ros::Duration(1.0f);
00359
00360
00361 if ( arrow_marker3_.points.size() <2)
00362 {
00363 ros_point3.x = 0;
00364 ros_point3.z =0;
00365 ros_point3.y = 0;
00366 arrow_marker3_.points.push_back(ros_point3);
00367 double x;
00368 if(a1>0){
00369 x=-5.0;
00370 ros_point3.x = -5/sqrt(5*5+((-1/a1)*(-5)+b1)*((-1/a1)*(-5)+b1));
00371 }else{
00372 x=5.0;
00373 ros_point3.x = 5/sqrt(5*5+((-1/a1)*5+b1)*((-1/a1)*5+b1));
00374 }
00375 ros_point3.z= ((-1/a1)*x+b1)/sqrt(5*5+((-1/a1)*x+b1)*((-1/a1)*x+b1));
00376 ros_point3.y = 0.0;
00377 arrow_marker3_.points.push_back(ros_point3);
00378
00379 }
00380
00381 arrow_marker3_.scale.x = 0.05;
00382 arrow_marker3_.scale.y = 0.05;
00383 arrow_marker3_.scale.z = 0.05;
00384
00385 arrow_marker3_.color.a = 1.0;
00386 arrow_marker3_.color.r = 0.0;
00387 arrow_marker3_.color.g = 0.3;
00388 arrow_marker3_.color.b = 0.7;
00389
00390
00391 geometry_msgs::Point ros_point4;
00392 arrow_marker4_.id=4;
00393 arrow_marker4_.header.frame_id = "/dabo/base_link";
00394 arrow_marker4_.header.stamp = ros::Time();
00395 arrow_marker4_.ns = "pitch";
00396 arrow_marker4_.type = visualization_msgs::Marker::ARROW;
00397 arrow_marker4_.action = visualization_msgs::Marker::ADD;
00398 arrow_marker4_.lifetime = ros::Duration(1.0f);
00399
00400
00401 if ( arrow_marker4_.points.size() <2)
00402 {
00403 double x;
00404 ros_point4.x = 0;
00405 ros_point4.z =0;
00406 ros_point4.y = 0;
00407 arrow_marker4_.points.push_back(ros_point4);
00408 if(tan(pitch)>0){
00409 x=-5.0;
00410 ros_point4.x = -5/sqrt(5*5+((-1/tan(pitch))*(-5))*((-1/tan(pitch))*(-5)));
00411 }
00412 else{
00413 x=5.0;
00414 ros_point4.x = 5/sqrt(5*5+((-1/tan(pitch))*5)*((-1/tan(pitch))*5));
00415 }
00416 ros_point4.z= ((-1/tan(pitch))*x)/sqrt(x*x+((-1/tan(pitch))*x)*((-1/tan(pitch))*x));
00417 ros_point4.y = 0.0;
00418 arrow_marker4_.points.push_back(ros_point4);
00419
00420 }
00421
00422 arrow_marker4_.scale.x = 0.05;
00423 arrow_marker4_.scale.y = 0.05;
00424 arrow_marker4_.scale.z = 0.05;
00425
00426 arrow_marker4_.color.a = 1.0;
00427 arrow_marker4_.color.r = 0.7;
00428 arrow_marker4_.color.g = 0.3;
00429 arrow_marker4_.color.b = 0.0;
00430
00431
00432 geometry_msgs::Point ros_point5;
00433 intersection_marker5_.id=5;
00434 intersection_marker5_.header.frame_id = "/dabo/base_link";
00435 intersection_marker5_.header.stamp = ros::Time();
00436 intersection_marker5_.ns = "intersection_point";
00437 intersection_marker5_.type = visualization_msgs::Marker::ARROW;
00438
00439 intersection_marker5_.action = visualization_msgs::Marker::ADD;
00440 intersection_marker5_.lifetime = ros::Duration(1.0f);
00441
00442
00443
00444
00445
00446
00447
00448 if ( intersection_marker5_.points.size() <2)
00449 {
00450 ros_point5.x = 0.28;
00451 ros_point5.z =0.44;
00452 ros_point5.y = 0;
00453 intersection_marker5_.points.push_back(ros_point5);
00454
00455 ros_point5.x = (0.44-b1)/a1+0.28;
00456 ros_point5.z=b1+0.44;
00457 ros_point5.y = 0.0;
00458 intersection_marker5_.points.push_back(ros_point5);
00459
00460 }
00461
00462 intersection_marker5_.scale.x = 0.1;
00463 intersection_marker5_.scale.y = 0.1;
00464 intersection_marker5_.scale.z = 0.1;
00465
00466 intersection_marker5_.color.a = 1.0;
00467 intersection_marker5_.color.r = 0.5;
00468 intersection_marker5_.color.g = 0.0;
00469 intersection_marker5_.color.b = 0.5;
00470
00471
00472
00473
00474
00475
00476
00477
00478
00479
00480
00481
00482
00483
00484
00485
00486
00487
00488
00489
00490
00491
00492
00493
00494
00495
00496
00497
00498
00499
00500
00501
00502
00503
00504
00505
00506
00507
00508
00509
00510
00511
00512
00513
00514
00515 switch(result_lines_){
00516
00517 case One_line_state:
00518
00519 MarkerArray_msg_.markers.clear();
00520
00521 MarkerArray_msg_.markers.push_back(arrow_marker3_);
00522 MarkerArray_msg_.markers.push_back(arrow_marker4_);
00523 MarkerArray_msg_.markers.push_back(intersection_marker5_);
00524 MarkerArray_msg_.markers.push_back(line_marker_);
00525
00526 break;
00527
00528 case Two_lines_state:
00529
00530 MarkerArray_msg_.markers.clear();
00531
00532 MarkerArray_msg_.markers.push_back(arrow_marker4_);
00533 MarkerArray_msg_.markers.push_back(arrow_marker3_);
00534 MarkerArray_msg_.markers.push_back(intersection_marker5_);
00535 MarkerArray_msg_.markers.push_back(line_marker_);
00536 MarkerArray_msg_.markers.push_back(line_marker2_);
00537
00538 break;
00539
00540 case Line_partial_state:
00541
00542 MarkerArray_msg_.markers.clear();
00543
00544 MarkerArray_msg_.markers.push_back(arrow_marker4_);
00545 MarkerArray_msg_.markers.push_back(arrow_marker3_);
00546 MarkerArray_msg_.markers.push_back(intersection_marker5_);
00547 MarkerArray_msg_.markers.push_back(line_marker_);
00548
00549 break;
00550
00551 case Line_unknown_state:
00552
00553 MarkerArray_msg_.markers.clear();
00554
00555 break;
00556
00557 }
00558
00559 }
00560
00561 void TibiDaboPitchEstimatorAlgNode::marker_point_front_laser_node(double front_laser_point_x, double front_laser_point_y)
00562 {
00563
00564
00565 distance_front_laser_marker6_.points.clear();
00566 geometry_msgs::Point ros_point6;
00567 distance_front_laser_marker6_.id=6;
00568 distance_front_laser_marker6_.header.frame_id = "/dabo/base_link";
00569 distance_front_laser_marker6_.header.stamp = ros::Time();
00570 distance_front_laser_marker6_.ns = "puntos_front_laser";
00571
00572 distance_front_laser_marker6_.type = visualization_msgs::Marker::SPHERE;
00573 distance_front_laser_marker6_.action = visualization_msgs::Marker::ADD;
00574 distance_front_laser_marker6_.lifetime = ros::Duration(1.0f);
00575
00576
00577
00578
00579
00580
00581
00582
00583
00584
00585
00586
00587
00588
00589
00590 distance_front_laser_marker6_.pose.position.x=front_laser_point_x;
00591 distance_front_laser_marker6_.pose.position.y=front_laser_point_y;
00592 distance_front_laser_marker6_.pose.position.z=0.44;
00593
00594 distance_front_laser_marker6_.scale.x = 0.2;
00595 distance_front_laser_marker6_.scale.y = 0.2;
00596 distance_front_laser_marker6_.scale.z = 0.2;
00597
00598 distance_front_laser_marker6_.color.a = 1.0;
00599 distance_front_laser_marker6_.color.r = 1.0;
00600 distance_front_laser_marker6_.color.g = 0.0;
00601 distance_front_laser_marker6_.color.b = 0.0;
00602 MarkerArray_msg_.markers.clear();
00603 MarkerArray_msg_.markers.push_back(distance_front_laser_marker6_);
00604 }
00605
00606
00607
00608
00609
00610
00611
00612
00613
00614
00615 void TibiDaboPitchEstimatorAlgNode::node_config_update(Config &config, uint32_t level)
00616 {
00617 this->alg_.lock();
00618
00619 this->alg_.unlock();
00620 }
00621
00622 void TibiDaboPitchEstimatorAlgNode::addNodeDiagnostics(void)
00623 {
00624 }
00625
00626
00627 int main(int argc,char *argv[])
00628 {
00629 return algorithm_base::main<TibiDaboPitchEstimatorAlgNode>(argc, argv, "tibi_dabo_pitch_estimator_alg_node");
00630 }