nodelet.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2013, Marcus Liebhardt, Yujin Robot.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Yujin Robot nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /*****************************************************************************
00031 ** Includes
00032 *****************************************************************************/
00033 #include <string>
00034 #include <nodelet/nodelet.h>
00035 #include <pluginlib/class_list_macros.h>
00036 #include <ecl/threads/thread.hpp>
00037 #include "yocs_diff_drive_pose_controller/controller.hpp"
00038 
00039 namespace yocs
00040 {
00041 
00042 class DiffDrivePoseControllerNodelet : public nodelet::Nodelet
00043 {
00044 public:
00045   DiffDrivePoseControllerNodelet() : spin_rate_(20.0), shutdown_requested_(false) { };
00046   ~DiffDrivePoseControllerNodelet()
00047   {
00048     NODELET_DEBUG_STREAM("Waiting for update thread to finish. [" << name_ << "]");
00049     shutdown_requested_ = true;
00050     update_thread_.join();
00051   }
00052 
00053   void onInit()
00054   {
00055     ros::NodeHandle nh = this->getPrivateNodeHandle();
00056     // resolve node(let) name
00057     name_ = nh.getUnresolvedNamespace();
00058     int pos = name_.find_last_of('/');
00059     name_ = name_.substr(pos + 1);
00060     NODELET_INFO_STREAM("Initialising nodelet... [" << name_ << "]");
00061     double spin_rate_param = 20;
00062     if(nh.getParam("spin_rate", spin_rate_param))
00063     {
00064       ROS_DEBUG_STREAM("Controller will spin at " << spin_rate_param << " hz. [" << name_ <<"]");
00065     }
00066     else
00067     {
00068       ROS_WARN_STREAM("Couldn't retrieve parameter 'spin_rate' from parameter server! Using default '"
00069                       << spin_rate_param << "'. [" << name_ <<"]");
00070     }
00071     spin_rate_ = ros::Rate(spin_rate_param);
00072     bool start_enabled = true;
00073     nh.getParam("start_enabled", start_enabled);
00074     controller_.reset(new DiffDrivePoseController(nh, name_));
00075     if (controller_->init())
00076     {
00077       if (start_enabled)
00078       {
00079         controller_->enable();
00080         ROS_INFO_STREAM("Controller will start enabled. [" << name_ <<"]");
00081       }
00082       else
00083       {
00084         controller_->disable();
00085         ROS_INFO_STREAM("Controller will start disabled. [" << name_ <<"]");
00086       }
00087       update_thread_.start(&DiffDrivePoseControllerNodelet::update, *this);
00088       NODELET_INFO_STREAM("Controller initialised. [" << name_ << "]");
00089     }
00090     else
00091     {
00092       NODELET_ERROR_STREAM("Couldn't initialise controller! Please restart. [" << name_ << "]");
00093     }
00094   }
00095 private:
00096   void update()
00097   {
00098     while (!shutdown_requested_ && ros::ok())
00099     {
00100       controller_->spinOnce();
00101       spin_rate_.sleep();
00102     }
00103   }
00104   std::string name_;
00105   ros::Rate spin_rate_;
00106   boost::shared_ptr<DiffDrivePoseController> controller_;
00107   ecl::Thread update_thread_;
00108   bool shutdown_requested_;
00109 };
00110 
00111 } // namespace yocs
00112 
00113 PLUGINLIB_EXPORT_CLASS(yocs::DiffDrivePoseControllerNodelet, nodelet::Nodelet);


yocs_diff_drive_pose_controller
Author(s): Marcus Liebhardt
autogenerated on Thu Jun 6 2019 21:47:33