提交 619e1c77 编写于 作者: A Aaron Xiao 提交者: Dong Li

Map: Move MakeMapId from common util to hdmap_util.

上级 ede05caf
......@@ -18,7 +18,6 @@ cc_library(
"//modules/common/math",
"//modules/common/proto:pnc_point_proto",
"//modules/common/time",
"//modules/map/proto:map_proto",
"//modules/perception/proto:perception_proto",
],
)
......
......@@ -91,12 +91,6 @@ double Distance2D(const PathPoint& a, const PathPoint& b) {
return std::hypot(a.x() - b.x(), a.y() - b.y());
}
apollo::hdmap::Id MakeMapId(const std::string& id) {
apollo::hdmap::Id map_id;
map_id.set_id(id);
return map_id;
}
} // namespace util
} // namespace common
} // namespace apollo
......@@ -30,7 +30,6 @@
#include "modules/common/proto/geometry.pb.h"
#include "modules/common/proto/pnc_point.pb.h"
#include "modules/map/proto/map_id.pb.h"
#include "modules/perception/proto/perception_obstacle.pb.h"
/**
......@@ -87,13 +86,6 @@ apollo::common::TrajectoryPoint MakeTrajectoryPoint(
*/
double Distance2D(const PathPoint& a, const PathPoint& b);
/**
* @brief create a Map ID given a string.
* @param id a string id
* @return a Map ID instance
*/
apollo::hdmap::Id MakeMapId(const std::string& id);
} // namespace util
} // namespace common
} // namespace apollo
......
......@@ -21,8 +21,8 @@ limitations under the License.
#include "glog/logging.h"
#include "modules/common/util/util.h"
#include "modules/map/hdmap/hdmap_impl.h"
#include "modules/map/hdmap/hdmap_util.h"
namespace {
......@@ -334,7 +334,7 @@ void LaneInfo::post_process(const HDMapImpl &map_instance) {
void LaneInfo::update_overlaps(const HDMapImpl &map_instance) {
for (const auto &overlap_id : _overlap_ids) {
const auto &overlap_ptr = map_instance.get_overlap_by_id(
apollo::common::util::MakeMapId(overlap_id));
apollo::hdmap::MakeMapId(overlap_id));
if (overlap_ptr == nullptr) {
continue;
}
......@@ -344,7 +344,7 @@ void LaneInfo::update_overlaps(const HDMapImpl &map_instance) {
if (object_id == _lane.id().id()) {
continue;
}
const auto &object_map_id = apollo::common::util::MakeMapId(object_id);
const auto &object_map_id = apollo::hdmap::MakeMapId(object_id);
if (map_instance.get_lane_by_id(object_map_id) != nullptr) {
_cross_lanes.emplace_back(overlap_ptr);
}
......
......@@ -13,8 +13,8 @@ See the License for the specific language governing permissions and
limitations under the License.
=========================================================================*/
#ifndef MODULES_MAP_MAP_LOADER_INC_HDMAP_COMMON_H
#define MODULES_MAP_MAP_LOADER_INC_HDMAP_COMMON_H
#ifndef MODULES_MAP_HDMAP_HDMAP_COMMON_H
#define MODULES_MAP_HDMAP_HDMAP_COMMON_H
#include <memory>
#include <string>
......@@ -357,4 +357,4 @@ using JunctionBoundaryPtr = std::shared_ptr<JunctionBoundary>;
} // namespace hdmap
} // namespace apollo
#endif // MODULES_MAP_MAP_LOADER_INC_HDMAP_COMMON_H
#endif // MODULES_MAP_HDMAP_HDMAP_COMMON_H
......@@ -13,8 +13,8 @@ See the License for the specific language governing permissions and
limitations under the License.
=========================================================================*/
#ifndef MODULES_MAP_MAP_LOADER_INC_HDMAP_IMPL_H
#define MODULES_MAP_MAP_LOADER_INC_HDMAP_IMPL_H
#ifndef MODULES_MAP_HDMAP_HDMAP_IMPL_H
#define MODULES_MAP_HDMAP_HDMAP_IMPL_H
#include <memory>
#include <vector>
......@@ -310,4 +310,4 @@ class HDMapImpl {
} // namespace hdmap
} // namespace apollo
#endif // MODULES_MAP_MAP_LOADER_INC_HDMAP_IMPL_H
#endif // MODULES_MAP_HDMAP_HDMAP_IMPL_H
......@@ -20,6 +20,7 @@ limitations under the License.
#include "modules/common/configs/config_gflags.h"
#include "modules/common/util/string_util.h"
#include "modules/map/proto/map_id.pb.h"
/**
* @namespace apollo::hdmap
......@@ -37,6 +38,17 @@ inline std::string BaseMapFile() {
FLAGS_map_dir, "/", FLAGS_base_map_filename);
}
/**
* @brief create a Map ID given a string.
* @param id a string id
* @return a Map ID instance
*/
inline apollo::hdmap::Id MakeMapId(const std::string& id) {
apollo::hdmap::Id map_id;
map_id.set_id(id);
return map_id;
}
} // namespace hdmap
} // namespace apollo
......
......@@ -24,7 +24,6 @@
#include "modules/routing/proto/routing.pb.h"
#include "modules/common/util/util.h"
#include "modules/map/hdmap/hdmap.h"
using Id = apollo::hdmap::Id;
......@@ -864,7 +863,7 @@ TEST(TestSuite, lane_info) {
HDMap hdmap;
EXPECT_EQ(hdmap.load_map_from_file(kMapFilename), 0);
LaneInfoConstPtr lane1 =
hdmap.get_lane_by_id(apollo::common::util::MakeMapId("l1"));
hdmap.get_lane_by_id(apollo::hdmap::MakeMapId("l1"));
EXPECT_EQ("l1", lane1->id().id());
EXPECT_EQ(lane1->points().size(), 2);
EXPECT_NEAR(lane1->points()[0].x(), 2.0, 1e-6);
......
......@@ -30,7 +30,7 @@
#include "modules/map/proto/map_id.pb.h"
#include "modules/common/log.h"
#include "modules/common/util/util.h"
#include "modules/map/hdmap/hdmap_util.h"
#include "modules/map/pnc_map/path.h"
namespace apollo {
......@@ -92,8 +92,7 @@ bool PncMap::validate_routing(const ::apollo::routing::RoutingResponse &routing)
const double kLargeEps = 1e-3;
for (int i = 0; i < num_routes; ++i) {
const auto &segment = routing.route(i);
const auto lane =
hdmap_.get_lane_by_id(common::util::MakeMapId(segment.id()));
const auto lane = hdmap_.get_lane_by_id(hdmap::MakeMapId(segment.id()));
if (lane == nullptr) {
AERROR << "Can not find lane with id = " + segment.id() + ".";
return false;
......@@ -142,8 +141,7 @@ bool PncMap::validate_routing(const ::apollo::routing::RoutingResponse &routing)
continue;
}
const auto &segment = routing.route(i);
const auto lane =
hdmap_.get_lane_by_id(common::util::MakeMapId(segment.id()));
const auto lane = hdmap_.get_lane_by_id(hdmap::MakeMapId(segment.id()));
const std::string next_id = routing.route(i + 1).id();
bool is_successor = false;
for (const auto &other_lane_id : lane->lane().successor_id()) {
......@@ -292,8 +290,7 @@ bool PncMap::CreatePathFromRouting(const ::apollo::routing::RoutingResponse &rou
// Extend the trajectory towards the start of the trajectory.
if (start_s < 0) {
const auto &first_segment = routing.route(0).road_info().passage_region(0).segment(0);
auto lane =
hdmap_.get_lane_by_id(common::util::MakeMapId(first_segment.id()));
auto lane = hdmap_.get_lane_by_id(hdmap::MakeMapId(first_segment.id()));
if (!lane) {
AERROR << "failed to get lane from id " << first_segment.id();
return false;
......@@ -334,7 +331,7 @@ bool PncMap::CreatePathFromRouting(const ::apollo::routing::RoutingResponse &rou
end_s - router_s + lane_segment.start_s(), lane_segment.end_s());
if (adjusted_start_s < adjusted_end_s) {
const auto lane_info =
hdmap_.get_lane_by_id(common::util::MakeMapId(lane_segment.id()));
hdmap_.get_lane_by_id(hdmap::MakeMapId(lane_segment.id()));
if (lane_info == nullptr) {
AERROR << "Failed to find lane " << lane_segment.id() << " in map";
return false;
......@@ -353,8 +350,7 @@ bool PncMap::CreatePathFromRouting(const ::apollo::routing::RoutingResponse &rou
std::string last_lane_id = last_segment.id();
double last_s = last_segment.end_s();
while (router_s < end_s - kRouteEpsilon) {
const auto lane =
hdmap_.get_lane_by_id(common::util::MakeMapId(last_lane_id));
const auto lane = hdmap_.get_lane_by_id(hdmap::MakeMapId(last_lane_id));
if (lane == nullptr) {
break;
}
......
......@@ -26,8 +26,8 @@
#include "modules/common/configs/config_gflags.h"
#include "modules/common/math/linear_interpolation.h"
#include "modules/common/math/vec2d.h"
#include "modules/common/util/util.h"
#include "modules/map/hdmap/hdmap.h"
#include "modules/map/hdmap/hdmap_util.h"
#include "modules/map/proto/map_id.pb.h"
#include "modules/prediction/common/prediction_gflags.h"
......@@ -86,7 +86,7 @@ std::shared_ptr<const LaneInfo> PredictionMap::LaneById(const Id& id) {
std::shared_ptr<const LaneInfo> PredictionMap::LaneById(
const std::string& str_id) {
return LaneById(apollo::common::util::MakeMapId(str_id));
return LaneById(apollo::hdmap::MakeMapId(str_id));
}
void PredictionMap::GetProjection(const Eigen::Vector2d& position,
......@@ -393,7 +393,7 @@ int PredictionMap::LaneTurnType(const Id& id) {
}
int PredictionMap::LaneTurnType(const std::string& lane_id) {
return LaneTurnType(apollo::common::util::MakeMapId(lane_id));
return LaneTurnType(apollo::hdmap::MakeMapId(lane_id));
}
} // namespace prediction
......
......@@ -22,7 +22,7 @@
#include "modules/common/log.h"
#include "modules/common/math/math_utils.h"
#include "modules/common/util/util.h"
#include "modules/map/hdmap/hdmap_util.h"
#include "modules/prediction/common/prediction_gflags.h"
#include "modules/prediction/common/prediction_map.h"
......@@ -180,7 +180,7 @@ void LaneSequencePredictor::DrawLaneSequenceTrajectoryPoints(
for (size_t i = 0; i < static_cast<size_t>(total_time / freq); ++i) {
Eigen::Vector2d point;
double theta = M_PI;
if (map->SmoothPointFromLane(apollo::common::util::MakeMapId(lane_id),
if (map->SmoothPointFromLane(apollo::hdmap::MakeMapId(lane_id),
lane_s, lane_l, &point, &theta) != 0) {
AERROR << "Unable to get smooth point from lane [" << lane_id
<< "] with s [" << lane_s << "] and l [" << lane_l
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册