Skip to content

Commit

Permalink
feat: apply autoware_ prefix for evaluator/kinematic_evaluator (a…
Browse files Browse the repository at this point in the history
…utowarefoundation#9936)

Signed-off-by: Junya Sasaki <junya.sasaki@tier4.jp>
Signed-off-by: Ryohsuke Mitsudome <ryohsuke.mitsudome@tier4.jp>
  • Loading branch information
sasakisasaki authored Jan 24, 2025
1 parent de92439 commit 5872113
Show file tree
Hide file tree
Showing 19 changed files with 79 additions and 77 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ control/control_performance_analysis/** berkay@leodrive.ai fumiya.watanabe@tier4
control/predicted_path_checker/** berkay@leodrive.ai
evaluator/autoware_control_evaluator/** daniel.sanchez@tier4.jp kosuke.takeuchi@tier4.jp takayuki.murooka@tier4.jp temkei.kem@tier4.jp
evaluator/autoware_planning_evaluator/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp temkei.kem@tier4.jp
evaluator/kinematic_evaluator/** dominik.jargot@robotec.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp
evaluator/autoware_kinematic_evaluator/** dominik.jargot@robotec.ai fumiya.watanabe@tier4.jp satoshi.ota@tier4.jp shumpei.wakabayashi@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp tomoya.kimura@tier4.jp junya.sasaki@tier4.jp
evaluator/localization_evaluator/** anh.nguyen.2@tier4.jp dominik.jargot@robotec.ai koji.minoda@tier4.jp masahiro.sakamoto@tier4.jp shintaro.sakoda@tier4.jp taiki.yamada@tier4.jp yamato.ando@tier4.jp
evaluator/autoware_perception_online_evaluator/** fumiya.watanabe@tier4.jp kosuke.takeuchi@tier4.jp kotaro.uetake@tier4.jp kyoichi.sugahara@tier4.jp shunsuke.miura@tier4.jp yoshi.ri@tier4.jp junya.sasaki@tier4.jp
evaluator/scenario_simulator_v2_adapter/** kyoichi.sugahara@tier4.jp maxime.clement@tier4.jp takamasa.horibe@tier4.jp temkei.kem@tier4.jp
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package kinematic_evaluator
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package autoware_kinematic_evaluator
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.40.0 (2024-12-12)
-------------------
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(kinematic_evaluator)
project(autoware_kinematic_evaluator)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
Expand All @@ -15,26 +15,25 @@ autoware_package()
find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

ament_auto_add_library(${PROJECT_NAME}_node SHARED
ament_auto_add_library(${PROJECT_NAME} SHARED
src/metrics_calculator.cpp
src/${PROJECT_NAME}_node.cpp
src/kinematic_evaluator_node.cpp
src/metrics/kinematic_metrics.cpp
)

rclcpp_components_register_node(${PROJECT_NAME}_node
PLUGIN "kinematic_diagnostics::KinematicEvaluatorNode"
EXECUTABLE ${PROJECT_NAME}
rclcpp_components_register_node(${PROJECT_NAME}
PLUGIN "autoware::kinematic_diagnostics::KinematicEvaluatorNode"
EXECUTABLE ${PROJECT_NAME}_node
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
ament_add_gtest(test_${PROJECT_NAME}
ament_add_gtest(test_kinematic_evaluator
test/test_kinematic_evaluator_node.cpp
)
target_link_libraries(test_${PROJECT_NAME}
${PROJECT_NAME}_node
target_link_libraries(test_kinematic_evaluator
${PROJECT_NAME}
)
endif()

Expand Down
7 changes: 7 additions & 0 deletions evaluator/autoware_kinematic_evaluator/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# autoware_kinematic_evaluator

TBD

## Parameters

{{json_to_markdown("evaluator/autoware_kinematic_evaluator/schema/kinematic_evaluator.schema.json")}}
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 KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_HPP_
#define KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_HPP_
#ifndef AUTOWARE__KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_HPP_
#define AUTOWARE__KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_HPP_

#include "autoware/kinematic_evaluator/metrics_calculator.hpp"
#include "autoware/universe_utils/math/accumulator.hpp"
#include "kinematic_evaluator/metrics_calculator.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2_ros/buffer.h"
#include "tf2_ros/transform_listener.h"
Expand All @@ -31,7 +31,7 @@
#include <unordered_map>
#include <vector>

namespace kinematic_diagnostics
namespace autoware::kinematic_diagnostics
{
using autoware::universe_utils::Accumulator;
using diagnostic_msgs::msg::DiagnosticArray;
Expand Down Expand Up @@ -78,6 +78,6 @@ class KinematicEvaluatorNode : public rclcpp::Node
std::array<std::deque<Accumulator<double>>, static_cast<size_t>(Metric::SIZE)> metric_stats_;
std::unordered_map<Metric, Accumulator<double>> metrics_dict_;
};
} // namespace kinematic_diagnostics
} // namespace autoware::kinematic_diagnostics

#endif // KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_HPP_
#endif // AUTOWARE__KINEMATIC_EVALUATOR__KINEMATIC_EVALUATOR_NODE_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 KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_
#define KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_
#ifndef AUTOWARE__KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_
#define AUTOWARE__KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_

#include "autoware/universe_utils/math/accumulator.hpp"

#include <nav_msgs/msg/odometry.hpp>

namespace kinematic_diagnostics
namespace autoware::kinematic_diagnostics
{
namespace metrics
{
Expand All @@ -35,6 +35,6 @@ using nav_msgs::msg::Odometry;
Accumulator<double> updateVelocityStats(const double & value, const Accumulator<double> stat_prev);

} // namespace metrics
} // namespace kinematic_diagnostics
} // namespace autoware::kinematic_diagnostics

#endif // KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_
#endif // AUTOWARE__KINEMATIC_EVALUATOR__METRICS__KINEMATIC_METRICS_HPP_
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 KINEMATIC_EVALUATOR__METRICS__METRIC_HPP_
#define KINEMATIC_EVALUATOR__METRICS__METRIC_HPP_
#ifndef AUTOWARE__KINEMATIC_EVALUATOR__METRICS__METRIC_HPP_
#define AUTOWARE__KINEMATIC_EVALUATOR__METRICS__METRIC_HPP_

#include <iostream>
#include <string>
#include <unordered_map>
#include <vector>

namespace kinematic_diagnostics
namespace autoware::kinematic_diagnostics
{
/**
* @brief Enumeration of velocity metrics
Expand Down Expand Up @@ -57,6 +57,6 @@ static struct CheckCorrectMaps
} check;

} // namespace details
} // namespace kinematic_diagnostics
} // namespace autoware::kinematic_diagnostics

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

#ifndef KINEMATIC_EVALUATOR__METRICS_CALCULATOR_HPP_
#define KINEMATIC_EVALUATOR__METRICS_CALCULATOR_HPP_
#ifndef AUTOWARE__KINEMATIC_EVALUATOR__METRICS_CALCULATOR_HPP_
#define AUTOWARE__KINEMATIC_EVALUATOR__METRICS_CALCULATOR_HPP_

#include "autoware/kinematic_evaluator/metrics/metric.hpp"
#include "autoware/kinematic_evaluator/parameters.hpp"
#include "autoware/universe_utils/math/accumulator.hpp"
#include "kinematic_evaluator/metrics/metric.hpp"
#include "kinematic_evaluator/parameters.hpp"

#include "geometry_msgs/msg/pose.hpp"
#include <nav_msgs/msg/odometry.hpp>

namespace kinematic_diagnostics
namespace autoware::kinematic_diagnostics
{
using autoware::universe_utils::Accumulator;
using nav_msgs::msg::Odometry;
Expand Down Expand Up @@ -52,6 +52,6 @@ class MetricsCalculator
const Metric metric, const Odometry & odom, const Accumulator<double> stat_prev) const;
}; // class MetricsCalculator

} // namespace kinematic_diagnostics
} // namespace autoware::kinematic_diagnostics

#endif // KINEMATIC_EVALUATOR__METRICS_CALCULATOR_HPP_
#endif // AUTOWARE__KINEMATIC_EVALUATOR__METRICS_CALCULATOR_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 KINEMATIC_EVALUATOR__PARAMETERS_HPP_
#define KINEMATIC_EVALUATOR__PARAMETERS_HPP_
#ifndef AUTOWARE__KINEMATIC_EVALUATOR__PARAMETERS_HPP_
#define AUTOWARE__KINEMATIC_EVALUATOR__PARAMETERS_HPP_

#include "kinematic_evaluator/metrics/metric.hpp"
#include "autoware/kinematic_evaluator/metrics/metric.hpp"

#include <array>

namespace kinematic_diagnostics
namespace autoware::kinematic_diagnostics
{
/**
* @brief Enumeration of trajectory metrics
Expand All @@ -29,6 +29,6 @@ struct Parameters
std::array<bool, static_cast<size_t>(Metric::SIZE)> metrics{}; // default values to false
}; // struct Parameters

} // namespace kinematic_diagnostics
} // namespace autoware::kinematic_diagnostics

#endif // KINEMATIC_EVALUATOR__PARAMETERS_HPP_
#endif // AUTOWARE__KINEMATIC_EVALUATOR__PARAMETERS_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
<launch>
<arg name="input/twist" default="/localization/kinematic_state"/>

<node pkg="autoware_kinematic_evaluator" exec="autoware_kinematic_evaluator_node" output="screen">
<param from="$(find-pkg-share autoware_kinematic_evaluator)/param/kinematic_evaluator.defaults.yaml"/>
<remap from="~/input/twist" to="$(var input/twist)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0"?>
<package format="3">
<name>kinematic_evaluator</name>
<name>autoware_kinematic_evaluator</name>
<version>0.40.0</version>
<description>kinematic evaluator ROS 2 node</description>

Expand All @@ -11,6 +11,7 @@
<maintainer email="takayuki.murooka@tier4.jp">Takayuki Murooka</maintainer>
<maintainer email="fumiya.watanabe@tier4.jp">Fumiya Watanabe</maintainer>
<maintainer email="satoshi.ota@tier4.jp">Satoshi Ota</maintainer>
<maintainer email="junya.sasaki@tier4.jp">Junya Sasaki</maintainer>

<license>Apache License 2.0</license>

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

#include "kinematic_evaluator/kinematic_evaluator_node.hpp"
#include "autoware/kinematic_evaluator/kinematic_evaluator_node.hpp"

#include "boost/lexical_cast.hpp"

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

namespace kinematic_diagnostics
namespace autoware::kinematic_diagnostics
{
KinematicEvaluatorNode::KinematicEvaluatorNode(const rclcpp::NodeOptions & node_options)
: Node("kinematic_evaluator", node_options)
Expand Down Expand Up @@ -139,7 +139,7 @@ geometry_msgs::msg::Pose KinematicEvaluatorNode::getCurrentEgoPose() const
return p;
}

} // namespace kinematic_diagnostics
} // namespace autoware::kinematic_diagnostics

#include "rclcpp_components/register_node_macro.hpp"
RCLCPP_COMPONENTS_REGISTER_NODE(kinematic_diagnostics::KinematicEvaluatorNode)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::kinematic_diagnostics::KinematicEvaluatorNode)
Original file line number Diff line number Diff line change
Expand Up @@ -12,19 +12,20 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "kinematic_evaluator/metrics/kinematic_metrics.hpp"
#include "autoware/kinematic_evaluator/metrics/kinematic_metrics.hpp"

namespace kinematic_diagnostics
namespace autoware::kinematic_diagnostics
{
namespace metrics
{

Accumulator<double> updateVelocityStats(const double & value, const Accumulator<double> stat_prev)
autoware::universe_utils::Accumulator<double> updateVelocityStats(
const double & value, const autoware::universe_utils::Accumulator<double> stat_prev)
{
Accumulator<double> stat(stat_prev);
autoware::universe_utils::Accumulator<double> stat(stat_prev);
stat.add(value);
return stat;
}

} // namespace metrics
} // namespace kinematic_diagnostics
} // namespace autoware::kinematic_diagnostics
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 "kinematic_evaluator/metrics_calculator.hpp"
#include "autoware/kinematic_evaluator/metrics_calculator.hpp"

#include "kinematic_evaluator/metrics/kinematic_metrics.hpp"
#include "autoware/kinematic_evaluator/metrics/kinematic_metrics.hpp"

namespace kinematic_diagnostics
namespace autoware::kinematic_diagnostics
{
Accumulator<double> MetricsCalculator::updateStat(
const Metric metric, const Odometry & odom, const Accumulator<double> stat_prev) const
Expand All @@ -31,4 +31,4 @@ Accumulator<double> MetricsCalculator::updateStat(
}
}

} // namespace kinematic_diagnostics
} // namespace autoware::kinematic_diagnostics
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include "rclcpp/time.hpp"
#include "tf2_ros/transform_broadcaster.h"

#include <kinematic_evaluator/kinematic_evaluator_node.hpp>
#include <autoware/kinematic_evaluator/kinematic_evaluator_node.hpp>

#include "diagnostic_msgs/msg/diagnostic_array.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
Expand All @@ -32,7 +32,7 @@
#include <utility>
#include <vector>

using EvalNode = kinematic_diagnostics::KinematicEvaluatorNode;
using EvalNode = autoware::kinematic_diagnostics::KinematicEvaluatorNode;
using diagnostic_msgs::msg::DiagnosticArray;
using nav_msgs::msg::Odometry;

Expand All @@ -44,7 +44,8 @@ class EvalTest : public ::testing::Test
rclcpp::init(0, nullptr);

rclcpp::NodeOptions options;
const auto share_dir = ament_index_cpp::get_package_share_directory("kinematic_evaluator");
const auto share_dir =
ament_index_cpp::get_package_share_directory("autoware_kinematic_evaluator");
options.arguments(
{"--ros-args", "--params-file", share_dir + "/param/kinematic_evaluator.defaults.yaml"});

Expand All @@ -70,9 +71,9 @@ class EvalTest : public ::testing::Test

~EvalTest() override { /*rclcpp::shutdown();*/ }

void setTargetMetric(kinematic_diagnostics::Metric metric)
void setTargetMetric(autoware::kinematic_diagnostics::Metric metric)
{
const auto metric_str = kinematic_diagnostics::metric_to_str.at(metric);
const auto metric_str = autoware::kinematic_diagnostics::metric_to_str.at(metric);
const auto is_target_metric = [metric_str](const auto & status) {
return status.name == metric_str;
};
Expand Down Expand Up @@ -130,7 +131,7 @@ class EvalTest : public ::testing::Test

TEST_F(EvalTest, TestVelocityStats)
{
setTargetMetric(kinematic_diagnostics::Metric::velocity_stats);
setTargetMetric(autoware::kinematic_diagnostics::Metric::velocity_stats);
Odometry odom = makeOdometry(0.0);
EXPECT_DOUBLE_EQ(publishOdometryAndGetMetric(odom), 0.0);
Odometry odom2 = makeOdometry(1.0);
Expand Down
7 changes: 0 additions & 7 deletions evaluator/kinematic_evaluator/README.md

This file was deleted.

This file was deleted.

0 comments on commit 5872113

Please sign in to comment.