From acf9609155c8f372abf789cad1d5bdfd3694636d Mon Sep 17 00:00:00 2001 From: Timothy Wiley Date: Sun, 21 May 2017 11:08:59 +1000 Subject: [PATCH] crosbot_fastslam: make start/stop method virtual and use them overloaded properly --- .../include/crosbot_fastslam/fastslam.hpp | 5 ++--- crosbot_fastslam/include/crosbot_fastslam/module.hpp | 3 ++- crosbot_fastslam/src/module.cpp | 11 +++++++++-- crosbot_fastslam/src/nodes/fastslam.cpp | 2 +- 4 files changed, 14 insertions(+), 7 deletions(-) diff --git a/crosbot_fastslam/include/crosbot_fastslam/fastslam.hpp b/crosbot_fastslam/include/crosbot_fastslam/fastslam.hpp index 31311f3..a67dae2 100644 --- a/crosbot_fastslam/include/crosbot_fastslam/fastslam.hpp +++ b/crosbot_fastslam/include/crosbot_fastslam/fastslam.hpp @@ -30,8 +30,8 @@ public: * Methods for configuring and starting/stopping. */ void configure(ConfigElementPtr config); - void start(); - void stop(); + virtual void start(); + virtual void stop(); /** * Allow for map to be paused resumed. @@ -154,7 +154,6 @@ protected: } }; - /** * FastSLAM motion parameters, and motion model */ diff --git a/crosbot_fastslam/include/crosbot_fastslam/module.hpp b/crosbot_fastslam/include/crosbot_fastslam/module.hpp index ecfc770..06dd335 100644 --- a/crosbot_fastslam/include/crosbot_fastslam/module.hpp +++ b/crosbot_fastslam/include/crosbot_fastslam/module.hpp @@ -65,7 +65,8 @@ public: virtual ~FastSLAMModule(); void initialize(ros::NodeHandle& nh); - void shutdown(); + virtual void start(); + virtual void stop(); // ROS Callbacks void callbackPoseEstimate(const geometry_msgs::PointStampedConstPtr& poseEstimate); diff --git a/crosbot_fastslam/src/module.cpp b/crosbot_fastslam/src/module.cpp index dc09fff..1f9e98c 100644 --- a/crosbot_fastslam/src/module.cpp +++ b/crosbot_fastslam/src/module.cpp @@ -116,13 +116,20 @@ void FastSLAMModule::initialize(ros::NodeHandle& nh) { start(); } -void FastSLAMModule::shutdown() { - stop(); +void FastSLAMModule::start() { + // Start fastslam + FastSLAMMap::start(); +} +void FastSLAMModule::stop() { + // Stop this element scanSub.shutdown(); snapSub.shutdown(); gridPub.shutdown(); historyPub.shutdown(); + + // Stop fastslam + FastSLAMMap::stop(); } void FastSLAMModule::callbackPoseEstimate(const geometry_msgs::PointStampedConstPtr& poseEstimate) { diff --git a/crosbot_fastslam/src/nodes/fastslam.cpp b/crosbot_fastslam/src/nodes/fastslam.cpp index fd30371..d1112c4 100644 --- a/crosbot_fastslam/src/nodes/fastslam.cpp +++ b/crosbot_fastslam/src/nodes/fastslam.cpp @@ -29,7 +29,7 @@ int main(int argc, char** argv) { while (ros::ok()) { ros::spin(); } - node->shutdown(); + node->stop(); return 0; } -- GitLab