follow_pedestrian.cpp
Go to the documentation of this file.
00001 /**************************************************************************************************
00002  Software License Agreement (BSD License)
00003 
00004  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
00005  All rights reserved.
00006 
00007  Redistribution and use in source and binary forms, with or without modification, are permitted
00008  provided that the following conditions are met:
00009 
00010   *Redistributions of source code must retain the above copyright notice, this list of
00011    conditions and the following disclaimer.
00012   *Redistributions in binary form must reproduce the above copyright notice, this list of
00013    conditions and the following disclaimer in the documentation and/or other materials provided
00014    with the distribution.
00015   *Neither the name of the University of Aveiro nor the names of its contributors may be used to
00016    endorse or promote products derived from this software without specific prior written permission.
00017  
00018  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
00019  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
00020  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
00021  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00022  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
00023  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
00024  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
00025  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 ***************************************************************************************************/
00035 #ifndef _FOLLOW_PEDESTRIAN_CPP_
00036 #define _FOLLOW_PEDESTRIAN_CPP_
00037 
00038 #include "follow_pedestrian.h"
00039 
00040 
00041 void foveationcontrol_sweeping(void)
00042 {
00043         static ros::Time tic=ros::Time::now();
00044         //      static int state=0;
00045         double x,y,z;
00046         pcl::PointXYZ pt;       
00047 
00048         if((ros::Time::now()-tic).toSec()>4.)
00049         {
00050                 tic=ros::Time::now();
00051 
00052                 x = (((double)rand())/(double)RAND_MAX);
00053                 pt.x = x*10+15;
00054 
00055                 y = (((double)rand())/(double)RAND_MAX);
00056                 pt.y = y*20-10;
00057 
00058                 z = (((double)rand())/(double)RAND_MAX);
00059                 pt.z = z*2;
00060 
00061                 pcl::PointCloud<pcl::PointXYZ> pc;
00062                 pc.points.push_back(pt);
00063                 sensor_msgs::PointCloud2 pcmsg_out;
00064                 pcl::toROSMsg(pc, pcmsg_out);
00065                 pcmsg_out.header.stamp = ros::Time::now();
00066                 pcmsg_out.header.frame_id = "/atc/vehicle/rear_axis";
00067                 p_pub_fctlr->publish(pcmsg_out);
00068 
00069         }
00070 }
00071 
00072 bool is_safe_using_lasers(void)
00073 {
00074         static ros::Time tic = ros::Time::now();
00075 
00076 
00077         if(!FLAG_LASER_SAFE_TO_DRIVE)
00078                 tic = ros::Time::now();
00079 
00080         if((ros::Time::now() - tic).toSec() > 5.5)
00081         {
00082                 return 1;
00083         }
00084         else
00085         {
00086                 return 0;
00087         }
00088 }
00089 
00090 void sleepok(int t, ros::NodeHandle &nh)
00091 {
00092         if (nh.ok()) sleep(t);
00093 }
00094 
00095 void play_sound(int sit, int mandatory, double num_h)
00096 {
00097         //always 0 - 5 hipothesys
00098         unsigned int b_h;       
00099 
00100         if (mandatory<0)
00101         {
00102                 status.tic_last_sound=ros::Time::now();
00103 
00104         }else if ((ros::Time::now()-status.tic_last_sound).toSec() >mandatory)
00105         {
00106                 status.tic_last_sound=ros::Time::now();
00107         }
00108         else
00109         {
00110                 return;
00111         }
00112 
00113         b_h = round((double)(a_h*(double)num_h));
00114         char text[1024];
00115         sprintf(text,"sit%d_hip%d",sit,b_h);
00116 
00117 
00118         std::string path= ros::package::getPath("atlas_sound_player")+ "/Recordings/GoogleLady_ros/" + text + ".wav";
00119         p_sc->playWave(path);
00120         sleepok(0.1, *p_n);
00121 
00122         printf("playing sound %s\n",text);
00123         //sleep(3);
00124 
00125 }
00126 
00127 
00128 
00129 void print_status(t_status* status)                                                                    
00130 {
00131         printf("*****************************\n");
00132         switch(status->state)
00133         {   
00134                 case SEARCHING:
00135                         printf("** Searching for new target\n");
00136                         break;
00137 
00138                 case TRACKING:
00139                         printf("** Tracking target %d\n",status->target_id);
00140                         break;
00141 
00142                 case TARGET_LOST:
00143                         printf("** Target lost\n");
00144                         break;
00145 
00146                 case INITIALISE:
00147                         printf("** Initialising\n");
00148                         break;
00149                 case TRACKING_NOT_SAFE:
00150                         printf("** Tracking_not_safe\n");
00151                         break;
00152         }   
00153 }
00154 
00155 
00156 bool check_safety_zone(t_targets* targets, t_safety_zone* safety_zone)                                
00157 {
00158         double x,y;
00159         for(size_t i=0; i<targets->position.points.size(); ++i)
00160         {
00161                 x=targets->position[i].x;
00162                 y=targets->position[i].y;
00163 
00164                 if(x<safety_zone->xmax && x>safety_zone->xmin && y<safety_zone->ymax && y>safety_zone->ymin)
00165                         return false;
00166         }
00167 
00168         return true;
00169 }
00170 
00171 
00172 void mtt_targets_cb (const mtt::TargetListPC& targetlist)
00173 {
00174         pcl::PointCloud<pcl::PointXYZ> pc_local;
00175     
00176     pcl::PCLPointCloud2 pcl_pc;
00177     pcl_conversions::toPCL(targetlist.position, pcl_pc);
00178     pcl::fromPCLPointCloud2(pcl_pc, pc_local);
00179     
00180 //     pcl::fromROSMsg(targetlist.position, pc_local);
00181 
00182         pcl::PointCloud<pcl::PointXYZ> v_local;
00183     
00184     pcl_conversions::toPCL(targetlist.velocity, pcl_pc);
00185     pcl::fromPCLPointCloud2(pcl_pc, v_local);
00186     
00187 //      pcl::fromROSMsg(targetlist.velocity, v_local);
00188 
00189 
00190         tf::StampedTransform transform;
00191         try
00192         {
00193                 p_listener->lookupTransform(targetlist.header.frame_id, "/atc/vehicle/rear_axis" , ros::Time(0), transform);
00194         }
00195         catch (tf::TransformException ex)
00196         {
00197                 ROS_ERROR("Could find valid transform after waiting 3 secs\n.%s",ex.what());
00198         }
00199 
00200 
00201         // Transform pc1 to pc2 ->transform
00202         pcl_ros::transformPointCloud(pc_local, targets.position, transform.inverse());
00203         targets.position.header.frame_id = "/atc/vehicle/rear_axis";
00204 
00205         pcl_ros::transformPointCloud(v_local, targets.velocity, transform.inverse());
00206         targets.position.header.frame_id = "/atc/vehicle/rear_axis";
00207 
00208         targets.id.erase(targets.id.begin(), targets.id.end());
00209         for (size_t i=0; i<targetlist.id.size(); ++i)
00210         {
00211                 targets.id.push_back(targetlist.id[i]);
00212         }
00213 
00214 
00215         //check safety zone
00216         FLAG_LASER_SAFE_TO_DRIVE = check_safety_zone(&targets, &safety_zone);
00217 
00218 #if _USE_DEBUG_
00219         //ROS_INFO("Received mtt_targets id size=%ld pc size = %ld", targets.id.size(), pc.points.size());
00220 #endif
00221 
00222 }
00223 
00224 
00225 bool search_for_new_target(t_targets* targets, t_status* status, t_search_area* area)
00226 {
00227         double d;
00228 
00229         for(size_t i=0; i<targets->id.size(); ++i)
00230         {
00231                 d=sqrt( (targets->position[i].x - area->x)*(targets->position[i].x - area->x)+
00232                                 (targets->position[i].y - area->y)*(targets->position[i].y - area->y));
00233 
00234                 if(d > area->radius)
00235                         continue;
00236 
00237 
00238                 ROS_INFO("Search area x=%f y=%f rad=%f \nFound target %d x=%f y=%f inside search zone %f",area->x, area->y, area->radius, targets->id[i],targets->position[i].x, targets->position[i].y, d);
00240                 status->target_id = targets->id[i];
00241                 status->current_x = targets->position[i].x;
00242                 status->current_y = targets->position[i].y;
00243                 status->current_z = targets->position[i].z;
00244 
00245                 return true;
00246         }
00247 
00248         return false;
00249 }
00250 
00251 bool get_new_target_information(t_targets *targets, t_status* status)
00252 {
00253         for(size_t i=0; i<targets->id.size(); ++i)
00254         {
00255                 if(status->target_id!= targets->id[i])
00256                         continue;
00257 
00258                 status->target_id = targets->id[i];
00259                 status->current_x = targets->position[i].x;
00260                 status->current_y = targets->position[i].y;
00261                 status->current_z = targets->position[i].z;
00262 
00263                 status->current_q = tf::createQuaternionMsgFromYaw(atan2(targets->velocity[i].y, targets->velocity[i].x)); 
00264 
00265                 return true;
00266         }
00267 
00268         return false;
00269 }
00270 
00271 void init_search_area(t_search_area* area)
00272 {
00273         //Set the search area
00274         area->x = _SEARCH_X_;   
00275         area->y = _SEARCH_Y_;   
00276         area->radius = _SEARCH_RADIUS_;
00277 }
00278 
00279 void foveationcontrol(t_status* status)
00280 {
00281         pcl::PointCloud<pcl::PointXYZ> pc;
00282         pcl::PointXYZ pt;       
00283         pt.x = status->current_x; pt.y = status->current_y;     pt.z = 0.8;
00284         pc.points.push_back(pt);
00285         sensor_msgs::PointCloud2 pcmsg_out;
00286         pcl::toROSMsg(pc, pcmsg_out);
00287         pcmsg_out.header.stamp = ros::Time::now();
00288         pcmsg_out.header.frame_id = "/atc/vehicle/rear_axis";
00289         p_pub_fctlr->publish(pcmsg_out);
00290 }
00291 
00292 void foveationcontrol_home(void)
00293 {
00294         pcl::PointCloud<pcl::PointXYZ> pc;
00295         pcl::PointXYZ pt;       
00296         pt.x = 10; pt.y = 0;    pt.z = 5;
00297         pc.points.push_back(pt);
00298         sensor_msgs::PointCloud2 pcmsg_out;
00299         pcl::toROSMsg(pc, pcmsg_out);
00300         pcmsg_out.header.stamp = ros::Time::now();
00301         pcmsg_out.header.frame_id = "/atc/vehicle/rear_axis";
00302         p_pub_fctlr->publish(pcmsg_out);
00303 }
00304 
00305 
00306 // void set_high_command_msg_direction_speed(atlascar_base::AtlascarCommand& msg, double dir, double speed)
00307 // {
00308 //      msg.steering_wheel = dir;
00309 //      msg.speed = speed;
00310 // }
00311 
00312 // void set_high_command_msg_lights(atlascar_base::AtlascarCommand& msg, bool high, bool medium, bool left, bool right, bool warning)
00313 // {
00314 //      msg.lights_high = high;
00315 //      msg.lights_medium = medium;
00316 //      msg.lights_left = left;
00317 //      msg.lights_right = right;
00318 //      msg.lights_warning = warning;
00319 // }
00320 
00321 int main(int argc, char **argv)
00322 {
00323 
00324         ros::init(argc, argv, "planar_pc_generator_node");
00325         ros::NodeHandle n("~");
00326         tf::TransformListener listener(n,ros::Duration(10));
00327         p_listener=&listener;
00328         p_n=&n;
00329 
00330         //create a sound_play client
00331         sound_play::SoundClient sc;
00332         p_sc = &sc;
00333 
00334         //create the fctlr publisher
00335         ros::Publisher pub_fctlr = n.advertise<sensor_msgs::PointCloud2>("/target", 1);
00336         p_pub_fctlr = &pub_fctlr;
00337 
00338         //ros::Publisher pedestrian_marker_pub = n.advertise<visualization_msgs::Marker>("/pedestrian_marker", 1);
00339 
00340         //set the search area
00341         init_search_area(&search_area);
00342 
00343         //set the safety zone
00344         safety_zone.xmax = _SAFE_ZONE_X_MAX_;
00345         safety_zone.xmin = _SAFE_ZONE_X_MIN_;
00346         safety_zone.ymax = _SAFE_ZONE_Y_MAX_;
00347         safety_zone.ymin = _SAFE_ZONE_Y_MIN_;
00348 
00349         //declare the subscribers
00350         ros::Subscriber sub_targets = n.subscribe("/mtt/targets", 1, mtt_targets_cb);
00351 
00352     ROS_ERROR("AtlascarCommand no longer avaliable, please correct");
00353         //declare the publishers
00354         ros::Publisher vis_pub = n.advertise<visualization_msgs::MarkerArray>( "/follow_pedestrian_markers", 0 );
00355 //      command_pub = n.advertise<atlascar_base::AtlascarCommand>("/atc/base/command", 10);
00356 
00357 //      command_msg.direct_control=0;
00358 //      command_msg.ignition=1;
00359 //      command_msg.lifetime=2;
00360 //      command_msg.priority=1;
00361 //      command_msg.auto_direction=1;
00362 //      command_msg.auto_ignition=1;
00363 //      command_msg.auto_throttle=1;
00364 //      command_msg.auto_brake=1;
00365 //      command_msg.auto_clutch=1;
00366 
00367         //STATUS msgs
00368         status.state=INITIALISE;
00369         status.tic_last_sound = ros::Time::now();
00370 
00371         //wait a bit before starting
00372         ros::Rate initial_sleep(0.2);
00373         initial_sleep.sleep();
00374 
00375         ros::Rate loop_rate(10);
00376         while (n.ok())
00377         {
00378                 ros::spinOnce();
00379 
00380                 //Run the state machine
00381                 state_machine();
00382 
00383                 //   ___________________________________
00384                 //   |                                 |
00385                 //   |        DRAW_IN_RVIZ             |
00386                 //   |_________________________________| 
00387                 visualization_msgs::MarkerArray marker_msg;
00388                 add_to_viz_markers_vec(&marker_msg.markers);
00389                 vis_pub.publish(marker_msg);
00390 
00391 
00392                 loop_rate.sleep();      
00393         }
00394 }
00395 #endif


follow_pedestrian
Author(s): Miguel Oliveira, Jorge Almeida
autogenerated on Fri Jun 6 2014 18:36:34