opendrive_planner.cpp 9.53 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>
Sergi Hernandez's avatar
Sergi Hernandez committed
43
44
45
46
47
48
49
50
51
52
53
54
55
56
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
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
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

#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() :
  costmap_(NULL), initialized_(false) {
}

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;
      private_nh.param("opendrive_file", opendrive_file,std::string(""));
      if(opendrive_file!="")
        this->roadmap.load(opendrive_file);
    }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);

    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");
}

void OpendriveGlobalPlanner::reconfigureCB(iri_opendrive_global_planner::OpendriveGlobalPlannerConfig& new_config, uint32_t level) 
{
  try{
    if(new_config.opendrive_file!=this->config.opendrive_file)
      this->roadmap.load(new_config.opendrive_file);
    this->config=new_config;
  }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) 
{
165
  double yaw;
Sergi Hernandez's avatar
Sergi Hernandez committed
166
  std::vector<unsigned int> path;
167
168
  std::vector<double> x,y,heading;
  TPoint real_goal;
Sergi Hernandez's avatar
Sergi Hernandez committed
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215

  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;
  }

/*
  double wx = start.pose.position.x;
  double wy = start.pose.position.y;

  unsigned int start_x_i, start_y_i, goal_x_i, goal_y_i;
  double start_x, start_y, goal_x, goal_y;

  if (!costmap_->worldToMap(wx, wy, start_x_i, start_y_i)) 
  {
    ROS_WARN("The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?");
    return false;
  }
  worldToMap(wx, wy, start_x, start_y);

  //clear the starting cell within the costmap because we know it can't be an obstacle
  clearRobotCell(start, start_x_i, start_y_i);

  int nx = costmap_->getSizeInCellsX(), ny = costmap_->getSizeInCellsY();
*/
  try{
    ROS_WARN("Make Plan");
216
    yaw=tf2::getYaw(start.pose.orientation);
Sergi Hernandez's avatar
Sergi Hernandez committed
217
    this->roadmap.set_start_point(start.pose.position.x,start.pose.position.y,yaw);
218
219
    yaw=tf2::getYaw(goal.pose.orientation);
    real_goal=this->roadmap.set_target_point(goal.pose.position.x,goal.pose.position.y,yaw);
Sergi Hernandez's avatar
Sergi Hernandez committed
220
221
    this->roadmap.find_shortest_path();
    this->roadmap.get_path(path);
222
223
224
225
//    for(unsigned int i=0;i<path.size();i++)
//      std::cout << path[i] << ",";
//    std::cout << std::endl;
    this->roadmap.get_trajectory(x,y,heading);
Sergi Hernandez's avatar
Sergi Hernandez committed
226
227
228
229
230
231
232
233
234
    plan.resize(x.size());
    ros::Time plan_time=ros::Time::now();
    for(unsigned int i=0;i<x.size();i++)
    {
      plan[i].header.frame_id=frame_id_;
      plan[i].header.stamp=plan_time;
      plan[i].pose.position.x=x[i];
      plan[i].pose.position.y=y[i];
      plan[i].pose.position.y=y[i];
235
236
237
      tf2::Quaternion orientation;
      orientation.setRPY(0.0,0.0,heading[i]);
      plan[i].pose.orientation=tf2::toMsg(orientation);
Sergi Hernandez's avatar
Sergi Hernandez committed
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
264
265
266
267
268
269
270
271
272
273
274
    }
  }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