Skip to content

Commit

Permalink
fix(map based prediction): suppress warnings (autowarefoundation#296)
Browse files Browse the repository at this point in the history
* feat: add Werror

Signed-off-by: h-ohta <[email protected]>

* fix: suppress warnings

Signed-off-by: h-ohta <[email protected]>

* fix: still use RCLCPP_ERROR

Signed-off-by: h-ohta <[email protected]>

* fix: add const

Signed-off-by: h-ohta <[email protected]>
  • Loading branch information
h-ohta authored and satoshi-ota committed May 20, 2022
1 parent 6668c0e commit 0b1d612
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 7 deletions.
2 changes: 1 addition & 1 deletion perception/map_based_prediction/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_EXTENSIONS OFF)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
add_compile_options(-Wall -Wextra -Wpedantic -Werror)
endif()

find_package(ament_cmake_auto REQUIRED)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,11 +48,11 @@ class MapBasedPrediction
const double height, const double current_d_position, const double current_d_velocity,
const double current_s_position, const double current_s_velocity,
const std_msgs::msg::Header & origin_header, Spline2D & spline2d,
autoware_auto_perception_msgs::msg::PredictedPath & path);
autoware_auto_perception_msgs::msg::PredictedPath & path) const;

void getLinearPredictedPath(
const geometry_msgs::msg::Pose & object_pose, const geometry_msgs::msg::Twist & object_twist,
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path);
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path) const;

void normalizeLikelihood(
autoware_auto_perception_msgs::msg::PredictedObjectKinematics & predicted_object_kinematics);
Expand Down
6 changes: 3 additions & 3 deletions perception/map_based_prediction/src/map_based_prediction.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -192,8 +192,8 @@ void MapBasedPrediction::normalizeLikelihood(
bool MapBasedPrediction::getPredictedPath(
const double height, const double current_d_position, const double current_d_velocity,
const double current_s_position, const double current_s_velocity,
const std_msgs::msg::Header & origin_header, Spline2D & spline2d,
autoware_auto_perception_msgs::msg::PredictedPath & path)
[[maybe_unused]] const std_msgs::msg::Header & origin_header, Spline2D & spline2d,
autoware_auto_perception_msgs::msg::PredictedPath & path) const
{
// Quintic polynomial for d
// A = np.array([[T**3, T**4, T**5],
Expand Down Expand Up @@ -269,7 +269,7 @@ bool MapBasedPrediction::getPredictedPath(

void MapBasedPrediction::getLinearPredictedPath(
const geometry_msgs::msg::Pose & object_pose, const geometry_msgs::msg::Twist & object_twist,
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path)
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path) const
{
const double & sampling_delta_time = sampling_delta_time_;
const double & time_horizon = time_horizon_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -557,7 +557,7 @@ void MapBasedPredictionROS::objectsCallback(
"map", // src
rclcpp::Time(), rclcpp::Duration::from_seconds(0.1));
} catch (tf2::TransformException & ex) {
RCLCPP_ERROR(get_logger(), ex.what());
RCLCPP_ERROR(get_logger(), "%s", ex.what());
return;
}

Expand Down

0 comments on commit 0b1d612

Please sign in to comment.