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

refactor(autoware_interpolation): prefix package and namespace with autoware #8088

Merged
merged 7 commits into from
Sep 20, 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
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
cmake_minimum_required(VERSION 3.14)
project(interpolation)
project(autoware_interpolation)

find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_add_library(interpolation SHARED
ament_auto_add_library(autoware_interpolation SHARED
src/linear_interpolation.cpp
src/spline_interpolation.cpp
src/spline_interpolation_points_2d.cpp
Expand All @@ -17,7 +17,7 @@ if(BUILD_TESTING)
ament_add_ros_isolated_gtest(test_interpolation ${test_files})

target_link_libraries(test_interpolation
interpolation
autoware_interpolation
)
endif()

Expand Down
File renamed without changes.
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef INTERPOLATION__INTERPOLATION_UTILS_HPP_
#define INTERPOLATION__INTERPOLATION_UTILS_HPP_
#ifndef AUTOWARE__INTERPOLATION__INTERPOLATION_UTILS_HPP_
#define AUTOWARE__INTERPOLATION__INTERPOLATION_UTILS_HPP_

#include <algorithm>
#include <array>
#include <stdexcept>
#include <vector>

namespace interpolation_utils
namespace autoware::interpolation
{
inline bool isIncreasing(const std::vector<double> & x)
{
Expand Down Expand Up @@ -109,6 +109,6 @@ void validateKeysAndValues(
throw std::invalid_argument("The size of base_keys and base_values are not the same.");
}
}
} // namespace interpolation_utils
} // namespace autoware::interpolation

#endif // INTERPOLATION__INTERPOLATION_UTILS_HPP_
#endif // AUTOWARE__INTERPOLATION__INTERPOLATION_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef INTERPOLATION__LINEAR_INTERPOLATION_HPP_
#define INTERPOLATION__LINEAR_INTERPOLATION_HPP_
#ifndef AUTOWARE__INTERPOLATION__LINEAR_INTERPOLATION_HPP_
#define AUTOWARE__INTERPOLATION__LINEAR_INTERPOLATION_HPP_

#include "interpolation/interpolation_utils.hpp"
#include "autoware/interpolation/interpolation_utils.hpp"

#include <vector>

namespace interpolation
namespace autoware::interpolation
{
double lerp(const double src_val, const double dst_val, const double ratio);

Expand All @@ -30,7 +30,6 @@ std::vector<double> lerp(
double lerp(
const std::vector<double> & base_keys, const std::vector<double> & base_values,
const double query_key);
} // namespace autoware::interpolation

} // namespace interpolation

#endif // INTERPOLATION__LINEAR_INTERPOLATION_HPP_
#endif // AUTOWARE__INTERPOLATION__LINEAR_INTERPOLATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef INTERPOLATION__SPHERICAL_LINEAR_INTERPOLATION_HPP_
#define INTERPOLATION__SPHERICAL_LINEAR_INTERPOLATION_HPP_
#ifndef AUTOWARE__INTERPOLATION__SPHERICAL_LINEAR_INTERPOLATION_HPP_
#define AUTOWARE__INTERPOLATION__SPHERICAL_LINEAR_INTERPOLATION_HPP_

#include "interpolation/interpolation_utils.hpp"
#include "autoware/interpolation/interpolation_utils.hpp"

#include <geometry_msgs/msg/quaternion.hpp>

Expand All @@ -29,7 +29,7 @@

#include <vector>

namespace interpolation
namespace autoware::interpolation
{
geometry_msgs::msg::Quaternion slerp(
const geometry_msgs::msg::Quaternion & src_quat, const geometry_msgs::msg::Quaternion & dst_quat,
Expand All @@ -43,6 +43,6 @@ std::vector<geometry_msgs::msg::Quaternion> slerp(
geometry_msgs::msg::Quaternion lerpOrientation(
const geometry_msgs::msg::Quaternion & o_from, const geometry_msgs::msg::Quaternion & o_to,
const double ratio);
} // namespace interpolation
} // namespace autoware::interpolation

#endif // INTERPOLATION__SPHERICAL_LINEAR_INTERPOLATION_HPP_
#endif // AUTOWARE__INTERPOLATION__SPHERICAL_LINEAR_INTERPOLATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,11 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef INTERPOLATION__SPLINE_INTERPOLATION_HPP_
#define INTERPOLATION__SPLINE_INTERPOLATION_HPP_
#ifndef AUTOWARE__INTERPOLATION__SPLINE_INTERPOLATION_HPP_
#define AUTOWARE__INTERPOLATION__SPLINE_INTERPOLATION_HPP_

#include "autoware/interpolation/interpolation_utils.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "interpolation/interpolation_utils.hpp"

#include <Eigen/Core>

Expand All @@ -26,7 +26,7 @@
#include <numeric>
#include <vector>

namespace interpolation
namespace autoware::interpolation
{
// static spline interpolation functions
std::vector<double> spline(
Expand All @@ -35,7 +35,6 @@ std::vector<double> spline(
std::vector<double> splineByAkima(
const std::vector<double> & base_keys, const std::vector<double> & base_values,
const std::vector<double> & query_keys);
} // namespace interpolation

// non-static 1-dimensional spline interpolation
//
Expand Down Expand Up @@ -93,5 +92,6 @@ class SplineInterpolation

Eigen::Index get_index(const double & key) const;
};
} // namespace autoware::interpolation

#endif // INTERPOLATION__SPLINE_INTERPOLATION_HPP_
#endif // AUTOWARE__INTERPOLATION__SPLINE_INTERPOLATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,19 +12,18 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef INTERPOLATION__SPLINE_INTERPOLATION_POINTS_2D_HPP_
#define INTERPOLATION__SPLINE_INTERPOLATION_POINTS_2D_HPP_
#ifndef AUTOWARE__INTERPOLATION__SPLINE_INTERPOLATION_POINTS_2D_HPP_
#define AUTOWARE__INTERPOLATION__SPLINE_INTERPOLATION_POINTS_2D_HPP_

#include "interpolation/spline_interpolation.hpp"
#include "autoware/interpolation/spline_interpolation.hpp"

#include <vector>

namespace interpolation
namespace autoware::interpolation
{

template <typename T>
std::vector<double> splineYawFromPoints(const std::vector<T> & points);
} // namespace interpolation

// non-static points spline interpolation
// NOTE: We can calculate yaw from the x and y by interpolation derivatives.
Expand Down Expand Up @@ -85,5 +84,6 @@ class SplineInterpolationPoints2d

std::vector<double> base_s_vec_;
};
} // namespace autoware::interpolation

#endif // INTERPOLATION__SPLINE_INTERPOLATION_POINTS_2D_HPP_
#endif // AUTOWARE__INTERPOLATION__SPLINE_INTERPOLATION_POINTS_2D_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,21 +12,21 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef INTERPOLATION__ZERO_ORDER_HOLD_HPP_
#define INTERPOLATION__ZERO_ORDER_HOLD_HPP_
#ifndef AUTOWARE__INTERPOLATION__ZERO_ORDER_HOLD_HPP_
#define AUTOWARE__INTERPOLATION__ZERO_ORDER_HOLD_HPP_

#include "interpolation/interpolation_utils.hpp"
#include "autoware/interpolation/interpolation_utils.hpp"

#include <vector>

namespace interpolation
namespace autoware::interpolation
{
inline std::vector<size_t> calc_closest_segment_indices(
const std::vector<double> & base_keys, const std::vector<double> & query_keys,
const double overlap_threshold = 1e-3)
{
// throw exception for invalid arguments
const auto validated_query_keys = interpolation_utils::validateKeys(base_keys, query_keys);
const auto validated_query_keys = validateKeys(base_keys, query_keys);

std::vector<size_t> closest_segment_indices(validated_query_keys.size());
size_t closest_segment_idx = 0;
Expand Down Expand Up @@ -58,7 +58,7 @@ std::vector<T> zero_order_hold(
const std::vector<size_t> & closest_segment_indices)
{
// throw exception for invalid arguments
interpolation_utils::validateKeysAndValues(base_keys, base_values);
validateKeysAndValues(base_keys, base_values);

std::vector<T> query_values(closest_segment_indices.size());
for (size_t i = 0; i < closest_segment_indices.size(); ++i) {
Expand All @@ -76,6 +76,6 @@ std::vector<T> zero_order_hold(
return zero_order_hold(
base_keys, base_values, calc_closest_segment_indices(base_keys, query_keys, overlap_threshold));
}
} // namespace interpolation
} // namespace autoware::interpolation

#endif // INTERPOLATION__ZERO_ORDER_HOLD_HPP_
#endif // AUTOWARE__INTERPOLATION__ZERO_ORDER_HOLD_HPP_
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?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>interpolation</name>
<name>autoware_interpolation</name>
<version>0.1.0</version>
<description>The spline interpolation package</description>
<maintainer email="[email protected]">Fumiya Watanabe</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,11 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "interpolation/linear_interpolation.hpp"
#include "autoware/interpolation/linear_interpolation.hpp"

#include <vector>

namespace interpolation
namespace autoware::interpolation
{
double lerp(const double src_val, const double dst_val, const double ratio)
{
Expand All @@ -28,8 +28,8 @@ std::vector<double> lerp(
const std::vector<double> & query_keys)
{
// throw exception for invalid arguments
const auto validated_query_keys = interpolation_utils::validateKeys(base_keys, query_keys);
interpolation_utils::validateKeysAndValues(base_keys, base_values);
const auto validated_query_keys = validateKeys(base_keys, query_keys);
validateKeysAndValues(base_keys, base_values);

// calculate linear interpolation
std::vector<double> query_values;
Expand All @@ -56,4 +56,4 @@ double lerp(
{
return lerp(base_keys, base_values, std::vector<double>{query_key}).front();
}
} // namespace interpolation
} // namespace autoware::interpolation
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,9 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "interpolation/spherical_linear_interpolation.hpp"
#include "autoware/interpolation/spherical_linear_interpolation.hpp"

namespace interpolation
namespace autoware::interpolation
{
geometry_msgs::msg::Quaternion slerp(
const geometry_msgs::msg::Quaternion & src_quat, const geometry_msgs::msg::Quaternion & dst_quat,
Expand All @@ -34,8 +34,8 @@ std::vector<geometry_msgs::msg::Quaternion> slerp(
const std::vector<double> & query_keys)
{
// throw exception for invalid arguments
const auto validated_query_keys = interpolation_utils::validateKeys(base_keys, query_keys);
interpolation_utils::validateKeysAndValues(base_keys, base_values);
const auto validated_query_keys = validateKeys(base_keys, query_keys);
validateKeysAndValues(base_keys, base_values);

// calculate linear interpolation
std::vector<geometry_msgs::msg::Quaternion> query_values;
Expand Down Expand Up @@ -68,4 +68,4 @@ geometry_msgs::msg::Quaternion lerpOrientation(
const auto q_interpolated = q_from.slerp(q_to, ratio);
return tf2::toMsg(q_interpolated);
}
} // namespace interpolation
} // namespace autoware::interpolation
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "interpolation/spline_interpolation.hpp"
#include "autoware/interpolation/spline_interpolation.hpp"

#include <cstdint>
#include <vector>

namespace
namespace autoware::interpolation
{
Eigen::VectorXd solve_tridiagonal_matrix_algorithm(
const Eigen::Ref<const Eigen::VectorXd> & a, const Eigen::Ref<const Eigen::VectorXd> & b,
Expand Down Expand Up @@ -52,10 +52,7 @@ Eigen::VectorXd solve_tridiagonal_matrix_algorithm(

return x;
}
} // namespace

namespace interpolation
{
std::vector<double> spline(
const std::vector<double> & base_keys, const std::vector<double> & base_values,
const std::vector<double> & query_keys)
Expand Down Expand Up @@ -139,7 +136,6 @@ std::vector<double> splineByAkima(
}
return res;
}
} // namespace interpolation

Eigen::Index SplineInterpolation::get_index(const double & key) const
{
Expand All @@ -153,7 +149,7 @@ void SplineInterpolation::calcSplineCoefficients(
const std::vector<double> & base_keys, const std::vector<double> & base_values)
{
// throw exceptions for invalid arguments
interpolation_utils::validateKeysAndValues(base_keys, base_values);
autoware::interpolation::validateKeysAndValues(base_keys, base_values);
const Eigen::VectorXd x = Eigen::Map<const Eigen::VectorXd>(
base_keys.data(), static_cast<Eigen::Index>(base_keys.size()));
const Eigen::VectorXd y = Eigen::Map<const Eigen::VectorXd>(
Expand Down Expand Up @@ -201,7 +197,7 @@ std::vector<double> SplineInterpolation::getSplineInterpolatedValues(
const std::vector<double> & query_keys) const
{
// throw exceptions for invalid arguments
const auto validated_query_keys = interpolation_utils::validateKeys(base_keys_, query_keys);
const auto validated_query_keys = autoware::interpolation::validateKeys(base_keys_, query_keys);
std::vector<double> interpolated_values;
interpolated_values.reserve(query_keys.size());

Expand All @@ -219,7 +215,7 @@ std::vector<double> SplineInterpolation::getSplineInterpolatedDiffValues(
const std::vector<double> & query_keys) const
{
// throw exceptions for invalid arguments
const auto validated_query_keys = interpolation_utils::validateKeys(base_keys_, query_keys);
const auto validated_query_keys = autoware::interpolation::validateKeys(base_keys_, query_keys);
std::vector<double> interpolated_diff_values;
interpolated_diff_values.reserve(query_keys.size());

Expand All @@ -236,7 +232,7 @@ std::vector<double> SplineInterpolation::getSplineInterpolatedQuadDiffValues(
const std::vector<double> & query_keys) const
{
// throw exceptions for invalid arguments
const auto validated_query_keys = interpolation_utils::validateKeys(base_keys_, query_keys);
const auto validated_query_keys = autoware::interpolation::validateKeys(base_keys_, query_keys);
std::vector<double> interpolated_quad_diff_values;
interpolated_quad_diff_values.reserve(query_keys.size());

Expand All @@ -248,3 +244,4 @@ std::vector<double> SplineInterpolation::getSplineInterpolatedQuadDiffValues(

return interpolated_quad_diff_values;
}
} // namespace autoware::interpolation
Loading
Loading