Skip to content
Snippets Groups Projects
Commit d7277bcd authored by Paul D'Angio's avatar Paul D'Angio
Browse files

switched to shared pointers for ros node components

parent d562be22
No related branches found
No related tags found
No related merge requests found
...@@ -4,7 +4,7 @@ ...@@ -4,7 +4,7 @@
int main(int argc, char **argv) int main(int argc, char **argv)
{ {
// Create the driver. // Create the driver.
rpi_driver* driver = new rpi_driver(); auto driver = std::make_shared<rpi_driver>();
// Create the node. // Create the node.
ros_node node(driver, argc, argv); ros_node node(driver, argc, argv);
......
...@@ -8,7 +8,7 @@ ...@@ -8,7 +8,7 @@
#include <cmath> #include <cmath>
// CONSTRUCTORS // 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. // Initialize flags.
ros_node::f_gyroscope_calibrating = false; ros_node::f_gyroscope_calibrating = false;
...@@ -20,7 +20,7 @@ ros_node::ros_node(driver *driver, int argc, char **argv) ...@@ -20,7 +20,7 @@ ros_node::ros_node(driver *driver, int argc, char **argv)
ros::init(argc, argv, "driver_mpu9250"); ros::init(argc, argv, "driver_mpu9250");
// Get the node's handle. // Get the node's handle.
ros_node::m_node = new ros::NodeHandle(); ros_node::m_node = std::make_shared<ros::NodeHandle>();
// Read parameters. // Read parameters.
ros::NodeHandle private_node("~"); ros::NodeHandle private_node("~");
...@@ -73,12 +73,6 @@ ros_node::ros_node(driver *driver, int argc, char **argv) ...@@ -73,12 +73,6 @@ ros_node::ros_node(driver *driver, int argc, char **argv)
// Perform initial gyroscope calibration. // Perform initial gyroscope calibration.
ros_node::calibrate_gyroscope(500); ros_node::calibrate_gyroscope(500);
} }
ros_node::~ros_node()
{
// Clean up resources.
delete ros_node::m_node;
delete ros_node::m_driver;
}
// ROS // ROS
void ros_node::spin() void ros_node::spin()
......
...@@ -21,8 +21,7 @@ public: ...@@ -21,8 +21,7 @@ public:
/// \param driver The MPU9250 driver instance. /// \param driver The MPU9250 driver instance.
/// \param argc Number of main() args. /// \param argc Number of main() args.
/// \param argv The main() args. /// \param argv The main() args.
ros_node(driver* driver, int argc, char **argv); ros_node(std::shared_ptr<driver> driver, int argc, char **argv);
~ros_node();
// METHODS // METHODS
/// \brief spin Runs the node. /// \brief spin Runs the node.
...@@ -31,7 +30,7 @@ public: ...@@ -31,7 +30,7 @@ public:
private: private:
// COMPONENTS // COMPONENTS
/// \brief m_driver The driver instance. /// \brief m_driver The driver instance.
driver* m_driver; std::shared_ptr<driver> m_driver;
// CALIBRATIONS // CALIBRATIONS
/// \brief The accelerometer's calibration. /// \brief The accelerometer's calibration.
...@@ -53,7 +52,7 @@ private: ...@@ -53,7 +52,7 @@ private:
// ROS // ROS
/// \brief m_node The node's handle. /// \brief m_node The node's handle.
ros::NodeHandle* m_node; std::shared_ptr<ros::NodeHandle> m_node;
// PUBLISHERS // PUBLISHERS
/// \brief Publisher for accelerometer data. /// \brief Publisher for accelerometer data.
......
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment