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
00039 #include "ros/ros.h"
00040 #include "std_msgs/String.h"
00041 #include "geometry_msgs/PoseWithCovariance.h"
00042 #include "tf/transform_listener.h"
00043 #include "mtt/TargetList.h"
00044 #include <visualization_msgs/Marker.h>
00045 #include <visualization_msgs/MarkerArray.h>
00046 #include "opencv/cv.h"
00047 #include "opencv/ml.h"
00048 #include <vector>
00049 #include <iostream>
00050
00051
00052
00053
00054 CvBoost adaboost;
00055 CvMat* sample_to_classify = 0;
00056 CvMat* weak_responses = 0;
00057
00058
00059 ros::Time time_last_msg(0);
00060 ros::Duration time_elapsed;
00061 ros::Duration duration_btw_msg;
00062 ros::Publisher nfeatures_pub;
00063 ros::Publisher marker_pub;
00064
00065 tf::TransformListener *p_listener;
00066 tf::StampedTransform transform;
00067
00068 geometry_msgs::Twist twist;
00069 geometry_msgs::Twist features;
00070 geometry_msgs::PoseWithCovariance nfeatures;
00071 visualization_msgs::MarkerArray ma;
00072
00073 std::list<geometry_msgs::PoseWithCovariance> matlab_list;
00074
00075 double target_x, target_y;
00076 double target_vel, target_theta;
00077 double robot_x, robot_y;
00078 double robot_vel, robot_theta;
00079 double position_diff, heading_diff;
00080 double angle_to_robot;
00081 double velocity_diff;
00082 double lateral_disp;
00083 double label;
00084 uint badLeader = 0;
00085 uint target_id = 0;
00086 uint single_target = 0;
00087 uint counter = 0;
00088
00089 void drawPose(const geometry_msgs::Pose& input, uint target, double classification)
00090 {
00091
00092 visualization_msgs::Marker marker;
00093
00094 marker.header.frame_id = "/map";
00095 marker.header.stamp = ros::Time::now();
00096
00097 marker.ns = "quality";
00098 marker.id = target;
00099
00100 marker.type = visualization_msgs::Marker::CYLINDER;
00101 marker.action = visualization_msgs::Marker::ADD;
00102
00103
00104 marker.pose.position.x = input.position.x;
00105 marker.pose.position.y = input.position.y;
00106 marker.pose.position.z = 0;
00107 marker.pose.orientation.x = 0.0;
00108 marker.pose.orientation.y = 0.0;
00109 marker.pose.orientation.z = 0.0;
00110 marker.pose.orientation.w = 1.0;
00111
00112
00113 marker.scale.x = 0.5;
00114 marker.scale.y = 0.5;
00115 marker.scale.z = 0.5;
00116
00117
00118 if(classification == 1){
00119 marker.color.r = 0.0f;
00120 marker.color.g = 1.0f;
00121 }
00122 else if (classification == 2){
00123 marker.color.r = 1.0f;
00124 marker.color.g = 0.0f;
00125 }
00126
00127 marker.color.b = 0.0f;
00128 marker.color.a = 1.0;
00129
00130 marker.lifetime = ros::Duration(1.0);
00131
00132
00133 ma.markers.push_back(marker);
00134
00135
00136
00137 }
00138
00139 void targetsCallback(const mtt::TargetList& list)
00140 {
00141 static ros::Time start_time = ros::Time::now();
00142 time_elapsed = ros::Time::now() - start_time;
00143 matlab_list.clear();
00144
00146
00147
00148
00149
00150
00151 try{
00152 p_listener->lookupTransform("/map", "/base_link", ros::Time(0), transform);
00153 p_listener->lookupTwist("/map", "/base_link", ros::Time(0), ros::Duration(0.5), twist);
00154 }
00155 catch (tf::TransformException ex){
00156 ROS_ERROR("%s",ex.what());
00157 }
00158
00159 robot_x = transform.getOrigin().x();
00160 robot_y = transform.getOrigin().y();
00161 robot_theta = tf::getYaw(transform.getRotation());
00162 robot_vel = sqrt(pow(twist.linear.x, 2) + pow(twist.linear.y, 2));
00163
00165
00166 for(uint i = 0; i < list.Targets.size(); i++){
00167 target_id = list.Targets[i].id;
00168 target_x = list.Targets[i].pose.position.x;
00169 target_y = list.Targets[i].pose.position.y;
00170 target_theta = tf::getYaw(list.Targets[i].pose.orientation);
00171 target_vel = sqrt(pow(list.Targets[i].velocity.linear.x,2)+
00172 pow(list.Targets[i].velocity.linear.y,2));
00173 position_diff = sqrt(pow(robot_x - target_x,2)+
00174 pow(robot_y - target_y,2));
00175 heading_diff = robot_theta - target_theta;
00176 angle_to_robot = -robot_theta + atan2(target_y - robot_y,
00177 target_x - robot_x );
00178 velocity_diff = robot_vel - target_vel;
00179 lateral_disp = sin(angle_to_robot)*position_diff;
00180
00181
00182
00183 sample_to_classify->data.fl[1] = target_vel;
00184 sample_to_classify->data.fl[2] = lateral_disp;
00185 sample_to_classify->data.fl[3] = heading_diff;
00186 sample_to_classify->data.fl[4] = angle_to_robot;
00187 sample_to_classify->data.fl[5] = position_diff;
00188
00189
00190 label = adaboost.predict(sample_to_classify, 0, weak_responses );
00191
00192 drawPose(list.Targets[i].pose, target_id, label);
00193
00194 }
00195
00196 marker_pub.publish(ma);
00197 ma.markers.clear();
00198 }
00199
00200
00201
00202 int main(int argc, char **argv)
00203 {
00204 ros::init(argc, argv, "process_target");
00205 ros::NodeHandle n;
00206
00207 tf::TransformListener listener;
00208 p_listener=&listener;
00209
00210
00211 std::cout << "loaded file: " << argv[1] << std::endl;
00212 adaboost.load(argv[1]);
00213 sample_to_classify = cvCreateMat( 1, 6, CV_32F );
00214 weak_responses = cvCreateMat( 1, adaboost.get_weak_predictors()->total, CV_32F );
00215
00216 ros::Subscriber sub = n.subscribe("/targets", 1000, targetsCallback);
00217
00218
00219 nfeatures_pub = n.advertise<geometry_msgs::PoseWithCovariance>("/example_topic", 1000);
00220 marker_pub = n.advertise<visualization_msgs::MarkerArray>("/leader_quality", 1000);
00221
00222 ros::spin();
00223
00224 return 0;
00225 }