diff --git a/crosbot_fastslam/include/crosbot_fastslam/fastslam.hpp b/crosbot_fastslam/include/crosbot_fastslam/fastslam.hpp index 31311f37874fa4f49bc707d7f170b9e7f9833af5..a67dae2ae84dcc9cf1fb7cafd018d71ed93c501b 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 ecfc770c213850be4ef11723e7e9a6921bac3e7b..06dd335540d837be863e18bda379489710227111 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 dc09fff2e2475451e47781cfb7dd31b9e3b158f2..1f9e98ce98b77a3a1a420f30ab24c78140804857 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 fd303715de8ad1853890071edfc0cf949fc0cbd7..d1112c4de212647086436b4a886d44a2fd947fd2 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; }