Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: autoware_msgs migration #6

Merged
merged 3 commits into from
May 8, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion autoware_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 autoware_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 autoware_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 autoware_lanelet2_extension/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,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 autoware_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 "autoware_lanelet2_extension/utility/message_conversion.hpp"
#include "autoware_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
4 changes: 0 additions & 4 deletions build_depends.repos
Original file line number Diff line number Diff line change
@@ -1,8 +1,4 @@
repositories:
autoware_auto_msgs:
type: git
url: https://github.com/tier4/autoware_auto_msgs.git
version: tier4/main
autoware_cmake:
type: git
url: https://github.com/autowarefoundation/autoware_cmake.git
Expand Down
Loading