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
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
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
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
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 pcl::fromROSMsg(targetlist.position, pc_local);
00176
00177 pcl::PointCloud<pcl::PointXYZ> v_local;
00178 pcl::fromROSMsg(targetlist.velocity, v_local);
00179
00180
00181 tf::StampedTransform transform;
00182 try
00183 {
00184 p_listener->lookupTransform(targetlist.header.frame_id, "/atc/vehicle/rear_axis" , ros::Time(0), transform);
00185 }
00186 catch (tf::TransformException ex)
00187 {
00188 ROS_ERROR("Could find valid transform after waiting 3 secs\n.%s",ex.what());
00189 }
00190
00191
00192
00193 pcl_ros::transformPointCloud(pc_local, targets.position, transform.inverse());
00194 targets.position.header.frame_id = "/atc/vehicle/rear_axis";
00195
00196 pcl_ros::transformPointCloud(v_local, targets.velocity, transform.inverse());
00197 targets.position.header.frame_id = "/atc/vehicle/rear_axis";
00198
00199 targets.id.erase(targets.id.begin(), targets.id.end());
00200 for (size_t i=0; i<targetlist.id.size(); ++i)
00201 {
00202 targets.id.push_back(targetlist.id[i]);
00203 }
00204
00205
00206
00207 FLAG_LASER_SAFE_TO_DRIVE = check_safety_zone(&targets, &safety_zone);
00208
00209 #if _USE_DEBUG_
00210
00211 #endif
00212
00213 }
00214
00215
00216 bool search_for_new_target(t_targets* targets, t_status* status, t_search_area* area)
00217 {
00218 double d;
00219
00220 for(size_t i=0; i<targets->id.size(); ++i)
00221 {
00222 d=sqrt( (targets->position[i].x - area->x)*(targets->position[i].x - area->x)+
00223 (targets->position[i].y - area->y)*(targets->position[i].y - area->y));
00224
00225 if(d > area->radius)
00226 continue;
00227
00228
00229 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);
00231 status->target_id = targets->id[i];
00232 status->current_x = targets->position[i].x;
00233 status->current_y = targets->position[i].y;
00234 status->current_z = targets->position[i].z;
00235
00236 return true;
00237 }
00238
00239 return false;
00240 }
00241
00242 bool get_new_target_information(t_targets *targets, t_status* status)
00243 {
00244 for(size_t i=0; i<targets->id.size(); ++i)
00245 {
00246 if(status->target_id!= targets->id[i])
00247 continue;
00248
00249 status->target_id = targets->id[i];
00250 status->current_x = targets->position[i].x;
00251 status->current_y = targets->position[i].y;
00252 status->current_z = targets->position[i].z;
00253
00254 status->current_q = tf::createQuaternionMsgFromYaw(atan2(targets->velocity[i].y, targets->velocity[i].x));
00255
00256 return true;
00257 }
00258
00259 return false;
00260 }
00261
00262 void init_search_area(t_search_area* area)
00263 {
00264
00265 area->x = _SEARCH_X_;
00266 area->y = _SEARCH_Y_;
00267 area->radius = _SEARCH_RADIUS_;
00268 }
00269
00270 void foveationcontrol(t_status* status)
00271 {
00272 pcl::PointCloud<pcl::PointXYZ> pc;
00273 pcl::PointXYZ pt;
00274 pt.x = status->current_x; pt.y = status->current_y; pt.z = 0.8;
00275 pc.points.push_back(pt);
00276 sensor_msgs::PointCloud2 pcmsg_out;
00277 pcl::toROSMsg(pc, pcmsg_out);
00278 pcmsg_out.header.stamp = ros::Time::now();
00279 pcmsg_out.header.frame_id = "/atc/vehicle/rear_axis";
00280 p_pub_fctlr->publish(pcmsg_out);
00281 }
00282
00283 void foveationcontrol_home(void)
00284 {
00285 pcl::PointCloud<pcl::PointXYZ> pc;
00286 pcl::PointXYZ pt;
00287 pt.x = 10; pt.y = 0; pt.z = 5;
00288 pc.points.push_back(pt);
00289 sensor_msgs::PointCloud2 pcmsg_out;
00290 pcl::toROSMsg(pc, pcmsg_out);
00291 pcmsg_out.header.stamp = ros::Time::now();
00292 pcmsg_out.header.frame_id = "/atc/vehicle/rear_axis";
00293 p_pub_fctlr->publish(pcmsg_out);
00294 }
00295
00296
00297 void set_high_command_msg_direction_speed(atlascar_base::AtlascarCommand& msg, double dir, double speed)
00298 {
00299 msg.steering_wheel = dir;
00300 msg.speed = speed;
00301 }
00302
00303 void set_high_command_msg_lights(atlascar_base::AtlascarCommand& msg, bool high, bool medium, bool left, bool right, bool warning)
00304 {
00305 msg.lights_high = high;
00306 msg.lights_medium = medium;
00307 msg.lights_left = left;
00308 msg.lights_right = right;
00309 msg.lights_warning = warning;
00310 }
00311
00312 int main(int argc, char **argv)
00313 {
00314
00315 ros::init(argc, argv, "planar_pc_generator_node");
00316 ros::NodeHandle n("~");
00317 tf::TransformListener listener(n,ros::Duration(10));
00318 p_listener=&listener;
00319 p_n=&n;
00320
00321
00322 sound_play::SoundClient sc;
00323 p_sc = ≻
00324
00325
00326 ros::Publisher pub_fctlr = n.advertise<sensor_msgs::PointCloud2>("/target", 1);
00327 p_pub_fctlr = &pub_fctlr;
00328
00329
00330
00331
00332 init_search_area(&search_area);
00333
00334
00335 safety_zone.xmax = _SAFE_ZONE_X_MAX_;
00336 safety_zone.xmin = _SAFE_ZONE_X_MIN_;
00337 safety_zone.ymax = _SAFE_ZONE_Y_MAX_;
00338 safety_zone.ymin = _SAFE_ZONE_Y_MIN_;
00339
00340
00341 ros::Subscriber sub_targets = n.subscribe("/mtt/targets", 1, mtt_targets_cb);
00342
00343
00344 ros::Publisher vis_pub = n.advertise<visualization_msgs::MarkerArray>( "/follow_pedestrian_markers", 0 );
00345 command_pub = n.advertise<atlascar_base::AtlascarCommand>("/atc/base/command", 10);
00346
00347 command_msg.direct_control=0;
00348 command_msg.ignition=1;
00349 command_msg.lifetime=2;
00350 command_msg.priority=1;
00351 command_msg.auto_direction=1;
00352 command_msg.auto_ignition=1;
00353 command_msg.auto_throttle=1;
00354 command_msg.auto_brake=1;
00355 command_msg.auto_clutch=1;
00356
00357
00358 status.state=INITIALISE;
00359 status.tic_last_sound = ros::Time::now();
00360
00361
00362 ros::Rate initial_sleep(0.2);
00363 initial_sleep.sleep();
00364
00365 ros::Rate loop_rate(10);
00366 while (n.ok())
00367 {
00368 ros::spinOnce();
00369
00370
00371 state_machine();
00372
00373
00374
00375
00376
00377 visualization_msgs::MarkerArray marker_msg;
00378 add_to_viz_markers_vec(&marker_msg.markers);
00379 vis_pub.publish(marker_msg);
00380
00381
00382 loop_rate.sleep();
00383 }
00384 }
00385 #endif