Skip to content
This repository has been archived by the owner on Jul 1, 2024. It is now read-only.

feat!: change from autoware_auto_msgs to autoware_msgs #247

Merged
merged 10 commits into from
Jun 4, 2024
2 changes: 1 addition & 1 deletion tmp/lanelet2_extension/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ Autoware intersection module requires the information on which lanes can be igno
This contains functions to convert lanelet map objects into ROS messages.
Currently it contains following conversions:

- lanelet::LaneletMapPtr to/from autoware_auto_mapping_msgs::msg::HADMapBin
- lanelet::LaneletMapPtr to/from autoware_map_msgs::msg::LaneletMapBin
- lanelet::Point3d to geometry_msgs::Point
- lanelet::Point2d to geometry_msgs::Point
- lanelet::BasicPoint3d to geometry_msgs::Point
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef LANELET2_EXTENSION__LOCALIZATION__LANDMARK_HPP_
#define LANELET2_EXTENSION__LOCALIZATION__LANDMARK_HPP_

#include "autoware_auto_mapping_msgs/msg/had_map_bin.hpp"
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>

#include <lanelet2_core/primitives/Polygon.h>

Expand All @@ -28,7 +28,7 @@ namespace lanelet::localization
{

std::vector<lanelet::Polygon3d> parseLandmarkPolygons(
const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg,
const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr & msg,
const std::string & target_subtype);

} // namespace lanelet::localization
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

// NOLINTBEGIN(readability-identifier-naming)

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <geometry_msgs/msg/point.hpp>
#include <geometry_msgs/msg/point32.hpp>
#include <geometry_msgs/msg/polygon.hpp>
Expand All @@ -36,17 +36,17 @@ namespace lanelet::utils::conversion
* @param map [lanelet map data]
* @param msg [converted ROS message. Only "data" field is filled]
*/
void toBinMsg(const lanelet::LaneletMapPtr & map, autoware_auto_mapping_msgs::msg::HADMapBin * msg);
void toBinMsg(const lanelet::LaneletMapPtr & map, autoware_map_msgs::msg::LaneletMapBin * msg);

/**
* [fromBinMsg converts ROS message into lanelet2 data. Similar implementation
* to lanelet::io_handlers::BinHandler::parse()]
* @param msg [ROS message for lanelet map]
* @param map [Converted lanelet2 data]
*/
void fromBinMsg(const autoware_auto_mapping_msgs::msg::HADMapBin & msg, lanelet::LaneletMapPtr map);
void fromBinMsg(const autoware_map_msgs::msg::LaneletMapBin & msg, lanelet::LaneletMapPtr map);
void fromBinMsg(
const autoware_auto_mapping_msgs::msg::HADMapBin & msg, lanelet::LaneletMapPtr map,
const autoware_map_msgs::msg::LaneletMapBin & msg, lanelet::LaneletMapPtr map,
lanelet::traffic_rules::TrafficRulesPtr * traffic_rules,
lanelet::routing::RoutingGraphPtr * routing_graph);

Expand Down
2 changes: 1 addition & 1 deletion tmp/lanelet2_extension/lib/landmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ namespace lanelet::localization
{

std::vector<lanelet::Polygon3d> parseLandmarkPolygons(
const autoware_auto_mapping_msgs::msg::HADMapBin::ConstSharedPtr & msg,
const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr & msg,
const std::string & target_subtype)
{
lanelet::LaneletMapPtr lanelet_map_ptr{std::make_shared<lanelet::LaneletMap>()};
Expand Down
6 changes: 3 additions & 3 deletions tmp/lanelet2_extension/lib/message_conversion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@

namespace lanelet::utils::conversion
{
void toBinMsg(const lanelet::LaneletMapPtr & map, autoware_auto_mapping_msgs::msg::HADMapBin * msg)
void toBinMsg(const lanelet::LaneletMapPtr & map, autoware_map_msgs::msg::LaneletMapBin * msg)
{
if (msg == nullptr) {
std::cerr << __FUNCTION__ << "msg is null pointer!";
Expand All @@ -58,7 +58,7 @@ void toBinMsg(const lanelet::LaneletMapPtr & map, autoware_auto_mapping_msgs::ms
msg->data.assign(data_str.begin(), data_str.end());
}

void fromBinMsg(const autoware_auto_mapping_msgs::msg::HADMapBin & msg, lanelet::LaneletMapPtr map)
void fromBinMsg(const autoware_map_msgs::msg::LaneletMapBin & msg, lanelet::LaneletMapPtr map)
{
if (!map) {
std::cerr << __FUNCTION__ << ": map is null pointer!";
Expand All @@ -79,7 +79,7 @@ void fromBinMsg(const autoware_auto_mapping_msgs::msg::HADMapBin & msg, lanelet:
}

void fromBinMsg(
const autoware_auto_mapping_msgs::msg::HADMapBin & msg, lanelet::LaneletMapPtr map,
const autoware_map_msgs::msg::LaneletMapBin & msg, lanelet::LaneletMapPtr map,
lanelet::traffic_rules::TrafficRulesPtr * traffic_rules,
lanelet::routing::RoutingGraphPtr * routing_graph)
{
Expand Down
3 changes: 1 addition & 2 deletions tmp/lanelet2_extension/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_auto_mapping_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_map_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_utils</depend>
<depend>geographiclib</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ class TestSuite : public ::testing::Test // NOLINT for gtest

TEST_F(TestSuite, BinMsgConversion) // NOLINT for gtest
{
autoware_auto_mapping_msgs::msg::HADMapBin bin_msg;
autoware_map_msgs::msg::LaneletMapBin bin_msg;
lanelet::LaneletMapPtr regenerated_map(new lanelet::LaneletMap);

lanelet::utils::conversion::toBinMsg(single_lanelet_map_ptr, &bin_msg);
Expand Down
4 changes: 2 additions & 2 deletions tmp/lanelet2_extension/test/src/test_route_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
#include "lanelet2_extension/utility/message_conversion.hpp"
#include "lanelet2_extension/utility/route_checker.hpp"

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
#include <autoware_planning_msgs/msg/lanelet_route.hpp>

#include <gtest/gtest.h>
Expand Down Expand Up @@ -74,7 +74,7 @@ class TestSuite : public ::testing::Test // NOLINT for gtest

TEST_F(TestSuite, isRouteValid) // NOLINT for gtest
{
autoware_auto_mapping_msgs::msg::HADMapBin bin_msg;
autoware_map_msgs::msg::LaneletMapBin bin_msg;

const auto route_ptr1 =
std::make_shared<autoware_planning_msgs::msg::LaneletRoute>(sample_route1);
Expand Down
Loading