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 #ifndef _trajectory_planner_nodelet_CPP_
00028 #define _trajectory_planner_nodelet_CPP_
00029
00036 #include "trajectory_planner_nodelet.h"
00037
00038 bool plan_trajectory=false;
00039 bool have_plan=false;
00040 geometry_msgs::PoseStamped pose_in;
00041 geometry_msgs::PoseStamped pose_transformed;
00042
00043 std::vector< pcl::PointCloud<pcl::PointXYZ> > pc_v;
00044
00045
00051 void set_coordinates(trajectory_planner::coordinates msg)
00052 {
00053
00054
00055
00056 pose_in.pose.position.x=msg.x;
00057 pose_in.pose.position.y=msg.y;
00058 pose_in.pose.orientation.w=cos(msg.theta/2.0);
00059 pose_in.pose.orientation.x=0.0;
00060 pose_in.pose.orientation.y=0.0;
00061 pose_in.pose.orientation.z=sin(msg.theta/2.0);
00062
00063 pose_in.header.frame_id="/world";
00064
00065 manage_vt->set_attractor_point(msg.x,msg.y,msg.theta);
00066 plan_trajectory=true;
00067 }
00068
00069
00075 void mtt_callback(mtt::TargetListPC msg)
00076 {
00077 ROS_INFO("received mtt num obs=%ld num lines first obs =%d frame_id=%s",msg.id.size(), msg.obstacle_lines[0].width, msg.header.frame_id.c_str());
00078
00079
00080 pc_v.erase(pc_v.begin(), pc_v.end());
00081 for (size_t i=0; i<msg.id.size(); ++i)
00082 {
00083 pcl::PointCloud<pcl::PointXYZ> tmp;
00084 pcl::fromROSMsg(msg.obstacle_lines[i], tmp);
00085 tmp.header.frame_id=msg.header.frame_id;
00086 tmp.header.stamp=msg.header.stamp;
00087
00088 ROS_INFO("Obstacle %ld has %ld lines", i, tmp.points.size());
00089 pc_v.push_back(tmp);
00090 }
00091 }
00092
00093
00099 vector<double> set_speed_vector(boost::shared_ptr<c_trajectory> t)
00100 {
00101 vector<double> speed_setted;
00102 for(size_t i=0;i<_NUM_NODES_;++i)
00103 {
00104 if(i < (_NUM_NODES_ - 1))
00105 {
00106 if((t->arc[i])*(t->arc[i+1])<0.0)
00107 {
00108 speed_setted.push_back((t->arc[i]/fabs(t->arc[i]))*_SPEED_SAFFETY_);
00109 }
00110 else
00111 {
00112 speed_setted.push_back((t->arc[i]/fabs(t->arc[i]))*_SPEED_REQUIRED_);
00113 }
00114 }
00115 else
00116 {
00117 speed_setted.push_back((t->arc[i]/fabs(t->arc[i]))*_SPEED_REQUIRED_);
00118 }
00119
00120 }
00121 return speed_setted;
00122 }
00123
00124
00132 int main(int argc, char **argv)
00133 {
00134 ros::init(argc, argv, "trajectory_planner_nodelet");
00135 ros::NodeHandle n("~");
00136 p_n=&n;
00137
00138
00139 tf::TransformBroadcaster broadcaster;
00140 tf::TransformListener listener;
00141 p_listener = &listener;
00142 ros::Publisher array_pub = n.advertise<visualization_msgs::MarkerArray>( "/array_of_markers", 1 );
00143 ros::Subscriber sub = n.subscribe("/msg_coordinates", 1, set_coordinates);
00144 ros::Subscriber mtt_sub = n.subscribe("/mtt_targets", 1, mtt_callback);
00145 ros::Rate loop_rate(10);
00146
00147
00148
00149
00150
00151
00152 manage_vt = (c_manage_trajectoryPtr) new c_manage_trajectory();
00153
00154
00155 t_desired_coordinates AP;
00156 AP.x=-1.0;
00157 AP.y=0.0;
00158 AP.theta=-M_PI/8;
00159 manage_vt->set_attractor_point(AP.x, AP.y, AP.theta);
00160
00161
00162
00163 manage_vt->set_vehicle_description(_VEHICLE_WIDTH_, _VEHICLE_LENGHT_BACK_, _VEHICLE_LENGHT_FRONT_,
00164 _VEHICLE_HEIGHT_TOP_, _VEHICLE_HEIGHT_BOTTOM_);
00165
00166
00167 manage_vt->set_inter_axis_distance(_D_);
00168
00169
00170
00171 for (int i=0; i< _NUM_TRAJ_; i++)
00172 {
00173 vector<double> v_a;
00174 vector<double> v_arc;
00175 for (int j=0; j<_NUM_NODES_; ++j)
00176 {
00177 v_a.push_back(M_PI/180.*a[i][j]);
00178 v_arc.push_back(arc[i][j]);
00179 }
00180 manage_vt->create_new_trajectory(v_a,v_arc,v_a);
00181 }
00182
00183
00184 int val = 0;
00185
00186 if (val>=(int)manage_vt->vt.size())
00187 {
00188 ROS_ERROR("Chosen trajectory does not exist");
00189 exit(0);
00190 }
00191 manage_vt->set_chosen_traj(val);
00192
00193
00194
00195 commandPublisher = n.advertise<trajectory_planner::traj_info>("/trajectory_information", 1000);
00196
00197
00198
00199
00200
00201 while(ros::ok())
00202 {
00203
00204 if(plan_trajectory==true)
00205 {
00206
00207
00208 plan_trajectory = false;
00209 ROS_INFO("Going to plan a trajectory");
00210
00211
00212
00213
00214 bool have_transform=true;
00215
00216 try
00217 {
00218 p_listener->lookupTransform("/world","/vehicle_odometry",ros::Time(0), transformw);
00219 }
00220 catch (tf::TransformException ex)
00221 {
00222 ROS_ERROR("%s",ex.what());
00223 have_transform=false;
00224 }
00225
00226 if (have_transform)
00227 {
00228 ros::Time time=ros::Time::now();
00229 broadcaster.sendTransform(tf::StampedTransform(transformw, time,"/world", "/parking_frame"));
00230 ros::spinOnce();
00231 broadcaster.sendTransform(tf::StampedTransform(transformw, time+ros::Duration(5),"/world", "/parking_frame"));
00232 ros::spinOnce();
00233
00234
00235 ros::Duration(0.1).sleep();
00236
00237
00238
00239
00240
00241
00242
00243 tf::Transformer tt;
00244 pose_in.header.stamp=time+ros::Duration(0.1);
00245 p_listener->transformPose ("/parking_frame", pose_in, pose_transformed);
00246
00247 ROS_INFO("pose_in frame_id=%s pose_transformed frame_id=%s",pose_in.header.frame_id.c_str(), pose_transformed.header.frame_id.c_str());
00248
00249 manage_vt->set_attractor_point(pose_transformed.pose.position.x,pose_transformed.pose.position.y,atan2(2.0*(pose_transformed.pose.orientation.w*pose_transformed.pose.orientation.z),1-(2*(pose_transformed.pose.orientation.z*pose_transformed.pose.orientation.z))));
00250
00251
00252
00253 pcl::PointCloud<pcl::PointXYZ> pct;
00254 mtt::TargetListPC msg_transformed;
00255
00256
00257
00258 for (size_t i=0; i<pc_v.size(); ++i)
00259 {
00260
00261 if (i==0)
00262 {
00263 try
00264 {
00265 p_listener->lookupTransform(pc_v[i].header.frame_id,"/parking_frame", pc_v[i].header.stamp, transform_mtt);
00266 }
00267 catch (tf::TransformException ex)
00268 {
00269 ROS_ERROR("%s",ex.what());
00270 }
00271 }
00272
00273 ROS_INFO("pc_v[%ld] frame_id=%s pcp frame_id=%s",i, pc_v[i].header.frame_id.c_str(), pct.header.frame_id.c_str());
00274 pcl_ros::transformPointCloud(pc_v[i],pct,transform_mtt.inverse());
00275
00276 sensor_msgs::PointCloud2 pc_msg;
00277 pcl::toROSMsg(pct, pc_msg);
00278 pc_msg.header.frame_id = "/parking_frame";
00279 pc_msg.header.stamp = ros::Time::now();
00280 msg_transformed.obstacle_lines.push_back(pc_msg);
00281 }
00282 manage_vt->set_obstacles(msg_transformed);
00283
00284
00285
00286
00287
00288
00289
00290 manage_vt->create_static_markers();
00291
00292
00293 ros::Time st=ros::Time::now();
00294
00295 manage_vt->compute_trajectories_scores();
00296
00297 cout<<"Compute scores: "<<(ros::Time::now()-st).toSec();
00298
00299 ROS_INFO("manage_vt chosen traj= %d",manage_vt->chosen_traj.index);
00300
00301
00302 trajectory_planner::traj_info info;
00303
00304 manage_vt->get_traj_info_msg_from_chosen(&info);
00305
00306 commandPublisher.publish(info);
00307
00308
00309 visualization_msgs::MarkerArray marker_array;
00310 manage_vt->compute_vis_marker_array(&marker_array);
00311 array_pub.publish(marker_array);
00312 cout<<"ja size:"<<marker_array.markers.size()<<endl;
00313
00314
00315 have_plan=true;
00316
00317 }
00318 }
00319
00320 if (have_plan==true)
00321 {
00322
00323
00324 broadcaster.sendTransform(tf::StampedTransform(transformw, ros::Time::now(),"/world", "/parking_frame"));
00325 cout<<"stat Publishing transform"<<endl;
00326 }
00327
00328
00329
00330
00331 loop_rate.sleep();
00332 ros::spinOnce();
00333 }
00334 }
00335 #endif