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_H_
00036 #define _FOLLOW_PEDESTRIAN_H_
00037
00038 #include <stdio.h>
00039 #include <ros/ros.h>
00040 #include <laser_geometry/laser_geometry.h>
00041 #include <sensor_msgs/LaserScan.h>
00042 #include <sensor_msgs/PointCloud2.h>
00043 #include <tf/transform_listener.h>
00044 #include <pcl_ros/transforms.h>
00045 #include <pcl/ros/conversions.h>
00046 #include <pcl/point_cloud.h>
00047 #include <pcl/point_types.h>
00048 #include <pcl/segmentation/extract_polygonal_prism_data.h>
00049 #include <pcl/filters/extract_indices.h>
00050 #include <pcl/filters/project_inliers.h>
00051
00052
00053 #include <visualization_msgs/Marker.h>
00054 #include <visualization_msgs/MarkerArray.h>
00055 #include <mtt/TargetListPC.h>
00056
00057
00058 #include <atlascar_base/AtlascarCommand.h>
00059 #include <sound_play/sound_play.h>
00060
00061 #include <ros/package.h>
00062
00063 #define PFLN printf("file %s line %d\n",__FILE__,__LINE__);
00064
00065 #define _USE_DEBUG_ 1
00066 #define LIGHT_OFF 0
00067 #define LIGHT_ON 1
00068 #define SPEED_STOP 0
00069 #define SPEED_MOVE_SLOW 0.1
00070 #define DIRECTION_IN_FRONT 0
00071
00072
00073
00074 #define _SAFE_ZONE_X_MAX_ 4
00075 #define _SAFE_ZONE_X_MIN_ 3.5
00076 #define _SAFE_ZONE_Y_MAX_ 0.5
00077 #define _SAFE_ZONE_Y_MIN_ -0.5
00078 #define _SEARCH_X_ 6
00079 #define _SEARCH_Y_ 0
00080 #define _SEARCH_RADIUS_ 0.3
00081
00082
00083
00084
00085
00086
00087
00088
00089
00090
00091 typedef struct
00092 {
00093 double x;
00094 double y;
00095 double radius;
00096 }t_search_area;
00097
00098 typedef struct
00099 {
00100 double xmin,xmax;
00101 double ymin,ymax;
00102
00103 }t_safety_zone;
00104
00105 typedef struct
00106 {
00107 pcl::PointCloud<pcl::PointXYZ> position;
00108 pcl::PointCloud<pcl::PointXYZ> velocity;
00109 std::vector<int> id;
00110 }t_targets;
00111
00112 typedef enum {SEARCHING,TRACKING, TRACKING_NOT_SAFE,TARGET_LOST,INITIALISE}enum_state;
00113
00114 typedef enum
00115 {
00116 SEARCHING_2_TRACKING=88,
00117 SEARCHING_2_TRACKING_NOT_SAFE,
00118 TRACKING_2_TARGET_LOST,
00119 TRACKING_2_TRACKING_NOT_SAFE,
00120 TRACKING_NOT_SAFE_2_TRACKING,
00121 TRACKING_NOT_SAFE_2_TARGET_LOST,
00122 NONE
00123 }t_transitions;
00124
00125 typedef struct
00126 {
00127 enum_state state;
00128 enum_state previous_state;
00129 int target_id;
00130 double current_angle,current_distance;
00131 double current_x,current_y,current_z;
00132 geometry_msgs::Quaternion current_q;
00133
00134 bool target_found;
00135 int last_id;
00136
00137 bool CONTROL_CAR_SPEED;
00138
00139 double direction;
00140 ros::Time tic_tracking_not_safe;
00141 ros::Time tic_searching;
00142 ros::Time tic_tracking;
00143 ros::Time tic_last_sound;
00144 ros::Time tic_last_itsnotsafe;
00145 bool reset_tracking;
00146 }t_status;
00147
00148
00149 void state_machine(void);
00150 void foveationcontrol_sweeping(void);
00151 bool is_safe_using_lasers(void);
00152 void sleepok(int t, ros::NodeHandle &nh);
00153 void play_sound(int sit, int mandatory, double num_h=5);
00154 void print_status(t_status* status);
00155 bool check_safety_zone(t_targets* targets, t_safety_zone* safety_zone);
00156 void mtt_targets_cb (const mtt::TargetListPC& targetlist);
00157 void add_to_viz_markers_vec(std::vector<visualization_msgs::Marker>* marker_vec);
00158 bool search_for_new_target(t_targets* targets, t_status* status, t_search_area* area);
00159 bool get_new_target_information(t_targets *targets, t_status* status);
00160 void init_search_area(t_search_area* area);
00161 void foveationcontrol(t_status* status);
00162 void foveationcontrol_home(void);
00163 void set_high_command_msg_direction_speed(atlascar_base::AtlascarCommand& msg, double dir, double speed);
00164 void set_high_command_msg_lights(atlascar_base::AtlascarCommand& msg, bool high, bool medium, bool left, bool right, bool warning);
00165
00166
00167 #ifdef _FOLLOW_PEDESTRIAN_CPP_
00168
00169 ros::NodeHandle* p_n;
00170 tf::TransformListener *p_listener;
00171 t_search_area search_area;
00172 t_safety_zone safety_zone;
00173 t_targets targets;
00174 t_status status;
00175 sound_play::SoundClient* p_sc;
00176 ros::Publisher* p_pub_fctlr;
00177 double a_h = drand48();
00178 bool FLAG_LASER_SAFE_TO_DRIVE=0;
00179
00180 atlascar_base::AtlascarCommand command_msg;
00181 ros::Publisher command_pub;
00182
00183 #else
00184
00185 extern ros::NodeHandle* p_n;
00186 extern tf::TransformListener *p_listener;
00187 extern t_search_area search_area;
00188 extern t_safety_zone safety_zone;
00189 extern t_targets targets;
00190 extern t_status status;
00191 extern sound_play::SoundClient* p_sc;
00192 extern ros::Publisher* p_pub_fctlr;
00193 extern double a_h;
00194 extern bool FLAG_LASER_SAFE_TO_DRIVE;
00195
00196 extern atlascar_base::AtlascarCommand command_msg;
00197 extern ros::Publisher command_pub;
00198
00199
00200 #endif
00201
00202 #endif