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
00027 #include "ros/ros.h"
00028 #include "ar_human_proc.h"
00029
00030
00031 #define DEG2RAD 0.01745
00032
00033
00034
00035
00036
00037
00038 ar_pose_reader::ar_pose_reader(std_msgs::String topic_name,ros::NodeHandle* n)
00039 {
00040 local_n=n;
00041 name.data.assign(topic_name.data);
00042 }
00043
00044 void ar_pose_reader::init()
00045 {
00046
00047
00048
00049
00050
00051
00052
00053
00054 ar_pose_sub = local_n->subscribe(name.data.c_str(), 15, &ar_pose_reader::ar_pose_callback,this);
00055
00056 for(int i = 0; i < list_size; i++){
00057
00058 markers_list[i].ghmm_wrapper.type = 0;
00059 }
00060
00061 }
00062
00063 void ar_pose_reader::ar_pose_callback(const ar_pose::ARMarkers::ConstPtr& markers)
00064 {
00065
00066 num_markers = markers->markers.size();
00067
00068
00069
00070
00071 for(int i=0; i< num_markers; i++){
00072
00073
00074 source_pose.header = markers->markers[i].header;
00075 source_pose.pose = markers->markers[i].pose.pose;
00076 marker_id = markers->markers[i].id;
00077 int confidence = markers->markers[i].confidence;
00078
00079
00080 try{
00081
00082
00083
00084 listener.transformPose("/map",source_pose,target_pose);
00085 }
00086 catch (tf::TransformException ex) {
00087 ROS_ERROR("%s", ex.what());
00088 return;
00089 }
00090
00091
00092
00093
00094 if(confidence > 60){
00095
00096
00097
00098
00099
00100
00101
00102
00103
00104
00105
00106
00107 manage_list(marker_id);
00108
00109
00110 double distance = euclidean_dist(
00111 markers_list[marker_id].ghmm_wrapper.pose.x,
00112 markers_list[marker_id].ghmm_wrapper.pose.y,
00113 target_pose.pose.position.x,
00114 target_pose.pose.position.y);
00115
00116 if(markers_list[marker_id].ghmm_wrapper.type == 0 && distance > 5.0){
00117 ROS_INFO("distance:%f",distance);
00118
00119
00120 }
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130 markers_list[marker_id].ghmm_wrapper.object_id = marker_id;
00131
00132 markers_list[marker_id].ghmm_wrapper.header.frame_id = target_pose.header.frame_id;
00133 markers_list[marker_id].ghmm_wrapper.header.stamp = target_pose.header.stamp;
00134 markers_list[marker_id].ghmm_wrapper.pose.x = target_pose.pose.position.x;
00135 markers_list[marker_id].ghmm_wrapper.pose.y = target_pose.pose.position.y;
00136 markers_list[marker_id].ghmm_wrapper.pose.theta = tf::getYaw(target_pose.pose.orientation);
00137
00138 ROS_INFO("id:%d,type:%d",markers_list[marker_id].ghmm_wrapper.object_id,
00139 markers_list[marker_id].ghmm_wrapper.type);
00140
00142 trajectory_pub.publish(markers_list[marker_id].ghmm_wrapper);
00143
00144 } else {
00145 ROS_INFO("confidence too low:%d",confidence);
00146 }
00147 }
00148
00149 }
00150
00151 void manage_list(int marker_id){
00152 markers_list[marker_id].detect_time = ros::Time::now();
00153 if(markers_list[marker_id].ghmm_wrapper.type == 2){
00154 markers_list[marker_id].ghmm_wrapper.type = 1;
00155 ROS_INFO("MARKER %d DETECTED",marker_id);
00156 }
00157 else if(markers_list[marker_id].ghmm_wrapper.type == 1){
00158 markers_list[marker_id].ghmm_wrapper.type = 0;
00159 }
00160 }
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173 ar_humanProc::ar_humanProc()
00174 {
00175
00176 pose_pub = n.advertise<social_filter::humanPoses>("human_poses", 15);
00177
00178
00179 trajectory_pub = n.advertise<trajectory_simulator::TrajectoryObservation>("dynamic_objects", 15);
00180 }
00181
00182 void ar_humanProc::init()
00183 {
00184
00185 std_msgs::String msg;
00186 std::stringstream ss;
00187 ss<<"/ar_pose_marker";
00188 msg.data = ss.str();
00189
00190
00191 ar_pose_reader* reader_ptr = new ar_pose_reader(msg, &n);
00192 reader_ptr->init();
00193 readers.push_back(reader_ptr);
00194 }
00195
00196
00197 void ar_humanProc::pub()
00198 {
00199
00200 }
00201
00202
00203 ar_humanProc::~ar_humanProc()
00204 {
00205
00206
00207 }
00208
00209
00210 int main(int argc, char **argv)
00211 {
00212 ros::init(argc, argv, "ar_human_processes");
00213 ar_humanProc h_processor;
00214 h_processor.init();
00215 ros::Rate loop_rate(10);
00216
00217 while (ros::ok())
00218 {
00219 h_processor.pub();
00220 ros::spinOnce();
00221 loop_rate.sleep();
00222
00223
00224 for(int i = 0; i < list_size; i++){
00225 duration_since_detection = ros::Time::now() - markers_list[i].detect_time;
00226
00227
00228
00229
00230 if (duration_since_detection.toSec() > 1.0 && markers_list[i].ghmm_wrapper.type != 2){
00231
00232 markers_list[i].ghmm_wrapper.type = 2;
00233 ROS_INFO("MARKER %d DISAPPEARED",i);
00234
00235
00236 ROS_INFO("id:%d,type:%d",markers_list[i].ghmm_wrapper.object_id,
00237 markers_list[i].ghmm_wrapper.type);
00238
00240 trajectory_pub.publish(markers_list[i].ghmm_wrapper);
00241 }
00242 }
00243 }
00244
00245 return 0;
00246 }
00247