tibi_dabo_pitch_estimator_alg_node.cpp
Go to the documentation of this file.
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   //init class attributes if necessary
00014   //this->loop_rate_ = 2;//in [Hz]
00015 
00016   // [init publishers]
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   // [init subscribers]
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   // [init services]
00028   
00029   // [init clients]
00030   
00031   // [init action servers]
00032   
00033   // [init action clients]
00034 }
00035 
00036 TibiDaboPitchEstimatorAlgNode::~TibiDaboPitchEstimatorAlgNode(void)
00037 {
00038   // [free dynamic memory]
00039 }
00040 
00041 void TibiDaboPitchEstimatorAlgNode::mainNodeThread(void)
00042 {
00043 
00044 //this->laser_mutex_.enter(); 
00045  this->alg_.lock(); 
00046                 
00047                 result_=reg_line_.linear_regression(laser_,a1,b1,a2,b2,error);
00048 
00049 //NOTA: hacer switch con el enum de C++
00050                 switch(result_){
00051                 
00052                         case Claser_linear_regression::One_line:
00053                 
00054                                 //ROS_INFO("\n a1= %lf b1= %lf with error=%lf",a1,b1,error);
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                                 //ROS_INFO("\n a1= %lf b1= %lf a2= %lf b2= %lf with error=%lf",a1,b1,a2,b2,error);
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                                 //ROS_INFO("\n a1= %lf b1= %lf with error=%lf",a1,b1,error);
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                                 //ROS_INFO("\n too much error in linear regression");
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 //this->laser_mutex_.exit(); 
00088   // [fill msg structures]
00089   //this->LaserScan_msg_.data = my_var;
00090   //this->MarkerArray_msg_.data = my_var;
00091   
00092   // [fill srv structure and make request to the server]
00093   
00094   // [fill action structure and make request to the action server]
00095 
00096   // [publish messages]
00097   
00098   this->MarkerArray_lines_publisher_.publish(this->MarkerArray_msg_);
00099 }
00100 
00101 /*  [subscriber callbacks] */
00102 void TibiDaboPitchEstimatorAlgNode::pitch_callback(const iri_segway_rmp_msgs::SegwayRMP200Status::ConstPtr& msg) 
00103 { 
00104   //ROS_INFO("TibiDaboPitchEstimatorAlgNode::pitch_callback: New Message Received"); 
00105 
00106   //use appropiate mutex to shared variables if necessary 
00107   this->alg_.lock(); 
00108   this->pitch_mutex_.enter(); 
00109 
00110   pitch=msg->pitch_angle;
00111 
00112   //unlock previously blocked shared variables 
00113   this->alg_.unlock(); 
00114   this->pitch_mutex_.exit(); 
00115 }
00116 void TibiDaboPitchEstimatorAlgNode::laser_callback(const sensor_msgs::LaserScan::ConstPtr& msg) 
00117 { 
00118   //ROS_INFO("TibiDaboPitchEstimatorAlgNode::laser_callback: New Message Received");
00119   //use appropiate mutex to shared variables if necessary 
00120   this->laser_mutex_.enter(); 
00121                 //iterative laser 
00122                 //read the laser data
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                                 //save laser point into "my" laser_
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   //unlock previously blocked shared variables 
00138   this->laser_mutex_.exit(); 
00139 
00140 }
00141 
00142 //function front_laser
00143 
00144 
00145 void TibiDaboPitchEstimatorAlgNode::front_laser_callback(const sensor_msgs::LaserScan::ConstPtr& msg) 
00146 { 
00147   //ROS_INFO("TibiDaboPitchEstimatorAlgNode::front_laser_callback: New Message Received");
00148   //use appropiate mutex to shared variables if necessary 
00149   //iterative front laser 
00150   //read the laser data
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; //coge todo el mensage del front laser y lo copia a mi laser filtrado. (que saldra este por salida o este, con posicion del punto a 0.0, para flitrarlo.
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         //función para mostrar por pantalla los laseres del front laser para usarlos con matlab.
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                         //printf("%lf %lf\n", msg->ranges[i] * cos(angle)-0.28,0.44-msg->ranges[i] * sin(angle));
00196                         angle += msg->angle_increment;
00197 
00198                 }
00199         //printf("\n");
00200         //printf("\n");
00201         //printf("\n");
00202         
00203           this->alg_.unlock();
00204   //unlock previously blocked shared variables 
00205   this->laser_mutex_.exit(); 
00206 
00207 }
00208  
00209 //function rear_laser
00210 
00211 void TibiDaboPitchEstimatorAlgNode::rear_laser_callback(const sensor_msgs::LaserScan::ConstPtr& msg) 
00212 { 
00213   //ROS_INFO("TibiDaboPitchEstimatorAlgNode::rear_laser_callback: New Message Received");
00214   //use appropiate mutex to shared variables if necessary 
00215   //iterative rear laser 
00216   //read the laser data
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 ;  //double intersection_y = (0.44-b1_)/(-a1_)+0.28 ;
00235                 double intersection_x = b1+0.44 ; //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         //función para mostrar por pantalla los laseres del rear laser para usarlos con matlab.
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                         //printf("%lf %lf\n", msg->ranges[i] * cos(angle)-0.28,0.44-msg->ranges[i] * sin(angle));
00264                         angle += msg->angle_increment;
00265 
00266                 }
00267         
00268         //printf("\n");
00269         //printf("\n");
00270         //printf("\n");
00271         
00272         this->alg_.unlock();
00273   //unlock previously blocked shared variables 
00274   this->laser_mutex_.exit(); 
00275 
00276 
00277 }
00278 
00279 
00280 //function to create lines in rviz, with the points of the laser.
00281 
00282 void TibiDaboPitchEstimatorAlgNode::line_node(double& a1,double& b1,double& a2,double& b2, res_lines result_lines_)
00283 {
00284         //line floor and wall marker
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         //distance_front_laser_marker6_.points.clear();
00291                 //marker line1 floor
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                 //marker line2 wall
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         //marker my_pitch       
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         //arrow_marker3_.points.reserve(2);
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));// pitch line. witch Position 90º respect the floor.
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         //marker pitch  
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         //arrow_marker4_.points.reserve(2);
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));// pitch line. witch Position 90º respect the floor.
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                 //marker intersection point     
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                 //intersection_marker5_.type = visualization_msgs::Marker::SPHERE;              
00439                 intersection_marker5_.action = visualization_msgs::Marker::ADD;
00440                 intersection_marker5_.lifetime = ros::Duration(1.0f);
00441         
00442                 /*intersection_marker5_.pose.position.x=(0.44-b1)/a1+0.28;
00443                 intersection_marker5_.pose.position.z=b1+0.44;//intersection point front_laser with floor.
00444                 intersection_marker5_.pose.position.y=0;
00445                 intersection_marker5_.points.push_back(ros_point5);*/
00446                 //ROS_INFO("intersection point X=%lf intersection point Y= %lf" ,(0.44-b1)/a1,b1);      
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; //mirar.
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;// pitch line. witch Position 90º respect the floor.
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         /*//marker point        front laser
00472                         
00473                 geometry_msgs::Point ros_point6;
00474                 distance_front_laser_marker6_.id=5;             
00475                 distance_front_laser_marker6_.header.frame_id = "/dabo/base_link";
00476                 distance_front_laser_marker6_.header.stamp = ros::Time();
00477                 distance_front_laser_marker6_.ns = "puntos_front_laser";
00478                 //distance_front_laser_marker6_.type = visualization_msgs::Marker::ARROW;
00479                 distance_front_laser_marker6_.type = visualization_msgs::Marker::SPHERE;        
00480                 distance_front_laser_marker6_.action = visualization_msgs::Marker::ADD;
00481                 distance_front_laser_marker6_.lifetime = ros::Duration(1.0f);   
00482 
00483                 if ( distance_front_laser_marker6_.points.size() <2)
00484                 {
00485                         ros_point6.x = 0.28 ;
00486                         ros_point6.z = 0.44 ;
00487                         ros_point6.y = 0 ; //mirar.
00488                         distance_front_laser_marker6_.points.push_back(ros_point6);
00489                                                         
00490                         ros_point6.x = distance_point_laser;    
00491                         ros_point6.z= 0 ;// pitch line. witch Position 90º respect the floor.
00492                         ros_point6.y = 0.0 ;
00493                         distance_front_laser_marker6_.points.push_back(ros_point6);
00494         
00495                 }
00496 
00497                 distance_front_laser_marker6_.pose.position.x=front_laser_point_x;
00498                 distance_front_laser_marker6_.pose.position.y=front_laser_point_y;//point front_laser
00499                 distance_front_laser_marker6_.pose.position.z=0.44;
00500 
00501 
00502 
00503                 distance_front_laser_marker6_.scale.x = 0.1;
00504                 distance_front_laser_marker6_.scale.y = 0.1;
00505                 distance_front_laser_marker6_.scale.z = 0.1;
00506         
00507                 distance_front_laser_marker6_.color.a = 1.0;
00508                 distance_front_laser_marker6_.color.r = 0.5;
00509                 distance_front_laser_marker6_.color.g = 1.0;
00510                 distance_front_laser_marker6_.color.b = 0.0;*/
00511         
00512         
00513         
00514         
00515                 switch(result_lines_){
00516                 
00517                         case One_line_state:
00518                         
00519                                         MarkerArray_msg_.markers.clear();
00520                                         //MarkerArray_msg_.markers.push_back(distance_front_laser_marker6_);
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                         //ROS_INFO("caso: %d" , One_line_state);
00526                         break;
00527                 
00528                         case Two_lines_state:
00529                         
00530                                 MarkerArray_msg_.markers.clear();
00531                                 //MarkerArray_msg_.markers.push_back(distance_front_laser_marker6_);
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                         //ROS_INFO("caso: %d" , Two_lines_state);
00538                         break;
00539                         
00540                         case Line_partial_state:
00541                         
00542                                 MarkerArray_msg_.markers.clear();
00543                                 //MarkerArray_msg_.markers.push_back(distance_front_laser_marker6_);
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                         //ROS_INFO("caso: %d" , Line_partial_state);
00549                         break;
00550                 
00551                         case Line_unknown_state:
00552                                 
00553                                 MarkerArray_msg_.markers.clear();
00554                         //ROS_INFO("caso: %d" , Line_unknown_state);
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         //marker point  front laser             
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                 //distance_front_laser_marker6_.type = visualization_msgs::Marker::ARROW;
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                 /*if ( distance_front_laser_marker6_.points.size() <2)
00577                 {
00578                         ros_point6.x = 0.28 ;
00579                         ros_point6.z = 0.44 ;
00580                         ros_point6.y = 0 ; //mirar.
00581                         distance_front_laser_marker6_.points.push_back(ros_point6);
00582                                                         
00583                         ros_point6.x = distance_point_laser;    
00584                         ros_point6.z= 0 ;// pitch line. witch Position 90º respect the floor.
00585                         ros_point6.y = 0.0 ;
00586                         distance_front_laser_marker6_.points.push_back(ros_point6);
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 /*  [service callbacks] */
00610 
00611 /*  [action callbacks] */
00612 
00613 /*  [action requests] */
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 /* main function */
00627 int main(int argc,char *argv[])
00628 {
00629   return algorithm_base::main<TibiDaboPitchEstimatorAlgNode>(argc, argv, "tibi_dabo_pitch_estimator_alg_node");
00630 }


tibi_dabo_pitch_estimator
Author(s): erepiso
autogenerated on Fri Dec 6 2013 20:37:50