controller_loader.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2014-2017, Fetch Robotics Inc.
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 the Fetch Robotics Inc. 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 FETCH ROBOTICS INC. BE LIABLE FOR ANY
00021  * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022  * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024  * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025  * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
00026  * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027  */
00028 
00029 // Author: Michael Ferguson
00030 
00031 #include <robot_controllers_interface/controller_loader.h>
00032 
00033 namespace robot_controllers
00034 {
00035 
00036 ControllerLoader::ControllerLoader() :
00037     plugin_loader_("robot_controllers", "robot_controllers::Controller"),
00038     active_(false)
00039 {
00040 }
00041 
00042 bool ControllerLoader::init(const std::string& name, ControllerManager* manager)
00043 {
00044   ros::NodeHandle nh(name);
00045   std::string controller_type;
00046 
00047   if (nh.getParam("type", controller_type))
00048   {
00049     // If plugin is bad, catch pluginlib exception
00050     try
00051     {
00052       controller_ = plugin_loader_.createInstance(controller_type);
00053       controller_->init(nh, manager);
00054     }
00055     catch (pluginlib::LibraryLoadException e)
00056     {
00057       ROS_ERROR_STREAM("Plugin error while loading controller: " << e.what());
00058       return false;
00059     }
00060     return true;
00061   }
00062   ROS_ERROR_STREAM("Unable to load controller " << name.c_str());
00063   return false;
00064 }
00065 
00066 bool ControllerLoader::start()
00067 {
00068   active_ = controller_->start();
00069   return active_;
00070 }
00071 
00072 bool ControllerLoader::stop(bool force)
00073 {
00074   bool stopped = controller_->stop(force);
00075   if (stopped)
00076   {
00077     active_ = false;
00078   }
00079   return stopped;
00080 }
00081 
00082 bool ControllerLoader::reset()
00083 {
00084   if (active_)
00085   {
00086     return controller_->reset();
00087   }
00088   return true;
00089 }
00090 
00091 bool ControllerLoader::isActive()
00092 {
00093   return active_;
00094 }
00095 
00096 void ControllerLoader::update(const ros::Time& time, const ros::Duration& dt)
00097 {
00098   if (active_)
00099   {
00100     controller_->update(time, dt);
00101   }
00102 }
00103 
00104 ControllerPtr ControllerLoader::getController()
00105 {
00106   return controller_;
00107 }
00108 
00109 }  // namespace robot_controllers


robot_controllers_interface
Author(s): Michael Ferguson
autogenerated on Wed Jun 14 2017 04:09:05