Skip to content

Commit

Permalink
Merge pull request autowarefoundation#172 from tier4/sync-upstream
Browse files Browse the repository at this point in the history
chore: sync upstream
  • Loading branch information
tier4-autoware-public-bot[bot] committed Nov 10, 2022
2 parents 87d8680 + 536a958 commit 7c576ef
Show file tree
Hide file tree
Showing 78 changed files with 1,828 additions and 1,416 deletions.
6 changes: 3 additions & 3 deletions .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ common/path_distance_calculator/** isamu.takagi@tier4.jp
common/perception_utils/** satoshi.tanaka@tier4.jp shunsuke.miura@tier4.jp takayuki.murooka@tier4.jp yusuke.muramatsu@tier4.jp
common/polar_grid/** yukihiro.saito@tier4.jp
common/rtc_manager_rviz_plugin/** taiki.tanaka@tier4.jp
common/signal_processing/** takayuki.murooka@tier4.jp
common/signal_processing/** ali.boyali@tier4.jp takayuki.murooka@tier4.jp
common/tier4_api_utils/** isamu.takagi@tier4.jp
common/tier4_autoware_utils/** kenji.miyake@tier4.jp takamasa.horibe@tier4.jp
common/tier4_calibration_rviz_plugin/** tomoya.kimura@tier4.jp
Expand All @@ -44,7 +44,6 @@ common/tier4_vehicle_rviz_plugin/** yukihiro.saito@tier4.jp
common/time_utils/** christopherj.ho@gmail.com
common/trtexec_vendor/** daisuke.nishimatsu@tier4.jp
common/tvm_utility/** ambroise.vincent@arm.com
common/vehicle_constants_manager/** mfc@leodrive.ai
common/web_controller/** yukihiro.saito@tier4.jp
control/control_performance_analysis/** ali.boyali@tier4.jp berkay@leodrive.ai
control/external_cmd_selector/** kenji.miyake@tier4.jp
Expand Down Expand Up @@ -78,7 +77,7 @@ localization/pose2twist/** yamato.ando@tier4.jp
localization/pose_initializer/** isamu.takagi@tier4.jp yamato.ando@tier4.jp
localization/stop_filter/** koji.minoda@tier4.jp yamato.ando@tier4.jp
localization/twist2accel/** koji.minoda@tier4.jp yamato.ando@tier4.jp
map/map_loader/** kenji.miyake@tier4.jp ryohsuke.mitsudome@tier4.jp
map/map_loader/** koji.minoda@tier4.jp ryohsuke.mitsudome@tier4.jp ryu.yamamoto@tier4.jp
map/map_tf_generator/** azumi.suzuki@tier4.jp
map/util/lanelet2_map_preprocessor/** ryohsuke.mitsudome@tier4.jp
perception/compare_map_segmentation/** abrahammonrroy@yahoo.com yukihiro.saito@tier4.jp
Expand Down Expand Up @@ -121,6 +120,7 @@ planning/motion_velocity_smoother/** fumiya.watanabe@tier4.jp
planning/obstacle_avoidance_planner/** takayuki.murooka@tier4.jp
planning/obstacle_cruise_planner/** takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp
planning/obstacle_stop_planner/** satoshi.ota@tier4.jp
planning/obstacle_velocity_limiter/** maxime.clement@tier4.jp
planning/planning_debug_tools/** taiki.tanaka@tier4.jp takamasa.horibe@tier4.jp
planning/planning_error_monitor/** yutaka.shimizu@tier4.jp
planning/planning_evaluator/** maxime.clement@tier4.jp
Expand Down
131 changes: 131 additions & 0 deletions common/perception_utils/test/src/test_object_classification.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,137 @@ TEST(object_classification, test_getHighestProbLabel)
}
}

// Test isVehicle
TEST(object_classification, test_isVehicle)
{
using autoware_auto_perception_msgs::msg::ObjectClassification;
using perception_utils::isVehicle;

{ // True Case with uint8_t
EXPECT_TRUE(isVehicle(ObjectClassification::BICYCLE));
EXPECT_TRUE(isVehicle(ObjectClassification::BUS));
EXPECT_TRUE(isVehicle(ObjectClassification::CAR));
EXPECT_TRUE(isVehicle(ObjectClassification::MOTORCYCLE));
EXPECT_TRUE(isVehicle(ObjectClassification::TRAILER));
EXPECT_TRUE(isVehicle(ObjectClassification::TRUCK));
}

// False Case with uint8_t
{
EXPECT_FALSE(isVehicle(ObjectClassification::UNKNOWN));
EXPECT_FALSE(isVehicle(ObjectClassification::PEDESTRIAN));
}

// True Case with object_classifications
{ // normal case
std::vector<autoware_auto_perception_msgs::msg::ObjectClassification> classification;
classification.push_back(createObjectClassification(ObjectClassification::CAR, 0.5));
classification.push_back(createObjectClassification(ObjectClassification::TRUCK, 0.8));
classification.push_back(createObjectClassification(ObjectClassification::BUS, 0.7));
EXPECT_TRUE(isVehicle(classification));
}

// False Case with object_classifications
{ // false case
std::vector<autoware_auto_perception_msgs::msg::ObjectClassification> classification;
classification.push_back(createObjectClassification(ObjectClassification::PEDESTRIAN, 0.8));
classification.push_back(createObjectClassification(ObjectClassification::BICYCLE, 0.7));
EXPECT_FALSE(isVehicle(classification));
}
} // TEST isVehicle

// TEST isCarLikeVehicle
TEST(object_classification, test_isCarLikeVehicle)
{
using autoware_auto_perception_msgs::msg::ObjectClassification;
using perception_utils::isCarLikeVehicle;

{ // True Case with uint8_t
EXPECT_TRUE(isCarLikeVehicle(ObjectClassification::BUS));
EXPECT_TRUE(isCarLikeVehicle(ObjectClassification::CAR));
EXPECT_TRUE(isCarLikeVehicle(ObjectClassification::TRAILER));
EXPECT_TRUE(isCarLikeVehicle(ObjectClassification::TRUCK));
}

// False Case with uint8_t
{
EXPECT_FALSE(isCarLikeVehicle(ObjectClassification::UNKNOWN));
EXPECT_FALSE(isCarLikeVehicle(ObjectClassification::BICYCLE));
EXPECT_FALSE(isCarLikeVehicle(ObjectClassification::PEDESTRIAN));
EXPECT_FALSE(isCarLikeVehicle(ObjectClassification::MOTORCYCLE));
}

// True Case with object_classifications
{ // normal case
std::vector<autoware_auto_perception_msgs::msg::ObjectClassification> classification;
classification.push_back(createObjectClassification(ObjectClassification::CAR, 0.5));
classification.push_back(createObjectClassification(ObjectClassification::TRUCK, 0.8));
classification.push_back(createObjectClassification(ObjectClassification::BICYCLE, 0.7));
EXPECT_TRUE(isCarLikeVehicle(classification));
}

// False Case with object_classifications
{ // false case
std::vector<autoware_auto_perception_msgs::msg::ObjectClassification> classification;
classification.push_back(createObjectClassification(ObjectClassification::MOTORCYCLE, 0.8));
classification.push_back(createObjectClassification(ObjectClassification::BICYCLE, 0.8));
EXPECT_FALSE(isCarLikeVehicle(classification));
}

// Edge case
// When classification has more multiple labels with same maximum probability
// getHighestProbLabel() returns only first highest-scored label.
// so, in edge case it returns a label earlier added.
{ // When car and non-car label has same probability
std::vector<autoware_auto_perception_msgs::msg::ObjectClassification> classification;
classification.push_back(createObjectClassification(ObjectClassification::MOTORCYCLE, 0.8));
classification.push_back(createObjectClassification(ObjectClassification::CAR, 0.8));
EXPECT_FALSE(
isCarLikeVehicle(classification)); // evaluated with earlier appended "MOTORCYCLE" label
}
} // TEST isCarLikeVehicle

// TEST isLargeVehicle
TEST(object_classification, test_isLargeVehicle)
{
using autoware_auto_perception_msgs::msg::ObjectClassification;
using perception_utils::isLargeVehicle;

{ // True Case with uint8_t
EXPECT_TRUE(isLargeVehicle(ObjectClassification::BUS));
EXPECT_TRUE(isLargeVehicle(ObjectClassification::TRAILER));
EXPECT_TRUE(isLargeVehicle(ObjectClassification::TRUCK));
}

// False Case with uint8_t
{
EXPECT_FALSE(isLargeVehicle(ObjectClassification::UNKNOWN));
EXPECT_FALSE(isLargeVehicle(ObjectClassification::BICYCLE));
EXPECT_FALSE(isLargeVehicle(ObjectClassification::PEDESTRIAN));
EXPECT_FALSE(isLargeVehicle(ObjectClassification::MOTORCYCLE));
EXPECT_FALSE(isLargeVehicle(ObjectClassification::CAR));
}

{ // false case
std::vector<autoware_auto_perception_msgs::msg::ObjectClassification> classification;
classification.push_back(createObjectClassification(ObjectClassification::MOTORCYCLE, 0.8));
classification.push_back(createObjectClassification(ObjectClassification::BICYCLE, 0.8));
classification.push_back(createObjectClassification(ObjectClassification::CAR, 0.8));
EXPECT_FALSE(isLargeVehicle(classification));
}

// Edge case
// When classification has more multiple labels with same maximum probability
// getHighestProbLabel() returns only first highest-scored label.
// so, in edge case it returns a label earlier added.
{ // When large-vehicle and non-large-vehicle label has same probability
std::vector<autoware_auto_perception_msgs::msg::ObjectClassification> classification;
classification.push_back(createObjectClassification(ObjectClassification::BUS, 0.8));
classification.push_back(createObjectClassification(ObjectClassification::CAR, 0.8));
EXPECT_TRUE(isLargeVehicle(classification)); // evaluated with earlier appended "BUS" label
}
} // TEST isLargeVehicle

TEST(object_classification, test_getHighestProbClassification)
{
using autoware_auto_perception_msgs::msg::ObjectClassification;
Expand Down
1 change: 1 addition & 0 deletions common/tier4_autoware_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ find_package(Boost REQUIRED)
ament_auto_add_library(tier4_autoware_utils SHARED
src/tier4_autoware_utils.cpp
src/geometry/boost_polygon_utils.cpp
src/ros/msg_operation.cpp
)

if(BUILD_TESTING)
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
// Copyright 2022 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TIER4_AUTOWARE_UTILS__ROS__MSG_OPERATION_HPP_
#define TIER4_AUTOWARE_UTILS__ROS__MSG_OPERATION_HPP_

#include "geometry_msgs/msg/quaternion.hpp"

// NOTE: Do not use tier4_autoware_utils namespace
namespace geometry_msgs
{
namespace msg
{
Quaternion operator+(Quaternion a, Quaternion b) noexcept;
Quaternion operator-(Quaternion a) noexcept;
Quaternion operator-(Quaternion a, Quaternion b) noexcept;
} // namespace msg
} // namespace geometry_msgs

#endif // TIER4_AUTOWARE_UTILS__ROS__MSG_OPERATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
#include "tier4_autoware_utils/ros/debug_traits.hpp"
#include "tier4_autoware_utils/ros/marker_helper.hpp"
#include "tier4_autoware_utils/ros/msg_covariance.hpp"
#include "tier4_autoware_utils/ros/msg_operation.hpp"
#include "tier4_autoware_utils/ros/processing_time_publisher.hpp"
#include "tier4_autoware_utils/ros/self_pose_listener.hpp"
#include "tier4_autoware_utils/ros/transform_listener.hpp"
Expand Down
55 changes: 55 additions & 0 deletions common/tier4_autoware_utils/src/ros/msg_operation.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
// Copyright 2022 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "tier4_autoware_utils/ros/msg_operation.hpp"

#include <tf2/utils.h>

#ifdef ROS_DISTRO_GALACTIC
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

// NOTE: Do not use tier4_autoware_utils namespace
namespace geometry_msgs
{
namespace msg
{
Quaternion operator+(Quaternion a, Quaternion b) noexcept
{
tf2::Quaternion quat_a;
tf2::Quaternion quat_b;
tf2::fromMsg(a, quat_a);
tf2::fromMsg(b, quat_b);
return tf2::toMsg(quat_a + quat_b);
}

Quaternion operator-(Quaternion a) noexcept
{
tf2::Quaternion quat_a;
tf2::fromMsg(a, quat_a);
return tf2::toMsg(quat_a * -1.0);
}

Quaternion operator-(Quaternion a, Quaternion b) noexcept
{
tf2::Quaternion quat_a;
tf2::Quaternion quat_b;
tf2::fromMsg(a, quat_a);
tf2::fromMsg(b, quat_b);
return tf2::toMsg(quat_a * quat_b.inverse());
}
} // namespace msg
} // namespace geometry_msgs
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
#ifndef TRAJECTORY_FOLLOWER__DEBUG_VALUES_HPP_
#define TRAJECTORY_FOLLOWER__DEBUG_VALUES_HPP_

#include "common/types.hpp"
#include "trajectory_follower/visibility_control.hpp"

#include <array>
Expand All @@ -28,7 +27,7 @@ namespace control
{
namespace trajectory_follower
{
using autoware::common::types::float64_t;

/// Debug Values used for debugging or controller tuning
class TRAJECTORY_FOLLOWER_PUBLIC DebugValues
{
Expand Down Expand Up @@ -77,13 +76,13 @@ class TRAJECTORY_FOLLOWER_PUBLIC DebugValues
* @brief get all the debug values as an std::array
* @return array of all debug values
*/
std::array<float64_t, static_cast<size_t>(TYPE::SIZE)> getValues() const { return m_values; }
std::array<double, static_cast<size_t>(TYPE::SIZE)> getValues() const { return m_values; }
/**
* @brief set the given type to the given value
* @param [in] type TYPE of the value
* @param [in] value value to set
*/
void setValues(const TYPE type, const float64_t value)
void setValues(const TYPE type, const double value)
{
m_values.at(static_cast<size_t>(type)) = value;
}
Expand All @@ -92,10 +91,10 @@ class TRAJECTORY_FOLLOWER_PUBLIC DebugValues
* @param [in] type index of the type
* @param [in] value value to set
*/
void setValues(const size_t type, const float64_t value) { m_values.at(type) = value; }
void setValues(const size_t type, const double value) { m_values.at(type) = value; }

private:
std::array<float64_t, static_cast<size_t>(TYPE::SIZE)> m_values;
std::array<double, static_cast<size_t>(TYPE::SIZE)> m_values;
};
} // namespace trajectory_follower
} // namespace control
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
#ifndef TRAJECTORY_FOLLOWER__INTERPOLATE_HPP_
#define TRAJECTORY_FOLLOWER__INTERPOLATE_HPP_

#include "common/types.hpp"
#include "trajectory_follower/visibility_control.hpp"

#include <cmath>
Expand All @@ -30,28 +29,27 @@ namespace control
{
namespace trajectory_follower
{
using autoware::common::types::bool8_t;
using autoware::common::types::float64_t;

/**
* @brief linearly interpolate the given values assuming a base indexing and a new desired indexing
* @param [in] base_index indexes for each base value
* @param [in] base_value values for each base index
* @param [in] return_index desired interpolated indexes
* @param [out] return_value resulting interpolated values
*/
TRAJECTORY_FOLLOWER_PUBLIC bool8_t linearInterpolate(
const std::vector<float64_t> & base_index, const std::vector<float64_t> & base_value,
const std::vector<float64_t> & return_index, std::vector<float64_t> & return_value);
TRAJECTORY_FOLLOWER_PUBLIC bool linearInterpolate(
const std::vector<double> & base_index, const std::vector<double> & base_value,
const std::vector<double> & return_index, std::vector<double> & return_value);
/**
* @brief linearly interpolate the given values assuming a base indexing and a new desired index
* @param [in] base_index indexes for each base value
* @param [in] base_value values for each base index
* @param [in] return_index desired interpolated index
* @param [out] return_value resulting interpolated value
*/
TRAJECTORY_FOLLOWER_PUBLIC bool8_t linearInterpolate(
const std::vector<float64_t> & base_index, const std::vector<float64_t> & base_value,
const float64_t & return_index, float64_t & return_value);
TRAJECTORY_FOLLOWER_PUBLIC bool linearInterpolate(
const std::vector<double> & base_index, const std::vector<double> & base_value,
const double & return_index, double & return_value);
} // namespace trajectory_follower
} // namespace control
} // namespace motion
Expand Down
Loading

0 comments on commit 7c576ef

Please sign in to comment.