Skip to content

Commit

Permalink
Fixes changed headers from the particle_filter library
Browse files Browse the repository at this point in the history
  • Loading branch information
jaagut committed Jan 4, 2025
1 parent 394c6e0 commit ac3a467
Show file tree
Hide file tree
Showing 9 changed files with 18 additions and 23 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,11 @@ class HardwareInterface {
public:
virtual bool init() = 0;

virtual void read(const rclcpp::Time &t, const rclcpp::Duration &dt){};
virtual void read(const rclcpp::Time &t, const rclcpp::Duration &dt) {};

virtual void write(const rclcpp::Time &t, const rclcpp::Duration &dt){};
virtual void write(const rclcpp::Time &t, const rclcpp::Duration &dt) {};

virtual void restoreAfterPowerCycle(){};
virtual void restoreAfterPowerCycle() {};

virtual ~HardwareInterface(){};
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,7 @@ PressureConverter::PressureConverter(rclcpp::Node::SharedPtr nh, char side) {
}
for (int i = 0; i < 4; i++) {
std::stringstream single_wrench_frame;
single_wrench_frame << side << "_"
<< "cleat_" << wrench_topics[i];
single_wrench_frame << side << "_" << "cleat_" << wrench_topics[i];
wrench_frames_.push_back(single_wrench_frame.str());
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,14 +5,13 @@
#ifndef BITBOTS_LOCALIZATION_MOTIONMODEL_H
#define BITBOTS_LOCALIZATION_MOTIONMODEL_H

#include <particle_filter/CRandomNumberGenerator.h>
#include <particle_filter/MovementModel.h>

#include <bitbots_localization/RobotState.hpp>
#include <bitbots_localization/tools.hpp>
#include <cstdlib>
#include <geometry_msgs/msg/vector3.hpp>
#include <memory>
#include <particle_filter/CRandomNumberGenerator.hpp>
#include <particle_filter/MovementModel.hpp>

namespace bitbots_localization {
/**
Expand Down Expand Up @@ -61,5 +60,5 @@ class RobotMotionModel : public particle_filter::MovementModel<RobotState> {

double sample(double b) const;
};
}; // namespace bitbots_localization
}; // namespace bitbots_localization
#endif // BITBOTS_LOCALIZATION_MOTIONMODEL_H
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,11 @@
#ifndef BITBOTS_LOCALIZATION_OBSERVATIONMODEL_H
#define BITBOTS_LOCALIZATION_OBSERVATIONMODEL_H

#include <particle_filter/ParticleFilter.h>

#include <bitbots_localization/RobotState.hpp>
#include <bitbots_localization/map.hpp>
#include <bitbots_localization/tools.hpp>
#include <localization_parameters.hpp>
#include <particle_filter/ParticleFilter.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#include <soccer_vision_3d_msgs/msg/field_boundary.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,9 @@
#ifndef IMPORTANCERESAMPLINGWE_H
#define IMPORTANCERESAMPLINGWE_H

#include <particle_filter/CRandomNumberGenerator.h>
#include <particle_filter/ImportanceResampling.h>

#include <cassert>
#include <particle_filter/CRandomNumberGenerator.hpp>
#include <particle_filter/ImportanceResampling.hpp>

namespace bitbots_localization {
// ImportanceResampling with explorers
Expand Down Expand Up @@ -97,5 +96,5 @@ void ImportanceResamplingWE<StateType>::resample(const ParticleList &sourceList,
// template <class StateType>
// void ParticleFilter<StateType>::drawAllFromDistribution(const
// std::shared_ptr<StateDistribution<StateType>>& distribution) {
}; // namespace bitbots_localization
}; // namespace bitbots_localization
#endif // IMPORTANCERESAMPLINGWE_H
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,12 @@
#ifndef BITBOTS_LOCALIZATION_ROBOTSTATE_H
#define BITBOTS_LOCALIZATION_ROBOTSTATE_H

#include <particle_filter/ParticleFilter.h>
#include <tf2/LinearMath/Quaternion.h>

#include <Eigen/Core>
#include <bitbots_localization/tools.hpp>
#include <cmath>
#include <particle_filter/ParticleFilter.hpp>
#include <vector>

namespace bitbots_localization {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,9 @@
#ifndef BITBOTS_LOCALIZATION_STATEDISTRIBUTION_H
#define BITBOTS_LOCALIZATION_STATEDISTRIBUTION_H

#include <particle_filter/CRandomNumberGenerator.h>
#include <particle_filter/StateDistribution.h>

#include <bitbots_localization/RobotState.hpp>
#include <particle_filter/CRandomNumberGenerator.hpp>
#include <particle_filter/StateDistribution.hpp>
#include <rclcpp/rclcpp.hpp>
#include <utility>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,6 @@
#define BITBOTS_LOCALIZATION_LOCALIZATION_H

#include <message_filters/subscriber.h>
#include <particle_filter/CRandomNumberGenerator.h>
#include <particle_filter/ParticleFilter.h>
#include <particle_filter/gaussian_mixture_model.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Transform.h>
#include <tf2/convert.h>
Expand Down Expand Up @@ -45,6 +42,9 @@
#include <iterator>
#include <localization_parameters.hpp>
#include <memory>
#include <particle_filter/CRandomNumberGenerator.hpp>
#include <particle_filter/ParticleFilter.hpp>
#include <particle_filter/gaussian_mixture_model.hpp>
#include <rclcpp/rclcpp.hpp>
#include <sensor_msgs/msg/camera_info.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -53,5 +53,5 @@ class Map {
private:
double out_of_map_value_;
};
}; // namespace bitbots_localization
}; // namespace bitbots_localization
#endif // BITBOTS_LOCALIZATION_MAP_H

0 comments on commit ac3a467

Please sign in to comment.