Skip to content

Commit

Permalink
chore: updated the use of the kalman filter implementation since it w…
Browse files Browse the repository at this point in the history
…as moved into the autoware namespace

Signed-off-by: Kenzo Lobos-Tsunekawa <kenzo.lobos@tier4.jp>
  • Loading branch information
knzo25 committed Aug 20, 2024
1 parent ff6c871 commit 1dfc8d7
Show file tree
Hide file tree
Showing 8 changed files with 12 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
#define GROUND_PLANE_CALIBRATOR__GROUND_PLANE_CALIBRATOR_HPP_

#include <Eigen/Dense>
#include <autoware/kalman_filter/kalman_filter.hpp>
#include <ground_plane_calibrator/utils.hpp>
#include <kalman_filter/kalman_filter.hpp>
#include <rclcpp/logging.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tier4_ground_plane_utils/ground_plane_utils.hpp>
Expand Down Expand Up @@ -46,6 +46,7 @@
namespace ground_plane_calibrator
{

using autoware::kalman_filter::KalmanFilter;
using PointType = pcl::PointXYZ;
using tier4_ground_plane_utils::GroundPlaneExtractorParameters;

Expand Down
2 changes: 1 addition & 1 deletion calibrators/ground_plane_calibrator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@

<build_depend>autoware_cmake</build_depend>

<depend>autoware_kalman_filter</depend>
<depend>autoware_universe_utils</depend>
<depend>eigen</depend>
<depend>geometry_msgs</depend>
<depend>image_geometry</depend>
<depend>image_transport</depend>
<depend>kalman_filter</depend>
<depend>pcl_conversions</depend>
<depend>pcl_ros</depend>
<depend>rclcpp</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#define LIDAR_TO_LIDAR_2D_CALIBRATOR__LIDAR_TO_LIDAR_2D_CALIBRATOR_HPP_

#include <Eigen/Dense>
#include <kalman_filter/kalman_filter.hpp>
#include <autoware/kalman_filter/kalman_filter.hpp>
#include <pcl/kdtree/impl/kdtree_flann.hpp>
#include <rclcpp/logging.hpp>
#include <rclcpp/rclcpp.hpp>
Expand Down Expand Up @@ -47,6 +47,7 @@
namespace lidar_to_lidar_2d_calibrator
{

using autoware::kalman_filter::KalmanFilter;
using PointType = pcl::PointXYZ;

/**
Expand Down
2 changes: 1 addition & 1 deletion calibrators/lidar_to_lidar_2d_calibrator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,12 @@

<build_depend>autoware_cmake</build_depend>

<depend>autoware_kalman_filter</depend>
<depend>autoware_universe_utils</depend>
<depend>eigen</depend>
<depend>geometry_msgs</depend>
<depend>image_geometry</depend>
<depend>image_transport</depend>
<depend>kalman_filter</depend>
<depend>pcl_conversions</depend>
<depend>pcl_ros</depend>
<depend>rclcpp</depend>
Expand Down
2 changes: 1 addition & 1 deletion calibrators/mapping_based_calibrator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@

<build_depend>autoware_cmake</build_depend>

<depend>autoware_kalman_filter</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>eigen</depend>
<depend>geometry_msgs</depend>
<depend>image_geometry</depend>
<depend>image_transport</depend>
<depend>kalman_filter</depend>
<depend>libboost-filesystem</depend>
<depend>libboost-serialization</depend>
<depend>libpcl-all-dev</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
#define MARKER_RADAR_LIDAR_CALIBRATOR__TRACK_HPP_

#include <Eigen/Dense>
#include <autoware/kalman_filter/kalman_filter.hpp>
#include <builtin_interfaces/msg/time.hpp>
#include <kalman_filter/kalman_filter.hpp>
#include <marker_radar_lidar_calibrator/types.hpp>
#include <rclcpp/time.hpp>

Expand All @@ -26,6 +26,8 @@
namespace marker_radar_lidar_calibrator
{

using autoware::kalman_filter::KalmanFilter;

class Track
{
public:
Expand Down
2 changes: 1 addition & 1 deletion calibrators/marker_radar_lidar_calibrator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,10 @@

<build_depend>autoware_cmake</build_depend>

<depend>autoware_kalman_filter</depend>
<depend>autoware_universe_utils</depend>
<depend>eigen</depend>
<depend>geometry_msgs</depend>
<depend>kalman_filter</depend>
<depend>pcl_conversions</depend>
<depend>pcl_ros</depend>
<depend>radar_msgs</depend>
Expand Down
2 changes: 1 addition & 1 deletion calibrators/marker_radar_lidar_calibrator/src/track.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
// limitations under the License.

#include <Eigen/Dense>
#include <kalman_filter/kalman_filter.hpp>
#include <autoware/kalman_filter/kalman_filter.hpp>
#include <marker_radar_lidar_calibrator/track.hpp>
#include <marker_radar_lidar_calibrator/types.hpp>

Expand Down

0 comments on commit 1dfc8d7

Please sign in to comment.