Skip to content

Commit

Permalink
fix(control performance analysis): suppress warnings (autowarefoundat…
Browse files Browse the repository at this point in the history
…ion#293)

* fix: delete unused variable

Signed-off-by: h-ohta <hiroki.ota@tier4.jp>

* feat: add Werror

Signed-off-by: h-ohta <hiroki.ota@tier4.jp>

* fix: fix clang-diagnostic-unused-private-field

Signed-off-by: h-ohta <hiroki.ota@tier4.jp>
  • Loading branch information
h-ohta authored Feb 2, 2022
1 parent 7c4f24f commit a77f528
Show file tree
Hide file tree
Showing 3 changed files with 1 addition and 9 deletions.
2 changes: 1 addition & 1 deletion control/control_performance_analysis/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ if(NOT CMAKE_CXX_STANDARD)
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 @@ -88,7 +88,6 @@ class ControlPerformanceAnalysisNode : public rclcpp::Node

// Parameters
Param param_{}; // wheelbase, control period and feedback coefficients.
TargetPerformanceMsgVars target_error_vars_{};

// Subscriber Parameters
Trajectory::ConstSharedPtr current_trajectory_ptr_; // ConstPtr to local traj.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -162,8 +162,6 @@ bool ControlPerformanceAnalysisCore::isDataReady() const

std::pair<bool, TargetPerformanceMsgVars> ControlPerformanceAnalysisCore::getPerformanceVars()
{
constexpr double EPS = std::numeric_limits<double>::epsilon();

// Check if data is ready.
if (!isDataReady() || !idx_prev_wp_) {
return std::make_pair(false, TargetPerformanceMsgVars{});
Expand Down Expand Up @@ -225,9 +223,6 @@ std::pair<bool, TargetPerformanceMsgVars> ControlPerformanceAnalysisCore::getPer
target_vars.error_energy = error_vec.dot(error_vec);
target_vars.value_approximation = error_vec.transpose() * lyap_P_ * error_vec; // x'Px

double prev_value_approximation = prev_target_vars_->value_approximation;
double && value_decay = target_vars.value_approximation - prev_value_approximation;

target_vars.curvature_estimate = curvature_est;
target_vars.curvature_estimate_pp = curvature_est_pp;

Expand Down Expand Up @@ -401,8 +396,6 @@ double ControlPerformanceAnalysisCore::estimateCurvature()
front_axleWP_pose_prev.position.x - front_axleWP_pose.position.x,
front_axleWP_pose_prev.position.y - front_axleWP_pose.position.y);

auto distance_to_traj0 = idx_prev_waypoint * ds_arc_length;

// Define waypoints 10 meters behind the rear axle if exist.
// If not exist, we will take the first point of the
// curvature triangle as the start point of the trajectory.
Expand Down

0 comments on commit a77f528

Please sign in to comment.