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
00028
00029 #include <swri_route_util/route_speeds.h>
00030
00031 #include <unordered_map>
00032
00033 #include <swri_geometry_util/geometry_util.h>
00034 #include <swri_roscpp/swri_roscpp.h>
00035 #include <swri_route_util/util.h>
00036
00037 namespace smu = swri_math_util;
00038 namespace stu = swri_transform_util;
00039 namespace mcm = marti_common_msgs;
00040 namespace mnm = marti_nav_msgs;
00041
00042 namespace swri_route_util
00043 {
00044
00045 static void addItem(mcm::KeyValueArray &m, const std::string &key, const std::string &value)
00046 {
00047 m.items.emplace_back();
00048 m.items.back().key = key;
00049 m.items.back().value = value;
00050 }
00051
00052 SpeedForCurvatureParameters::SpeedForCurvatureParameters()
00053 :
00054 use_speed_from_accel_constant_(true),
00055 max_lateral_accel_mss_(0.2),
00056 curvature_filter_size_(20.0)
00057 {
00058 }
00059
00060 void SpeedForCurvatureParameters::loadFromRosParam(const ros::NodeHandle &pnh)
00061 {
00062
00063
00064 swri::param(pnh, "curvature_filter_size", curvature_filter_size_, 20.0);
00065
00066
00067 swri::param(pnh, "lateral_acceleration_mode",
00068 use_speed_from_accel_constant_, use_speed_from_accel_constant_);
00069 swri::param(pnh, "max_lateral_acceleration",
00070 max_lateral_accel_mss_, max_lateral_accel_mss_);
00071
00072 if (!speed_curve_.readFromParameter(pnh, "curvature_vs_speed", true)) {
00073 ROS_ERROR("Failed to load speed/curve parameter. Forcing lateral acceleration mode.");
00074 use_speed_from_accel_constant_ = true;
00075 } else {
00076 ROS_INFO("Loaded speed vs curvature curve (%s)", speed_curve_.interpolationTypeString().c_str());
00077 for (size_t i = 0; i < speed_curve_.numPoints(); i++) {
00078 std::pair<double, double> pt = speed_curve_.getPoint(i);
00079 ROS_INFO(" %zu -- %f [1/m] vs %f [m/s]", i, pt.first, pt.second);
00080 }
00081 }
00082 }
00083
00084 void SpeedForCurvatureParameters::loadFromConfig(const mcm::KeyValueArray &config)
00085 {
00086 std::unordered_map<std::string, std::string> config_map;
00087 for (size_t i = 0; i < config.items.size(); ++i) {
00088 config_map[config.items[i].key] = config.items[i].value;
00089 }
00090
00091 if (config_map.count("curvature_filter_size")) {
00092 curvature_filter_size_ = boost::lexical_cast<double>(config_map.at("curvature_filter_size"));
00093 ROS_INFO("Setting curvature_filter_size to %lf", curvature_filter_size_);
00094 config_map.erase("curvature_filter_size");
00095 }
00096
00097 if (config_map.count("lateral_acceleration_mode")) {
00098 use_speed_from_accel_constant_ =
00099 boost::lexical_cast<int>(config_map.at("lateral_acceleration_mode"));
00100 ROS_INFO("Setting lateral acceleration mode to %s",
00101 use_speed_from_accel_constant_ ? "true" : "false");
00102 config_map.erase("lateral_acceleration_mode");
00103 }
00104
00105 if (config_map.count("max_lateral_acceleration")) {
00106 max_lateral_accel_mss_ = boost::lexical_cast<double>(config_map.at("max_lateral_acceleration"));
00107 ROS_INFO("Setting max_lateral_acceleration to %lf", max_lateral_accel_mss_);
00108 config_map.erase("max_lateral_acceleration");
00109 }
00110
00111 if (config_map.count("curvature_vs_speed/interpolation_type")) {
00112 std::string interp_type = config_map.at("curvature_vs_speed/interpolation_type");
00113 if (interp_type == "zero_order_hold") {
00114 speed_curve_.setInterpolationType(smu::Interpolation1D::ZERO_ORDER_HOLD);
00115 ROS_INFO("Setting interpolation type to %s", interp_type.c_str());
00116 } else if (interp_type == "linear") {
00117 speed_curve_.setInterpolationType(smu::Interpolation1D::LINEAR);
00118 ROS_INFO("Setting interpolation type to %s", interp_type.c_str());
00119 } else {
00120 ROS_ERROR("Ignoring invalid interpolation type '%s'.", interp_type.c_str());
00121 }
00122 config_map.erase("curvature_vs_speed/interpolation_type");
00123 }
00124
00125
00126
00127
00128
00129 std::vector<double> x;
00130 std::vector<double> y;
00131 for (size_t i = 0; true; i++) {
00132 char base_key[1024];
00133 snprintf(base_key, sizeof(base_key), "curvature_vs_speed/values/%zu", i);
00134 const std::string x_key = std::string(base_key) + "/0";
00135 const std::string y_key = std::string(base_key) + "/1";
00136
00137 if (config_map.count(x_key) && config_map.count(y_key)) {
00138 x.push_back(boost::lexical_cast<double>(config_map.at(x_key)));
00139 config_map.erase(x_key);
00140 y.push_back(boost::lexical_cast<double>(config_map.at(y_key)));
00141 config_map.erase(y_key);
00142 } else {
00143 break;
00144 }
00145 }
00146
00147
00148
00149
00150 if (x.size()) {
00151 ROS_INFO("Setting curvature_vs_speed curve: ");
00152 speed_curve_.clear();
00153 for (size_t i = 0; i < x.size(); i++) {
00154 speed_curve_.appendPoint(x[i], y[i]);
00155 ROS_INFO(" %zu -- %lf, %lf", i, x[i], y[i]);
00156 }
00157 }
00158
00159
00160 for (auto const &it : config_map) {
00161 ROS_WARN("Ignoring unknown configuration value '%s'", it.first.c_str());
00162 }
00163 }
00164
00165 void SpeedForCurvatureParameters::readToConfig(mcm::KeyValueArray &config) const
00166 {
00167 mcm::KeyValueArrayPtr msg = boost::make_shared<mcm::KeyValueArray>();
00168 config.header.stamp = ros::Time::now();
00169
00170 addItem(config, "curvature_filter_size",
00171 boost::lexical_cast<std::string>(curvature_filter_size_));
00172 addItem(config, "lateral_acceleration_mode",
00173 use_speed_from_accel_constant_ ? "1" : "0");
00174 addItem(config, "max_lateral_acceleration",
00175 boost::lexical_cast<std::string>(max_lateral_accel_mss_));
00176 addItem(config, "curvature_vs_speed/interpolation_type",
00177 speed_curve_.interpolationTypeString());
00178
00179 for (size_t i = 0; i < speed_curve_.numPoints(); i++) {
00180 char base_key[1024];
00181 snprintf(base_key, sizeof(base_key), "curvature_vs_speed/values/%zu", i);
00182
00183 addItem(config, std::string(base_key) + "/0",
00184 boost::lexical_cast<std::string>(speed_curve_.getPoint(i).first));
00185 addItem(config, std::string(base_key) + "/1",
00186 boost::lexical_cast<std::string>(speed_curve_.getPoint(i).second));
00187 }
00188 }
00189
00190 static double estimateCurvature(const Route &route,
00191 const size_t index,
00192 double filter_size)
00193 {
00194
00195 mnm::RoutePosition pos1;
00196 pos1.id = route.points[index].id();
00197 pos1.distance = 0.0;
00198
00199
00200 mnm::RoutePosition pos0 = pos1;
00201 pos0.distance -= filter_size;
00202
00203
00204 mnm::RoutePosition pos2 = pos1;
00205 pos2.distance += filter_size;
00206
00207
00208 RoutePoint pt0;
00209 interpolateRoutePosition(pt0, route, pos0, true);
00210 RoutePoint pt1;
00211 interpolateRoutePosition(pt1, route, pos1, true);
00212 RoutePoint pt2;
00213 interpolateRoutePosition(pt2, route, pos2, true);
00214
00215
00216 const tf::Vector3 T0 = (pt1.position() - pt0.position()).normalized();
00217
00218 const tf::Vector3 T1 = (pt2.position() - pt1.position()).normalized();
00219
00220 return ((T1-T0)/filter_size).length();
00221 }
00222
00223 static double maxSpeedForCurvature(double curvature,
00224 const SpeedForCurvatureParameters ¶ms)
00225 {
00226 double k = std::abs(curvature);
00227
00228 if (params.use_speed_from_accel_constant_) {
00229 double a = std::abs(params.max_lateral_accel_mss_);
00230
00231 double max_speed = 1000.0;
00232
00233 if (k < 1e-4) {
00234 return max_speed;
00235 } else {
00236 return std::min(max_speed, std::sqrt(a/k));
00237 }
00238 } else {
00239 return params.speed_curve_.eval(k);
00240 }
00241 }
00242
00243 void speedsForCurvature(
00244 mnm::RouteSpeedArray &speeds,
00245 const Route &route,
00246 const SpeedForCurvatureParameters ¶meters)
00247 {
00248 speeds.header.stamp = ros::Time::now();
00249
00250
00251 speeds.speeds.resize(route.points.size());
00252
00253 for (size_t i = 0; i < route.points.size(); ++i) {
00254 speeds.speeds[i].id = route.points[i].id();
00255 speeds.speeds[i].distance = 0.0;
00256
00257 double k = estimateCurvature(route, i, parameters.curvature_filter_size_);
00258 speeds.speeds[i].speed = maxSpeedForCurvature(k, parameters);
00259 }
00260 }
00261
00262 SpeedForObstaclesParameters::SpeedForObstaclesParameters()
00263 :
00264 origin_to_front_m_(2.0),
00265 origin_to_rear_m_(1.0),
00266 origin_to_left_m_(1.0),
00267 origin_to_right_m_(1.0),
00268 max_distance_m_(10.0),
00269 min_distance_m_(1.0),
00270 max_speed_(10.0),
00271 min_speed_(1.0),
00272 stop_buffer_m_(5.0)
00273 {
00274 }
00275
00276 void SpeedForObstaclesParameters::loadFromRosParam(const ros::NodeHandle &pnh)
00277 {
00278 swri::param(pnh, "origin_to_front_m", origin_to_front_m_, 2.0);
00279 swri::param(pnh, "origin_to_rear_m", origin_to_rear_m_, 1.0);
00280 swri::param(pnh, "origin_to_left_m", origin_to_left_m_, 1.0);
00281 swri::param(pnh, "origin_to_right_m", origin_to_right_m_, 1.0);
00282
00283 swri::param(pnh, "max_distance_m", max_distance_m_, 10.0);
00284 swri::param(pnh, "min_distance_m", min_distance_m_, 1.0);
00285 swri::param(pnh, "max_speed", max_speed_, 10.0);
00286 swri::param(pnh, "min_speed", min_speed_, 1.0);
00287
00288 swri::param(pnh, "stop_buffer_m", stop_buffer_m_, 5.0);
00289 }
00290
00291 void generateObstacleData(
00292 std::vector<ObstacleData> &obstacle_data,
00293 const stu::Transform g_route_from_obs,
00294 const mnm::ObstacleArray &obstacles_msg)
00295 {
00296 obstacle_data.resize(obstacles_msg.obstacles.size());
00297 for (size_t i = 0; i < obstacle_data.size(); i++) {
00298 const mnm::Obstacle &obs_msg = obstacles_msg.obstacles[i];
00299
00300 geometry_msgs::Pose pose = obs_msg.pose;
00301 if (pose.orientation.x == 0.0 &&
00302 pose.orientation.y == 0.0 &&
00303 pose.orientation.z == 0.0 &&
00304 pose.orientation.w == 0.0) {
00305 pose.orientation.w = 1.0;
00306 }
00307
00308 tf::Transform g_obs_from_local;
00309 tf::poseMsgToTF(pose, g_obs_from_local);
00310
00311 obstacle_data[i].center = g_route_from_obs*g_obs_from_local.getOrigin();
00312 obstacle_data[i].center.setZ(0.0);
00313
00314 double max_radius = 0.0;
00315 obstacle_data[i].polygon.resize(obs_msg.polygon.size());
00316 for (size_t j = 0; j < obs_msg.polygon.size(); j++) {
00317 tf::Vector3 pt;
00318 tf::pointMsgToTF(obs_msg.polygon[j], pt);
00319
00320 max_radius = std::max(max_radius, pt.length());
00321 obstacle_data[i].polygon[j] = g_route_from_obs*(g_obs_from_local*pt);
00322 obstacle_data[i].polygon[j].setZ(0.0);
00323 }
00324 obstacle_data[i].radius = max_radius;
00325 }
00326 }
00327
00328 void speedsForObstacles(
00329 mnm::RouteSpeedArray &speeds,
00330 std::vector<DistanceReport> &reports,
00331 const Route &route,
00332 const mnm::RoutePosition &route_position,
00333 const std::vector<ObstacleData> &obstacles,
00334 const SpeedForObstaclesParameters &p)
00335 {
00336 tf::Vector3 local_fl(p.origin_to_left_m_, p.origin_to_left_m_, 0.0);
00337 tf::Vector3 local_fr(p.origin_to_left_m_, -p.origin_to_right_m_, 0.0);
00338 tf::Vector3 local_br(-p.origin_to_right_m_, -p.origin_to_right_m_, 0.0);
00339 tf::Vector3 local_bl(-p.origin_to_right_m_, p.origin_to_left_m_, 0.0);
00340 double car_r = 0.0;
00341 car_r = std::max(car_r, local_fl.length());
00342 car_r = std::max(car_r, local_fr.length());
00343 car_r = std::max(car_r, local_br.length());
00344 car_r = std::max(car_r, local_bl.length());
00345
00346 bool skip_point = true;
00347
00348 for (size_t route_index = 0; route_index < route.points.size(); route_index++) {
00349 const RoutePoint &point = route.points[route_index];
00350
00351 if (skip_point) {
00352 if (point.id() == route_position.id) {
00353 skip_point = false;
00354 }
00355 continue;
00356 }
00357
00358
00359
00360
00361
00362 double veh_r = car_r;
00363 if (point.hasProperty("vehicle_width_override"))
00364 {
00365 ROS_DEBUG("Speeds for obstacle found vehicle_width_override property");
00366 double width = point.getTypedProperty<double>("vehicle_width_override");
00367
00368
00369 if (veh_r >= width/2.0)
00370 {
00371 veh_r = width/2.0;
00372 ROS_WARN_THROTTLE(1.0, "Vehicle width being overriden to %0.2f", (float)veh_r);
00373 }
00374 }
00375
00376 for (const auto& obstacle: obstacles) {
00377 const tf::Vector3 v = obstacle.center - point.position();
00378 const double d = v.length() - veh_r - obstacle.radius;
00379 if (d > p.max_distance_m_) {
00380
00381 continue;
00382 }
00383
00384 tf::Vector3 closest_point = obstacle.center;
00385
00386 double distance = std::numeric_limits<double>::max();
00387 for (size_t i = 1; i < obstacle.polygon.size(); i++) {
00388 double dist = swri_geometry_util::DistanceFromLineSegment(
00389 obstacle.polygon[i - 1],
00390 obstacle.polygon[i],
00391 point.position()) - veh_r;
00392
00393 if (dist < distance) {
00394 distance = dist;
00395 closest_point = swri_geometry_util::ProjectToLineSegment(
00396 obstacle.polygon[i - 1],
00397 obstacle.polygon[i],
00398 point.position());
00399 }
00400 }
00401
00402 if (obstacle.polygon.size() > 1) {
00403 double dist = swri_geometry_util::DistanceFromLineSegment(
00404 obstacle.polygon.back(),
00405 obstacle.polygon.front(),
00406 point.position()) - veh_r;
00407
00408 if (dist < distance) {
00409 distance = dist;
00410 closest_point = swri_geometry_util::ProjectToLineSegment(
00411 obstacle.polygon.back(),
00412 obstacle.polygon.front(),
00413 point.position());
00414 }
00415 }
00416
00417 if (distance > p.max_distance_m_) {
00418
00419 continue;
00420 }
00421
00422
00423
00424
00425 if (distance > 0.0) {
00426 DistanceReport report;
00427 report.near = false;
00428 report.collision = false;
00429 report.route_index = route_index;
00430 report.vehicle_point = point.position() + (closest_point - point.position()).normalized() * veh_r;
00431 report.obstacle_point = closest_point;
00432 reports.push_back(report);
00433
00434 const double s = std::max(0.0, (distance - p.min_distance_m_) / (
00435 p.max_distance_m_ - p.min_distance_m_));
00436 double speed = (1.0-s)*p.min_speed_ + s*p.max_speed_;
00437
00438 speeds.speeds.emplace_back();
00439 speeds.speeds.back().id = point.id();
00440 speeds.speeds.back().distance = 0.0;
00441 speeds.speeds.back().speed = speed;
00442
00443 continue;
00444 }
00445
00446 DistanceReport report;
00447 report.near = false;
00448 report.collision = true;
00449 report.route_index = route_index;
00450 report.vehicle_point = point.position();
00451 report.obstacle_point = closest_point;
00452 reports.push_back(report);
00453
00454 speeds.speeds.emplace_back();
00455 speeds.speeds.back().id = point.id();
00456 speeds.speeds.back().distance = -p.stop_buffer_m_ - p.origin_to_front_m_;
00457 speeds.speeds.back().speed = 0.0;
00458
00459 speeds.speeds.emplace_back();
00460 speeds.speeds.back().id = point.id();
00461 speeds.speeds.back().distance = (-p.stop_buffer_m_ - p.origin_to_front_m_) / 2.0;
00462 speeds.speeds.back().speed = 0.0;
00463
00464 speeds.speeds.emplace_back();
00465 speeds.speeds.back().id = point.id();
00466 speeds.speeds.back().distance = 0.0;
00467 speeds.speeds.back().speed = 0.0;
00468
00469 continue;
00470 }
00471 }
00472 }
00473 }