From d7277bcd24930587b77e1c465b6af99a7f5db3c1 Mon Sep 17 00:00:00 2001
From: Paul D'Angio <pcdangio@gmail.com>
Date: Tue, 17 Nov 2020 23:01:01 -0500
Subject: [PATCH] switched to shared pointers for ros node components

---
 driver_mpu9250/src/main_rpi.cpp |  2 +-
 driver_mpu9250/src/ros_node.cpp | 10 ++--------
 driver_mpu9250/src/ros_node.h   |  7 +++----
 3 files changed, 6 insertions(+), 13 deletions(-)

diff --git a/driver_mpu9250/src/main_rpi.cpp b/driver_mpu9250/src/main_rpi.cpp
index 7095145..9198fb1 100644
--- a/driver_mpu9250/src/main_rpi.cpp
+++ b/driver_mpu9250/src/main_rpi.cpp
@@ -4,7 +4,7 @@
 int main(int argc, char **argv)
 {
     // Create the driver.
-    rpi_driver* driver = new rpi_driver();
+    auto driver = std::make_shared<rpi_driver>();
 
     // Create the node.
     ros_node node(driver, argc, argv);
diff --git a/driver_mpu9250/src/ros_node.cpp b/driver_mpu9250/src/ros_node.cpp
index af727b6..cd47976 100644
--- a/driver_mpu9250/src/ros_node.cpp
+++ b/driver_mpu9250/src/ros_node.cpp
@@ -8,7 +8,7 @@
 #include <cmath>
 
 // CONSTRUCTORS
-ros_node::ros_node(driver *driver, int argc, char **argv)
+ros_node::ros_node(std::shared_ptr<driver> driver, int argc, char **argv)
 {
     // Initialize flags.
     ros_node::f_gyroscope_calibrating = false;
@@ -20,7 +20,7 @@ ros_node::ros_node(driver *driver, int argc, char **argv)
     ros::init(argc, argv, "driver_mpu9250");
 
     // Get the node's handle.
-    ros_node::m_node = new ros::NodeHandle();
+    ros_node::m_node = std::make_shared<ros::NodeHandle>();
 
     // Read parameters.
     ros::NodeHandle private_node("~");
@@ -73,12 +73,6 @@ ros_node::ros_node(driver *driver, int argc, char **argv)
     // Perform initial gyroscope calibration.
     ros_node::calibrate_gyroscope(500);
 }
-ros_node::~ros_node()
-{
-    // Clean up resources.
-    delete ros_node::m_node;
-    delete ros_node::m_driver;
-}
 
 // ROS
 void ros_node::spin()
diff --git a/driver_mpu9250/src/ros_node.h b/driver_mpu9250/src/ros_node.h
index de992e2..1aafd49 100644
--- a/driver_mpu9250/src/ros_node.h
+++ b/driver_mpu9250/src/ros_node.h
@@ -21,8 +21,7 @@ public:
     /// \param driver The MPU9250 driver instance.
     /// \param argc Number of main() args.
     /// \param argv The main() args.
-    ros_node(driver* driver, int argc, char **argv);
-    ~ros_node();
+    ros_node(std::shared_ptr<driver> driver, int argc, char **argv);
 
     // METHODS
     /// \brief spin Runs the node.
@@ -31,7 +30,7 @@ public:
 private:
     // COMPONENTS
     /// \brief m_driver The driver instance.
-    driver* m_driver;
+    std::shared_ptr<driver> m_driver;
 
     // CALIBRATIONS
     /// \brief The accelerometer's calibration.
@@ -53,7 +52,7 @@ private:
 
     // ROS
     /// \brief m_node The node's handle.
-    ros::NodeHandle* m_node;
+    std::shared_ptr<ros::NodeHandle> m_node;
 
     // PUBLISHERS
     /// \brief Publisher for accelerometer data.
-- 
GitLab