diff --git a/control/velocity_controller/src/velocity_controller_core.cpp b/control/velocity_controller/src/velocity_controller_core.cpp index 53260f69bbc51..19e4d04d22baa 100644 --- a/control/velocity_controller/src/velocity_controller_core.cpp +++ b/control/velocity_controller/src/velocity_controller_core.cpp @@ -183,7 +183,7 @@ void VelocityController::blockUntilVehiclePositionAvailable(const tf2::Duration { RCLCPP_INFO( get_logger(), "waiting %d ms for %s->%s transform to become available", - std::chrono::duration_cast(duration).count(), input, output); + std::chrono::duration_cast(duration).count(), input, output); rclcpp::sleep_for(duration); } RCLCPP_INFO(get_logger(), "transform available"); diff --git a/localization/pose_twist_fusion_filter/ekf_localizer/src/ekf_localizer.cpp b/localization/pose_twist_fusion_filter/ekf_localizer/src/ekf_localizer.cpp index f2eef6e5634ba..7fadff0ebbddd 100644 --- a/localization/pose_twist_fusion_filter/ekf_localizer/src/ekf_localizer.cpp +++ b/localization/pose_twist_fusion_filter/ekf_localizer/src/ekf_localizer.cpp @@ -84,7 +84,7 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti /* initialize ros system */ auto timer_control_callback = std::bind(&EKFLocalizer::timerCallback, this); - auto period_control = std::chrono::duration_cast( + auto period_control = std::chrono::duration_cast( std::chrono::duration(ekf_dt_)); timer_control_ = std::make_shared>( this->get_clock(), period_control, std::move(timer_control_callback), @@ -92,7 +92,7 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti this->get_node_timers_interface()->add_timer(timer_control_, nullptr); auto timer_tf_callback = std::bind(&EKFLocalizer::timerTFCallback, this); - auto period_tf = std::chrono::duration_cast( + auto period_tf = std::chrono::duration_cast( std::chrono::duration(1.0 / tf_rate_)); timer_tf_ = std::make_shared>( this->get_clock(), period_tf, std::move(timer_tf_callback), diff --git a/planning/scenario_planning/common/motion_velocity_optimizer/CMakeLists.txt b/planning/scenario_planning/common/motion_velocity_optimizer/CMakeLists.txt index 28378138aef57..c0b2ff8f92c1e 100644 --- a/planning/scenario_planning/common/motion_velocity_optimizer/CMakeLists.txt +++ b/planning/scenario_planning/common/motion_velocity_optimizer/CMakeLists.txt @@ -39,6 +39,10 @@ ament_auto_add_executable(motion_velocity_optimizer if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) + # ignore python + set(ament_cmake_flake8_FOUND TRUE) + set(ament_cmake_pyflake_FOUND TRUE) + ament_lint_auto_find_test_dependencies() endif() diff --git a/planning/scenario_planning/common/motion_velocity_optimizer/src/motion_velocity_optimizer.cpp b/planning/scenario_planning/common/motion_velocity_optimizer/src/motion_velocity_optimizer.cpp index f98acb1e72644..d99ae38ddc2c5 100644 --- a/planning/scenario_planning/common/motion_velocity_optimizer/src/motion_velocity_optimizer.cpp +++ b/planning/scenario_planning/common/motion_velocity_optimizer/src/motion_velocity_optimizer.cpp @@ -133,7 +133,7 @@ MotionVelocityOptimizer::MotionVelocityOptimizer() { external_velocity_limit_update_rate_ = get_parameter("over_a_weight").as_double(); auto timer_callback = std::bind(&MotionVelocityOptimizer::timerCallback, this); - auto period = std::chrono::duration_cast( + auto period = std::chrono::duration_cast( std::chrono::duration(1.0 / external_velocity_limit_update_rate_)); timer_ = std::make_shared>( get_clock(), period, std::move(timer_callback), get_node_base_interface()->get_context()); @@ -742,7 +742,8 @@ void MotionVelocityOptimizer::blockUntilVehiclePositionAvailable(const tf2::Dura { RCLCPP_INFO( get_logger(), "waiting %d ms for %s->%s transform to become available", - std::chrono::duration_cast(duration).count(), input, output); + std::chrono::duration_cast(duration).count(), + input, output); rclcpp::sleep_for(duration); } RCLCPP_INFO(get_logger(), "transform available"); diff --git a/planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/src/lane_changer.cpp b/planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/src/lane_changer.cpp index 5630b4f2d2332..9a6fe49f545cc 100644 --- a/planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/src/lane_changer.cpp +++ b/planning/scenario_planning/lane_driving/behavior_planning/lane_change_planner/src/lane_changer.cpp @@ -172,13 +172,15 @@ void LaneChanger::run() { // wait until mandatory data is ready if (!route_handler_ptr_->isHandlerReady()) { - RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 5.0, "waiting for route to be ready"); + RCLCPP_WARN_THROTTLE( + get_logger(), *get_clock(), 5000 /* ms */, + "waiting for route to be ready"); return; } if (!data_manager_ptr_->isDataReady()) { RCLCPP_WARN_THROTTLE( get_logger(), - *get_clock(), 5.0, "waiting for vehicle pose, vehicle_velocity, and obstacles"); + *get_clock(), 5000 /* ms */, "waiting for vehicle pose, vehicle_velocity, and obstacles"); return; }