Skip to content

Commit 926a4e4

Browse files
committed
remove struct typedefs; rid raw pointers
1 parent ceceac6 commit 926a4e4

File tree

4 files changed

+21
-22
lines changed

4 files changed

+21
-22
lines changed

include/robot_localization/robot_localization_estimator.hpp

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -35,8 +35,9 @@
3535

3636
#include <boost/circular_buffer.hpp>
3737
#include <Eigen/Dense>
38-
#include <vector>
3938
#include <iostream>
39+
#include <memory>
40+
#include <vector>
4041

4142
#include "robot_localization/filter_base.hpp"
4243
#include "robot_localization/filter_common.hpp"
@@ -96,7 +97,6 @@ enum EstimatorResult
9697
Failed
9798
};
9899
} // namespace EstimatorResults
99-
typedef EstimatorResults::EstimatorResult EstimatorResult;
100100

101101
namespace FilterTypes
102102
{
@@ -107,7 +107,6 @@ enum FilterType
107107
NotDefined
108108
};
109109
} // namespace FilterTypes
110-
typedef FilterTypes::FilterType FilterType;
111110

112111
//! @brief Robot Localization Listener class
113112
//!
@@ -125,7 +124,7 @@ class RobotLocalizationEstimator
125124
//!
126125
explicit RobotLocalizationEstimator(
127126
unsigned int buffer_capacity,
128-
FilterType filter_type,
127+
FilterTypes::FilterType filter_type,
129128
const Eigen::MatrixXd & process_noise_covariance,
130129
const std::vector<double> & filter_args = std::vector<double>());
131130

@@ -148,7 +147,9 @@ class RobotLocalizationEstimator
148147
//!
149148
//! @return GetStateResult enum
150149
//!
151-
EstimatorResult getState(const double time, EstimatorState & state) const;
150+
EstimatorResults::EstimatorResult getState(
151+
const double time,
152+
EstimatorState & state) const;
152153

153154
//! @brief Clears the internal state buffer
154155
//!
@@ -222,7 +223,7 @@ class RobotLocalizationEstimator
222223
//!
223224
//! @brief A pointer to the filter instance that is used for extrapolation
224225
//!
225-
FilterBase * filter_;
226+
std::unique_ptr<FilterBase> filter_;
226227
};
227228

228229
} // namespace robot_localization

include/robot_localization/ros_robot_localization_listener.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -142,7 +142,7 @@ class RosRobotLocalizationListener
142142
//! @brief The core state estimator that facilitates inter- and
143143
//! extrapolation between buffered states.
144144
//!
145-
RobotLocalizationEstimator * estimator_{nullptr};
145+
std::unique_ptr<RobotLocalizationEstimator> estimator_;
146146

147147
//! @brief Quality of service definitions
148148
//!

src/robot_localization_estimator.cpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030
* POSSIBILITY OF SUCH DAMAGE.
3131
*/
3232

33+
#include <memory>
3334
#include <vector>
3435

3536
#include "robot_localization/ekf.hpp"
@@ -42,21 +43,21 @@ namespace robot_localization
4243
// are accepted for alpha, kappa, beta, not just a vector, for filter_args
4344
RobotLocalizationEstimator::RobotLocalizationEstimator(
4445
unsigned int buffer_capacity,
45-
FilterType filter_type,
46+
FilterTypes::FilterType filter_type,
4647
const Eigen::MatrixXd & process_noise_covariance,
4748
const std::vector<double> & filter_args)
4849
{
4950
state_buffer_.set_capacity(buffer_capacity);
5051

5152
// Set up the filter that is used for predictions
5253
if (filter_type == FilterTypes::EKF) {
53-
filter_ = new Ekf;
54+
filter_ = std::make_unique<Ekf>();
5455
} else if (filter_type == FilterTypes::UKF) {
5556
if (filter_args.size() < 3) {
56-
filter_ = new Ukf();
57+
filter_ = std::make_unique<Ukf>();
5758
} else {
58-
filter_ = new Ukf();
59-
static_cast<Ukf *>(filter_)->setConstants(filter_args[0], filter_args[1],
59+
filter_ = std::make_unique<Ukf>();
60+
dynamic_cast<Ukf *>(filter_.get())->setConstants(filter_args[0], filter_args[1],
6061
filter_args[2]);
6162
}
6263
}
@@ -66,7 +67,6 @@ RobotLocalizationEstimator::RobotLocalizationEstimator(
6667

6768
RobotLocalizationEstimator::~RobotLocalizationEstimator()
6869
{
69-
delete filter_;
7070
}
7171

7272
void RobotLocalizationEstimator::setState(const EstimatorState & state)
@@ -89,7 +89,7 @@ void RobotLocalizationEstimator::setState(const EstimatorState & state)
8989
}
9090
}
9191

92-
EstimatorResult RobotLocalizationEstimator::getState(
92+
EstimatorResults::EstimatorResult RobotLocalizationEstimator::getState(
9393
const double time,
9494
EstimatorState & state) const
9595
{

src/ros_robot_localization_listener.cpp

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -62,7 +62,8 @@
6262

6363
namespace robot_localization
6464
{
65-
FilterType filterTypeFromString(const std::string & filter_type_str)
65+
FilterTypes::FilterType filterTypeFromString(
66+
const std::string & filter_type_str)
6667
{
6768
if (filter_type_str == "ekf") {
6869
return FilterTypes::EKF;
@@ -74,7 +75,7 @@ FilterType filterTypeFromString(const std::string & filter_type_str)
7475
}
7576

7677
RosRobotLocalizationListener::RosRobotLocalizationListener(
77-
rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("robot_localization"))
78+
rclcpp::Node::SharedPtr node)
7879
: qos1_(1),
7980
qos10_(10),
8081
odom_sub_(node, "odom/filtered", qos1_.get_rmw_qos_profile()),
@@ -92,7 +93,7 @@ RosRobotLocalizationListener::RosRobotLocalizationListener(
9293
std::string filter_type_str = node->declare_parameter<std::string>(
9394
"filter_type", std::string("ekf"));
9495

95-
FilterType filter_type = filterTypeFromString(filter_type_str);
96+
FilterTypes::FilterType filter_type = filterTypeFromString(filter_type_str);
9697
if (filter_type == FilterTypes::NotDefined) {
9798
RCLCPP_ERROR(node_logger_->get_logger(),
9899
"RosRobotLocalizationListener: Parameter filter_type invalid");
@@ -142,8 +143,8 @@ RosRobotLocalizationListener::RosRobotLocalizationListener(
142143
std::vector<double> filter_args = node->declare_parameter<
143144
std::vector<double>>("filter_args", std::vector<double>());
144145

145-
estimator_ = new RobotLocalizationEstimator(buffer_size, filter_type,
146-
process_noise_covariance, filter_args);
146+
estimator_ = std::make_unique<RobotLocalizationEstimator>(buffer_size,
147+
filter_type, process_noise_covariance, filter_args);
147148

148149
sync_.registerCallback(std::bind(
149150
&RosRobotLocalizationListener::odomAndAccelCallback,
@@ -168,9 +169,6 @@ RosRobotLocalizationListener::RosRobotLocalizationListener(
168169

169170
RosRobotLocalizationListener::~RosRobotLocalizationListener()
170171
{
171-
if (estimator_) {
172-
delete estimator_;
173-
}
174172
}
175173

176174
void RosRobotLocalizationListener::odomAndAccelCallback(

0 commit comments

Comments
 (0)