diff --git a/driver_mpu9250/src/main_rpi.cpp b/driver_mpu9250/src/main_rpi.cpp index 70951451540ef0cf1eae3dbad29b931a2e43266f..9198fb157a94590d33f52f2a6d289f8a31f762c2 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 af727b672cd1c9c2d55a3f09c998f663ca6dfa9d..cd479760f1106a578996eef3088770f29ddc0be9 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 de992e2d0b075fbbe2dd0fa8bddcce3c08c06a00..1aafd49cb6e2e2454178809f5893844c2447139a 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.