Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Jan 23, 2025
1 parent 5b951a7 commit 052332a
Show file tree
Hide file tree
Showing 7 changed files with 18 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -24,13 +24,13 @@
#include "rclcpp/rclcpp.hpp"
#include "tf2/utils.h"

#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"
#include "autoware_vehicle_msgs/msg/velocity_report.hpp"
#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "geometry_msgs/msg/twist_with_covariance_stamped.hpp"
#include "sensor_msgs/msg/imu.hpp"
#include "std_msgs/msg/float64.hpp"
#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"

#include <iostream>
#include <memory>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,10 @@
#include "deviation_estimator/autoware_universe_utils.hpp"
#include "rclcpp/rclcpp.hpp"

#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "geometry_msgs/msg/twist_stamped.hpp"
#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"

#include <tf2/transform_datatypes.h>

Expand Down Expand Up @@ -95,12 +95,14 @@ double calculate_std_mean_const(const std::vector<T> & v, const double mean)

struct CompareMsgTimestamp
{
bool operator()(autoware_internal_debug_msgs::msg::Float64Stamped const & t1, double const & t2) const
bool operator()(
autoware_internal_debug_msgs::msg::Float64Stamped const & t1, double const & t2) const
{
return rclcpp::Time(t1.stamp).seconds() < t2;
}

bool operator()(autoware_internal_debug_msgs::msg::Float64Stamped const & t1, rclcpp::Time const & t2) const
bool operator()(
autoware_internal_debug_msgs::msg::Float64Stamped const & t1, rclcpp::Time const & t2) const
{
return rclcpp::Time(t1.stamp).seconds() < t2.seconds();
}
Expand Down Expand Up @@ -176,9 +178,11 @@ geometry_msgs::msg::Vector3 integrate_orientation(
const std::vector<geometry_msgs::msg::Vector3Stamped> & gyro_list,
const geometry_msgs::msg::Vector3 & gyro_bias);

double get_mean_abs_vx(const std::vector<autoware_internal_debug_msgs::msg::Float64Stamped> & vx_list);
double get_mean_abs_vx(
const std::vector<autoware_internal_debug_msgs::msg::Float64Stamped> & vx_list);
double get_mean_abs_wz(const std::vector<geometry_msgs::msg::Vector3Stamped> & gyro_list);
double get_mean_accel(const std::vector<autoware_internal_debug_msgs::msg::Float64Stamped> & vx_list);
double get_mean_accel(
const std::vector<autoware_internal_debug_msgs::msg::Float64Stamped> & vx_list);

geometry_msgs::msg::Vector3 transform_vector3(
const geometry_msgs::msg::Vector3 & vec, const geometry_msgs::msg::TransformStamped & transform);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@

#include "deviation_estimator/utils.hpp"

#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/vector3_stamped.hpp"
#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"

#include <utility>
#include <vector>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<build_depend>autoware_cmake</build_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>geometry_msgs</depend>
Expand All @@ -28,7 +29,6 @@
<depend>tf2</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>
<depend>autoware_internal_debug_msgs</depend>
<exec_depend>rosbag2_storage_mcap</exec_depend>

<test_depend>ament_cmake_gtest</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,8 @@ geometry_msgs::msg::Vector3 integrate_orientation(
/**
* @brief calculate mean of |vx|
*/
double get_mean_abs_vx(const std::vector<autoware_internal_debug_msgs::msg::Float64Stamped> & vx_list)
double get_mean_abs_vx(
const std::vector<autoware_internal_debug_msgs::msg::Float64Stamped> & vx_list)
{
double mean_abs_vx = 0;
for (const auto & msg : vx_list) {
Expand All @@ -179,7 +180,8 @@ double get_mean_abs_wz(const std::vector<geometry_msgs::msg::Vector3Stamped> & g
/**
* @brief calculate mean of acceleration
*/
double get_mean_accel(const std::vector<autoware_internal_debug_msgs::msg::Float64Stamped> & vx_list)
double get_mean_accel(
const std::vector<autoware_internal_debug_msgs::msg::Float64Stamped> & vx_list)
{
const double dt =
(rclcpp::Time(vx_list.back().stamp) - rclcpp::Time(vx_list.front().stamp)).seconds();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,14 +20,14 @@
#include "rclcpp/rclcpp.hpp"
#include "tf2/LinearMath/Quaternion.h"

#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"
#include "geometry_msgs/msg/pose_stamped.hpp"
#include "geometry_msgs/msg/pose_with_covariance_stamped.hpp"
#include "geometry_msgs/msg/twist_with_covariance_stamped.hpp"
#include "nav_msgs/msg/odometry.hpp"
#include "sensor_msgs/msg/imu.hpp"
#include "std_msgs/msg/float64.hpp"
#include "std_srvs/srv/set_bool.hpp"
#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"

#include <tf2/utils.h>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<build_depend>autoware_cmake</build_depend>

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>geometry_msgs</depend>
<depend>nav_msgs</depend>
Expand All @@ -25,7 +26,6 @@
<depend>std_srvs</depend>
<depend>tf2</depend>
<depend>tf2_ros</depend>
<depend>autoware_internal_debug_msgs</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down

0 comments on commit 052332a

Please sign in to comment.