opendrive_planner.cpp 16.8 KB
Newer Older
Sergi Hernandez's avatar
Sergi Hernandez committed
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
/*********************************************************************
 *
 * Software License Agreement (BSD License)
 *
 *  Copyright (c) 2008, 2013, Willow Garage, Inc.
 *  All rights reserved.
 *
 *  Redistribution and use in source and binary forms, with or without
 *  modification, are permitted provided that the following conditions
 *  are met:
 *
 *   * Redistributions of source code must retain the above copyright
 *     notice, this list of conditions and the following disclaimer.
 *   * Redistributions in binary form must reproduce the above
 *     copyright notice, this list of conditions and the following
 *     disclaimer in the documentation and/or other materials provided
 *     with the distribution.
 *   * Neither the name of Willow Garage, Inc. nor the names of its
 *     contributors may be used to endorse or promote products derived
 *     from this software without specific prior written permission.
 *
 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 *  POSSIBILITY OF SUCH DAMAGE.
 *
 * Author: Eitan Marder-Eppstein
 *         David V. Lu!!
 *********************************************************************/
#include <iri_opendrive_global_planner/opendrive_planner.h>
#include <pluginlib/class_list_macros.h>
#include <costmap_2d/cost_values.h>
#include <costmap_2d/costmap_2d.h>
42
#include <tf2/utils.h>
43
#include <limits>
Sergi Hernandez's avatar
Sergi Hernandez committed
44
45
46
47
48
49
50
51
52

#include "exceptions.h"

//register this planner as a BaseOpendriveGlobalPlanner plugin
PLUGINLIB_EXPORT_CLASS(iri_opendrive_global_planner::OpendriveGlobalPlanner, nav_core::BaseGlobalPlanner)

namespace iri_opendrive_global_planner {

OpendriveGlobalPlanner::OpendriveGlobalPlanner() :
53
  costmap_(NULL), initialized_(false), tf2_listener(tf2_buffer) {
54
55
56
  this->angle_tol=DEFAULT_ANGLE_THRESHOLD;
  this->dist_tol=DEFAULT_DIST_THRESHOLD;
  this->multi_hyp=false;
Sergi Hernandez's avatar
Sergi Hernandez committed
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
}

OpendriveGlobalPlanner::OpendriveGlobalPlanner(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id) :
  OpendriveGlobalPlanner() 
{
  //initialize the planner
  initialize(name, costmap, frame_id);
}

OpendriveGlobalPlanner::~OpendriveGlobalPlanner() 
{
  if (dsrv_)
    delete dsrv_;
}

void OpendriveGlobalPlanner::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros) 
{
  initialize(name, costmap_ros->getCostmap(), costmap_ros->getGlobalFrameID());
}

void OpendriveGlobalPlanner::initialize(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id) 
{
  if (!initialized_) 
  {
    ros::NodeHandle private_nh("~/" + name);
    costmap_ = costmap;
    frame_id_ = frame_id;

    try{
      std::string opendrive_file;
87
      double resolution,scale_factor,min_road_length;
88
89
      int cost_type;

90
91
92
93
94
95
      private_nh.param("resolution", resolution,0.0);
      this->roadmap.set_resolution(resolution);
      private_nh.param("scale_factor", scale_factor,0.0);
      this->roadmap.set_scale_factor(scale_factor);
      private_nh.param("min_road_length", min_road_length,0.0);
      this->roadmap.set_min_road_length(min_road_length);
Sergi Hernandez's avatar
Sergi Hernandez committed
96
97
      private_nh.param("opendrive_file", opendrive_file,std::string(""));
      if(opendrive_file!="")
98
      {
Sergi Hernandez's avatar
Sergi Hernandez committed
99
        this->roadmap.load(opendrive_file);
100
101
        this->create_opendrive_map(opendrive_file,resolution,scale_factor,min_road_length);
      }
102
      private_nh.param("opendrive_frame", this->opendrive_frame_id_,std::string(""));
103
104
105
106
107
      private_nh.param("angle_tol", this->angle_tol,DEFAULT_ANGLE_THRESHOLD);
      private_nh.param("dist_tol", this->dist_tol,DEFAULT_DIST_THRESHOLD);
      private_nh.param("multi_hyp", this->multi_hyp,false);
      private_nh.param("cost_type",cost_type,(int)COST_DIST);
      this->roadmap.set_cost_type((cost_t)cost_type);
Sergi Hernandez's avatar
Sergi Hernandez committed
108
109
110
111
112
113
114
    }catch(CException &e){
      ROS_ERROR_STREAM(e.what());
    }

    plan_pub_ = private_nh.advertise<nav_msgs::Path>("plan", 1);
    make_plan_srv_ = private_nh.advertiseService("make_plan", &OpendriveGlobalPlanner::makePlanService, this);

115
116
117
118
    this->opendrive_map_pub_ = private_nh.advertise<nav_msgs::OccupancyGrid>("opendrive_map", 1,boost::bind(&OpendriveGlobalPlanner::map_connect_callback, this, _1));

    this->opendrive_map_service=private_nh.advertiseService("get_opendrive_map", &OpendriveGlobalPlanner::get_opendrive_map,this);

Sergi Hernandez's avatar
Sergi Hernandez committed
119
120
121
122
123
124
125
126
127
    dsrv_ = new dynamic_reconfigure::Server<iri_opendrive_global_planner::OpendriveGlobalPlannerConfig>(ros::NodeHandle("~/" + name));
    dynamic_reconfigure::Server<iri_opendrive_global_planner::OpendriveGlobalPlannerConfig>::CallbackType cb = boost::bind(&OpendriveGlobalPlanner::reconfigureCB, this, _1, _2);
    dsrv_->setCallback(cb);

    initialized_ = true;
  } else
    ROS_WARN("This planner has already been initialized, you can't call it twice, doing nothing");
}

128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
void OpendriveGlobalPlanner::map_connect_callback(const ros::SingleSubscriberPublisher &subs)
{
  subs.publish(this->full_path_);
}

void OpendriveGlobalPlanner::create_opendrive_map(std::string &filename,double resolution,double scale_factor,double min_road_length)
{
  std::vector<double> x,partial_x,y,partial_y;
  double max_x=std::numeric_limits<double>::min(),min_x=std::numeric_limits<double>::max(),max_y=std::numeric_limits<double>::min(),min_y=std::numeric_limits<double>::max();
  COpendriveRoad road;

  road.load(filename);
  road.set_resolution(resolution);
  road.set_scale_factor(scale_factor);
  road.set_min_road_length(min_road_length);
  this->full_path_.header.frame_id = this->opendrive_frame_id_;
  this->full_path_.header.stamp = ros::Time::now();
  this->full_path_.info.map_load_time = ros::Time::now();
  this->full_path_.info.resolution = resolution;
  for(unsigned int i=0;i<road.get_num_nodes();i++)
  {
    const COpendriveRoadNode &node=road.get_node(i);
    for(unsigned int j=0;j<node.get_num_links();j++)
    {
      const COpendriveLink &link=node.get_link(j);
      link.get_trajectory(partial_x,partial_y);
      x.insert(x.end(),partial_x.begin(),partial_x.end());
      y.insert(y.end(),partial_y.begin(),partial_y.end());
      for(unsigned int k=0;k<partial_x.size();k++)
      {
        if(partial_x[k]>max_x)
          max_x=partial_x[k];
        else if(partial_x[k]<min_x)
          min_x=partial_x[k];
        if(partial_y[k]>max_y)
          max_y=partial_y[k];
        else if(partial_y[k]<min_y)
          min_y=partial_y[k];
      }
    }
  }
  this->full_path_.info.width=(max_x-min_x)/resolution;
  this->full_path_.info.height=(max_y-min_y)/resolution;
  this->full_path_.info.origin.position.x=min_x;
  this->full_path_.info.origin.position.y=min_y;
  this->full_path_.info.origin.position.z=0.0;
  this->full_path_.info.origin.orientation.x=0.0;
  this->full_path_.info.origin.orientation.y=0.0;
  this->full_path_.info.origin.orientation.z=0.0;
  this->full_path_.info.origin.orientation.w=1.0;
  this->full_path_.data.resize(this->full_path_.info.width*this->full_path_.info.height,255);
  for(unsigned int i=0;i<x.size();i++)
    this->full_path_.data[this->full_path_.info.width*((unsigned int)((y[i]-min_y)/resolution))+((unsigned int)((x[i]-min_x)/resolution))]=0;
}

bool OpendriveGlobalPlanner::get_opendrive_map(iri_adc_msgs::get_opendrive_map::Request  &req,iri_adc_msgs::get_opendrive_map::Response &res)
{
  res.opendrive_map=this->full_path_;

  return true;
}

Sergi Hernandez's avatar
Sergi Hernandez committed
190
191
192
void OpendriveGlobalPlanner::reconfigureCB(iri_opendrive_global_planner::OpendriveGlobalPlannerConfig& new_config, uint32_t level) 
{
  try{
193
194
195
    this->roadmap.set_resolution(new_config.resolution);
    this->roadmap.set_scale_factor(new_config.scale_factor);
    this->roadmap.set_min_road_length(new_config.min_road_length);
196
    this->opendrive_frame_id_=new_config.opendrive_frame;
197
198
199
    this->angle_tol=new_config.angle_tol;
    this->dist_tol=new_config.dist_tol;
    this->multi_hyp=new_config.multi_hyp;
200
201
202
203
204
    if(new_config.opendrive_file!=this->config.opendrive_file || new_config.scale_factor!=this->config.scale_factor || new_config.min_road_length!=this->config.min_road_length)
    {
      this->roadmap.load(new_config.opendrive_file);
      this->create_opendrive_map(new_config.opendrive_file,new_config.resolution,new_config.scale_factor,new_config.min_road_length);
    } 
205
    this->roadmap.set_cost_type((cost_t)new_config.cost_type);
206
    this->config=new_config;
Sergi Hernandez's avatar
Sergi Hernandez committed
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
  }catch(CException &e){
    ROS_ERROR_STREAM(e.what());
  }
}

void OpendriveGlobalPlanner::clearRobotCell(const geometry_msgs::PoseStamped& global_pose, unsigned int mx, unsigned int my) 
{
  if (!initialized_) 
  {
    ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
    return;
  }

  //set the associated costs in the cost map to be free
  costmap_->setCost(mx, my, costmap_2d::FREE_SPACE);
}

bool OpendriveGlobalPlanner::makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp) 
{
  makePlan(req.start, req.goal, resp.plan.poses);

  resp.plan.header.stamp = ros::Time::now();
  resp.plan.header.frame_id = frame_id_;

  return true;
}

void OpendriveGlobalPlanner::mapToWorld(double mx, double my, double& wx, double& wy) 
{
  wx = costmap_->getOriginX() + mx * costmap_->getResolution();
  wy = costmap_->getOriginY() + my * costmap_->getResolution();
}

bool OpendriveGlobalPlanner::worldToMap(double wx, double wy, double& mx, double& my) 
{
  double origin_x = costmap_->getOriginX(), origin_y = costmap_->getOriginY();
  double resolution = costmap_->getResolution();

  if (wx < origin_x || wy < origin_y)
    return false;

  mx = (wx - origin_x) / resolution;
  my = (wy - origin_y) / resolution;

  if (mx < costmap_->getSizeInCellsX() && my < costmap_->getSizeInCellsY())
    return true;

  return false;
}

bool OpendriveGlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,std::vector<geometry_msgs::PoseStamped>& plan) 
{
  return makePlan(start, goal, 0.0, plan);
}

bool OpendriveGlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,double tolerance, std::vector<geometry_msgs::PoseStamped>& plan) 
{
264
  double yaw,best_cost;
265
  unsigned int best_path_index;
266
  std::vector<unsigned int> best_path;
267
  std::vector<double> x,y,heading;
268
269
270
  std::vector< std::vector<unsigned int> > paths;
  std::vector<double> costs;
  std::vector<TMapPose> start_candidates,end_candidates;
271
272
273
274
275
276
  geometry_msgs::PoseStamped start_out,goal_out,point;
  std::string target_frame;
  std::string source_frame;
  ros::Time time;
  ros::Duration timeout;
  geometry_msgs::TransformStamped transform;
Sergi Hernandez's avatar
Sergi Hernandez committed
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302

  boost::mutex::scoped_lock lock(mutex_);
  if (!initialized_) {
    ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
    return false;
  }

  //clear the plan, just in case
  plan.clear();

  ros::NodeHandle n;
  std::string global_frame = frame_id_;

  //until tf can handle transforming things that are way in the past... we'll require the goal to be in our global frame
  if (goal.header.frame_id != global_frame) 
  {
    ROS_ERROR("The goal pose passed to this planner must be in the %s frame.  It is instead in the %s frame.", global_frame.c_str(), goal.header.frame_id.c_str());
    return false;
  }

  if (start.header.frame_id != global_frame) 
  {
    ROS_ERROR("The start pose passed to this planner must be in the %s frame.  It is instead in the %s frame.", global_frame.c_str(), start.header.frame_id.c_str());
    return false;
  }

303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
  /* transform start and end positions to map opendrive */
  try{
    target_frame = this->opendrive_frame_id_;
    source_frame = start.header.frame_id;
    time = ros::Time(0);
    timeout = ros::Duration(0.1);
    if(this->tf2_buffer.canTransform(target_frame, source_frame, time, timeout))
    {
      transform = this->tf2_buffer.lookupTransform(target_frame, source_frame, time);
      tf2::doTransform(start,start_out, transform);
    }else{
      ROS_WARN("No transform found for start point from '%s' to '%s'", source_frame.c_str(), target_frame.c_str());
    }
    source_frame = goal.header.frame_id;
    if(this->tf2_buffer.canTransform(target_frame, source_frame, time, timeout))
    {
      transform = this->tf2_buffer.lookupTransform(target_frame, source_frame, time);
      tf2::doTransform(goal,goal_out, transform);
    }else{
      ROS_WARN("No transform found for end point from '%s' to '%s'", source_frame.c_str(), target_frame.c_str());
    }
  }catch (tf2::TransformException &ex){
    ROS_ERROR("TF2 Exception: %s",ex.what()); 
Sergi Hernandez's avatar
Sergi Hernandez committed
326
327
328
329
  }

  try{
    ROS_WARN("Make Plan");
330
331
    yaw=tf2::getYaw(start_out.pose.orientation);
    this->roadmap.set_start_pose(start_out.pose.position.x,start_out.pose.position.y,yaw,this->dist_tol,this->angle_tol);
332
333
334
335
336
337
338
    this->roadmap.get_start_pose_candidates(start_candidates);
    std::cout << "Start pose candidates: " << std::endl;
    for(unsigned int i=0;i<start_candidates.size();i++)
    {
      std::cout << i << ". x: " << start_candidates[i].pose.x << ", y:" << start_candidates[i].pose.y << ", heading: " << start_candidates[i].pose.heading << std::endl;
      std::cout << "   distance from desired pose: " << start_candidates[i].dist << std::endl;
    }
339
340
    yaw=tf2::getYaw(goal_out.pose.orientation);
    this->roadmap.set_end_pose(goal_out.pose.position.x,goal_out.pose.position.y,yaw,this->dist_tol,this->angle_tol);
341
342
343
344
345
346
347
    this->roadmap.get_end_pose_candidates(end_candidates);
    std::cout << "End pose candidates: " << std::endl;
    for(unsigned int i=0;i<end_candidates.size();i++)
    {
      std::cout << i << ". x: " << end_candidates[i].pose.x << ", y:" << end_candidates[i].pose.y << ", heading: " << end_candidates[i].pose.heading << std::endl;
      std::cout << "   distance from desired pose: " << end_candidates[i].dist << std::endl;
    }
348
    this->roadmap.find_shortest_path(this->multi_hyp);
349
350
351
352
353
354
355
356
357
    this->roadmap.get_paths(costs,paths);
    for(unsigned int i=0;i<paths.size();i++)
    {
      std::cout << "path " << i << ":" << std::endl;
      for(unsigned int j=0;j<paths[i].size();j++)
        std::cout << paths[i][j] << ",";
      std::cout << std::endl;
    }
    best_path_index=this->roadmap.get_best_path(best_cost,best_path);
358
359
    if(best_path_index==-1)
      return false;
360
361
362
363
    std::cout << "best path index: " << best_path_index << std::endl;
    for(unsigned int i=0;i<best_path.size();i++)
      std::cout << best_path[i] << ",";
    std::cout << std::endl;
364
    this->roadmap.get_trajectory(best_path_index,x,y,heading);
Sergi Hernandez's avatar
Sergi Hernandez committed
365
    plan.resize(x.size());
366
367
368
369
370
371
372
373
    try{
      target_frame = this->frame_id_;
      source_frame = this->opendrive_frame_id_;
      time = ros::Time(0);
      timeout = ros::Duration(0.1);
      if(this->tf2_buffer.canTransform(target_frame, source_frame, time, timeout))
      {
        transform = this->tf2_buffer.lookupTransform(target_frame, source_frame, time);
374
        point.header.frame_id=this->frame_id_;
375
376
377
378
379
380
381
382
383
384
        point.header.stamp=time;
        for(unsigned int i=0;i<x.size();i++)
        {
          point.pose.position.x=x[i];
          point.pose.position.y=y[i];
          point.pose.position.z=0.0;
          tf2::Quaternion orientation;
          orientation.setRPY(0.0,0.0,heading[i]);
          point.pose.orientation=tf2::toMsg(orientation);
          tf2::doTransform(point,plan[i],transform);
385
          plan[i].header.frame_id=this->frame_id_;
386
387
388
389
390
391
392
          plan[i].header.stamp=time;
        }
      }else{
        ROS_WARN("No transform found for path points from '%s' to '%s'", source_frame.c_str(), target_frame.c_str());
      }
    }catch (tf2::TransformException &ex){
      ROS_ERROR("TF2 Exception: %s",ex.what()); 
Sergi Hernandez's avatar
Sergi Hernandez committed
393
    }
394

Sergi Hernandez's avatar
Sergi Hernandez committed
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
  }catch(CException &e){
    ROS_ERROR_STREAM(e.what());
    return false;
  }
  //make sure to resize the underlying array that Navfn uses

  //publish the plan for visualization purposes
  publishPlan(plan);
  return !plan.empty();
}

void OpendriveGlobalPlanner::publishPlan(const std::vector<geometry_msgs::PoseStamped>& path) 
{
  if (!initialized_) 
  {
    ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
    return;
  }

  //create a message for the plan
  nav_msgs::Path gui_path;
  gui_path.poses.resize(path.size());

  gui_path.header.frame_id = frame_id_;
  gui_path.header.stamp = ros::Time::now();

  // Extract the plan in world co-ordinates, we assume the path is all in the same frame
  for (unsigned int i = 0; i < path.size(); i++) 
  {
    gui_path.poses[i] = path[i];
  }

  plan_pub_.publish(gui_path);
}

} //end namespace iri_opendrive_global_planner