Skip to content

Commit

Permalink
refactor(pose_initializer)!: prefix package and namespace with autowa…
Browse files Browse the repository at this point in the history
…re (autowarefoundation#8701)

* add autoware_ prefix

Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com>

* fix link

Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com>

---------

Signed-off-by: a-maumau <maumaumaumaumaumaumaumaumaumau@gmail.com>
Co-authored-by: SakodaShintaro <shintaro.sakoda@tier4.jp>
  • Loading branch information
a-maumau and SakodaShintaro authored Sep 3, 2024
1 parent 93e4e7d commit 03f675e
Show file tree
Hide file tree
Showing 25 changed files with 87 additions and 48 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ localization/autoware_twist2accel/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier
localization/ekf_localizer/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp takamasa.horibe@tier4.jp takeshi.ishita@tier4.jp yamato.ando@tier4.jp
localization/localization_util/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/ndt_scan_matcher/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/pose_initializer/** anh.nguyen.2@tier4.jp isamu.takagi@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/autoware_pose_initializer/** anh.nguyen.2@tier4.jp isamu.takagi@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/yabloc/yabloc_common/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/yabloc/yabloc_image_processing/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
localization/yabloc/yabloc_monitor/** anh.nguyen.2@tier4.jp kento.yabuuchi.2@tier4.jp masahiro.sakamoto@tier4.jp ryu.yamamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@
<let name="sub_gnss_pose_cov" value="/localization/pose_estimator/pose_with_covariance" unless="$(var multi_localizer_mode)"/>
</group>

<include file="$(find-pkg-share pose_initializer)/launch/pose_initializer.launch.xml">
<include file="$(find-pkg-share autoware_pose_initializer)/launch/pose_initializer.launch.xml">
<arg name="user_defined_initial_pose/enable" value="$(var user_defined_initial_pose/enable)"/>
<arg name="user_defined_initial_pose/pose" value="$(var user_defined_initial_pose/pose)"/>
<arg name="ndt_enabled" value="$(var use_ndt_pose)"/>
Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_localization_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -24,13 +24,13 @@
<exec_depend>autoware_lidar_marker_localizer</exec_depend>
<exec_depend>autoware_pointcloud_preprocessor</exec_depend>
<exec_depend>autoware_pose_estimator_arbiter</exec_depend>
<exec_depend>autoware_pose_initializer</exec_depend>
<exec_depend>autoware_pose_instability_detector</exec_depend>
<exec_depend>eagleye_geo_pose_fusion</exec_depend>
<exec_depend>eagleye_gnss_converter</exec_depend>
<exec_depend>eagleye_rt</exec_depend>
<exec_depend>ekf_localizer</exec_depend>
<exec_depend>ndt_scan_matcher</exec_depend>
<exec_depend>pose_initializer</exec_depend>
<exec_depend>topic_tools</exec_depend>
<exec_depend>yabloc_common</exec_depend>
<exec_depend>yabloc_image_processing</exec_depend>
Expand Down
4 changes: 2 additions & 2 deletions launch/tier4_simulator_launch/launch/simulator.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@
</group>

<group if="$(eval '&quot;$(var localization_sim_mode)&quot;==&quot;api&quot;')">
<include file="$(find-pkg-share pose_initializer)/launch/pose_initializer.launch.xml">
<include file="$(find-pkg-share autoware_pose_initializer)/launch/pose_initializer.launch.xml">
<arg name="user_defined_initial_pose/enable" value="false"/>
<arg name="user_defined_initial_pose/pose" value="[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]"/>
<arg name="ndt_enabled" value="false"/>
Expand All @@ -159,7 +159,7 @@
<push-ros-namespace namespace="localization"/>
<group>
<push-ros-namespace namespace="util"/>
<include file="$(find-pkg-share pose_initializer)/launch/pose_initializer.launch.xml">
<include file="$(find-pkg-share autoware_pose_initializer)/launch/pose_initializer.launch.xml">
<arg name="user_defined_initial_pose/enable" value="false"/>
<arg name="user_defined_initial_pose/pose" value="[0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]"/>
<arg name="ndt_enabled" value="false"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,20 +1,20 @@
cmake_minimum_required(VERSION 3.14)
project(pose_initializer)
project(autoware_pose_initializer)

find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_add_library(${PROJECT_NAME} SHARED
src/pose_initializer/pose_initializer_core.cpp
src/pose_initializer/gnss_module.cpp
src/pose_initializer/localization_module.cpp
src/pose_initializer/stop_check_module.cpp
src/pose_initializer/ekf_localization_trigger_module.cpp
src/pose_initializer/ndt_localization_trigger_module.cpp
src/pose_initializer_core.cpp
src/gnss_module.cpp
src/localization_module.cpp
src/stop_check_module.cpp
src/ekf_localization_trigger_module.cpp
src/ndt_localization_trigger_module.cpp
)

rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "PoseInitializer"
PLUGIN "autoware::pose_initializer::PoseInitializer"
EXECUTABLE ${PROJECT_NAME}_node
EXECUTOR MultiThreadedExecutor
)
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# pose_initializer
# autoware_pose_initializer

## Purpose

The `pose_initializer` is the package to send an initial pose to `ekf_localizer`.
The `autoware_pose_initializer` is the package to send an initial pose to `ekf_localizer`.
It receives roughly estimated initial pose from GNSS/user.
Passing the pose to `ndt_scan_matcher`, and it gets a calculated ego pose from `ndt_scan_matcher` via service.
Finally, it publishes the initial pose to `ekf_localizer`.
Expand All @@ -13,7 +13,7 @@ This node depends on the map height fitter library.

### Parameters

{{ json_to_markdown("localization/pose_initializer/schema/pose_initializer.schema.json") }}
{{ json_to_markdown("localization/autoware_pose_initializer/schema/pose_initializer.schema.json") }}

### Services

Expand Down Expand Up @@ -51,7 +51,7 @@ If the score of initial pose estimation result is lower than score threshold, ER

## Connection with Default AD API

This `pose_initializer` is used via default AD API. For detailed description of the API description, please refer to [the description of `autoware_default_adapi`](https://github.com/autowarefoundation/autoware.universe/blob/main/system/autoware_default_adapi/document/localization.md).
This `autoware_pose_initializer` is used via default AD API. For detailed description of the API description, please refer to [the description of `autoware_default_adapi`](https://github.com/autowarefoundation/autoware.universe/blob/main/system/autoware_default_adapi/document/localization.md).

<img src="../../system/autoware_default_adapi/document/images/localization.drawio.svg" alt="drawing" width="800"/>

Expand Down Expand Up @@ -136,4 +136,4 @@ pose:
```

It behaves the same as "initialpose (from rviz)".
The position.z and the covariance will be overwritten by [ad_api_adaptors](https://github.com/autowarefoundation/autoware.universe/tree/main/system/autoware_default_adapi_helpers/ad_api_adaptors), so there is no need to input them.
The position.z and the covariance will be overwritten by [ad_api_adaptors](https://github.com/autowarefoundation/autoware.universe/tree/main/system/default_ad_api_helpers/ad_api_adaptors), so there is no need to input them.
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<launch>
<arg name="config_file" default="$(find-pkg-share pose_initializer)/config/pose_initializer.param.yaml"/>
<arg name="config_file" default="$(find-pkg-share autoware_pose_initializer)/config/pose_initializer.param.yaml"/>
<arg name="ndt_enabled"/>
<arg name="gnss_enabled"/>
<arg name="ekf_enabled"/>
Expand All @@ -9,7 +9,7 @@
<arg name="sub_gnss_pose_cov" default="sub_gnss_pose_cov"/>
<arg name="gnss_initial_pose_auto_fix_target" default="pointcloud_map"/>

<node pkg="pose_initializer" exec="pose_initializer_node" output="both">
<node pkg="autoware_pose_initializer" exec="autoware_pose_initializer_node" output="both">
<param from="$(var config_file)" allow_substs="true"/>
<remap from="yabloc_align" to="/localization/pose_estimator/yabloc/initializer/yabloc_align_srv"/>
<remap from="ndt_align" to="/localization/pose_estimator/ndt_align_srv"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>pose_initializer</name>
<name>autoware_pose_initializer</name>
<version>0.1.0</version>
<description>The pose_initializer package</description>
<description>The autoware_pose_initializer package</description>
<maintainer email="yamato.ando@tier4.jp">Yamato Ando</maintainer>
<maintainer email="isamu.takagi@tier4.jp">Takagi, Isamu</maintainer>
<maintainer email="masahiro.sakamoto@tier4.jp">Masahiro Sakamoto</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef POSE_INITIALIZER__COPY_VECTOR_TO_ARRAY_HPP_
#define POSE_INITIALIZER__COPY_VECTOR_TO_ARRAY_HPP_
#ifndef COPY_VECTOR_TO_ARRAY_HPP_
#define COPY_VECTOR_TO_ARRAY_HPP_

#include <fmt/core.h>

Expand All @@ -22,6 +22,8 @@
#include <string>
#include <vector>

namespace autoware::pose_initializer
{
template <typename T, size_t N>
void copy_vector_to_array(const std::vector<T> & vector, std::array<T, N> & array)
{
Expand All @@ -44,5 +46,6 @@ std::array<double, 36> get_covariance_parameter(NodeT * node, const std::string
copy_vector_to_array(parameter, covariance);
return covariance;
}
} // namespace autoware::pose_initializer

#endif // POSE_INITIALIZER__COPY_VECTOR_TO_ARRAY_HPP_
#endif // COPY_VECTOR_TO_ARRAY_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
#include <memory>
#include <string>

namespace autoware::pose_initializer
{
using ServiceException = component_interface_utils::ServiceException;
using Initialize = localization_interface::Initialize;

Expand Down Expand Up @@ -65,3 +67,4 @@ void EkfLocalizationTriggerModule::send_request(bool flag, bool need_spin) const
Initialize::Service::Response::ERROR_ESTIMATION, "EKF " + command_name + " failed");
}
}
} // namespace autoware::pose_initializer
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef POSE_INITIALIZER__EKF_LOCALIZATION_TRIGGER_MODULE_HPP_
#define POSE_INITIALIZER__EKF_LOCALIZATION_TRIGGER_MODULE_HPP_
#ifndef EKF_LOCALIZATION_TRIGGER_MODULE_HPP_
#define EKF_LOCALIZATION_TRIGGER_MODULE_HPP_

#include <rclcpp/rclcpp.hpp>

#include <std_srvs/srv/set_bool.hpp>

namespace autoware::pose_initializer
{
class EkfLocalizationTriggerModule
{
private:
Expand All @@ -33,5 +35,6 @@ class EkfLocalizationTriggerModule
rclcpp::Node * node_;
rclcpp::Client<SetBool>::SharedPtr client_ekf_trigger_;
};
} // namespace autoware::pose_initializer

#endif // POSE_INITIALIZER__EKF_LOCALIZATION_TRIGGER_MODULE_HPP_
#endif // EKF_LOCALIZATION_TRIGGER_MODULE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,8 @@

#include <memory>

namespace autoware::pose_initializer
{
GnssModule::GnssModule(rclcpp::Node * node)
: fitter_(node),
clock_(node->get_clock()),
Expand Down Expand Up @@ -55,3 +57,4 @@ geometry_msgs::msg::PoseWithCovarianceStamped GnssModule::get_pose()
}
return pose;
}
} // namespace autoware::pose_initializer
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,16 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef POSE_INITIALIZER__GNSS_MODULE_HPP_
#define POSE_INITIALIZER__GNSS_MODULE_HPP_
#ifndef GNSS_MODULE_HPP_
#define GNSS_MODULE_HPP_

#include <autoware/map_height_fitter/map_height_fitter.hpp>
#include <rclcpp/rclcpp.hpp>

#include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>

namespace autoware::pose_initializer
{
class GnssModule
{
private:
Expand All @@ -38,5 +40,6 @@ class GnssModule
PoseWithCovarianceStamped::ConstSharedPtr pose_;
double timeout_;
};
} // namespace autoware::pose_initializer

#endif // POSE_INITIALIZER__GNSS_MODULE_HPP_
#endif // GNSS_MODULE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
#include <memory>
#include <string>

namespace autoware::pose_initializer
{
using ServiceException = component_interface_utils::ServiceException;
using Initialize = localization_interface::Initialize;
using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped;
Expand Down Expand Up @@ -50,3 +52,4 @@ std::tuple<PoseWithCovarianceStamped, bool> LocalizationModule::align_pose(
// Overwrite the covariance.
return std::make_tuple(res->pose_with_covariance, res->reliable);
}
} // namespace autoware::pose_initializer
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef POSE_INITIALIZER__LOCALIZATION_MODULE_HPP_
#define POSE_INITIALIZER__LOCALIZATION_MODULE_HPP_
#ifndef LOCALIZATION_MODULE_HPP_
#define LOCALIZATION_MODULE_HPP_

#include <rclcpp/rclcpp.hpp>

Expand All @@ -23,6 +23,8 @@
#include <string>
#include <tuple>

namespace autoware::pose_initializer
{
class LocalizationModule
{
private:
Expand All @@ -37,5 +39,6 @@ class LocalizationModule
rclcpp::Logger logger_;
rclcpp::Client<RequestPoseAlignment>::SharedPtr cli_align_;
};
} // namespace autoware::pose_initializer

#endif // POSE_INITIALIZER__LOCALIZATION_MODULE_HPP_
#endif // LOCALIZATION_MODULE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
#include <memory>
#include <string>

namespace autoware::pose_initializer
{
using ServiceException = component_interface_utils::ServiceException;
using Initialize = localization_interface::Initialize;

Expand Down Expand Up @@ -65,3 +67,4 @@ void NdtLocalizationTriggerModule::send_request(bool flag, bool need_spin) const
Initialize::Service::Response::ERROR_ESTIMATION, "NDT " + command_name + " failed");
}
}
} // namespace autoware::pose_initializer
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef POSE_INITIALIZER__NDT_LOCALIZATION_TRIGGER_MODULE_HPP_
#define POSE_INITIALIZER__NDT_LOCALIZATION_TRIGGER_MODULE_HPP_
#ifndef NDT_LOCALIZATION_TRIGGER_MODULE_HPP_
#define NDT_LOCALIZATION_TRIGGER_MODULE_HPP_

#include <rclcpp/rclcpp.hpp>

#include <std_srvs/srv/set_bool.hpp>

namespace autoware::pose_initializer
{
class NdtLocalizationTriggerModule
{
private:
Expand All @@ -33,5 +35,6 @@ class NdtLocalizationTriggerModule
rclcpp::Node * node_;
rclcpp::Client<SetBool>::SharedPtr client_ndt_trigger_;
};
} // namespace autoware::pose_initializer

#endif // POSE_INITIALIZER__NDT_LOCALIZATION_TRIGGER_MODULE_HPP_
#endif // NDT_LOCALIZATION_TRIGGER_MODULE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@
#include <sstream>
#include <vector>

namespace autoware::pose_initializer
{
PoseInitializer::PoseInitializer(const rclcpp::NodeOptions & options)
: rclcpp::Node("pose_initializer", options)
{
Expand Down Expand Up @@ -221,6 +223,7 @@ geometry_msgs::msg::PoseWithCovarianceStamped PoseInitializer::get_gnss_pose()
throw ServiceException(
Initialize::Service::Response::ERROR_GNSS_SUPPORT, "GNSS is not supported.");
}
} // namespace autoware::pose_initializer

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(PoseInitializer)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::pose_initializer::PoseInitializer)
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef POSE_INITIALIZER__POSE_INITIALIZER_CORE_HPP_
#define POSE_INITIALIZER__POSE_INITIALIZER_CORE_HPP_
#ifndef POSE_INITIALIZER_CORE_HPP_
#define POSE_INITIALIZER_CORE_HPP_

#include "localization_util/diagnostics_module.hpp"

Expand All @@ -26,6 +26,8 @@

#include <memory>

namespace autoware::pose_initializer
{
class StopCheckModule;
class LocalizationModule;
class GnssModule;
Expand Down Expand Up @@ -69,5 +71,6 @@ class PoseInitializer : public rclcpp::Node
const Initialize::Service::Response::SharedPtr res);
PoseWithCovarianceStamped get_gnss_pose();
};
} // namespace autoware::pose_initializer

#endif // POSE_INITIALIZER__POSE_INITIALIZER_CORE_HPP_
#endif // POSE_INITIALIZER_CORE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@

#include "stop_check_module.hpp"

namespace autoware::pose_initializer
{
StopCheckModule::StopCheckModule(rclcpp::Node * node, double buffer_duration)
: VehicleStopCheckerBase(node, buffer_duration)
{
Expand All @@ -28,3 +30,4 @@ void StopCheckModule::on_twist(TwistWithCovarianceStamped::ConstSharedPtr msg)
twist.twist = msg->twist.twist;
addTwist(twist);
}
} // namespace autoware::pose_initializer
Loading

0 comments on commit 03f675e

Please sign in to comment.