controller_manager.h
Go to the documentation of this file.
00001 /*
00002     Copyright (c) 2011, Antons Rebguns <email>
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         * Redistributions of source code must retain the above copyright
00008         notice, this list of conditions and the following disclaimer.
00009         * Redistributions in binary form must reproduce the above copyright
00010         notice, this list of conditions and the following disclaimer in the
00011         documentation and/or other materials provided with the distribution.
00012         * Neither the name of the <organization> nor the
00013         names of its contributors may be used to endorse or promote products
00014         derived from this software without specific prior written permission.
00015 
00016     THIS SOFTWARE IS PROVIDED BY Antons Rebguns <email> ''AS IS'' AND ANY
00017     EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018     WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019     DISCLAIMED. IN NO EVENT SHALL Antons Rebguns <email> BE LIABLE FOR ANY
00020     DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021     (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022     LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023     ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024     (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025     SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 
00029 #ifndef CONTROLLER_MANAGER_H
00030 #define CONTROLLER_MANAGER_H
00031 
00032 #include <map>
00033 #include <set>
00034 #include <string>
00035 
00036 #include <boost/thread.hpp>
00037 
00038 #include <dynamixel_hardware_interface/serial_proxy.h>
00039 #include <dynamixel_hardware_interface/single_joint_controller.h>
00040 #include <dynamixel_hardware_interface/multi_joint_controller.h>
00041 
00042 #include <ros/ros.h>
00043 #include <pluginlib/class_loader.h>
00044 #include <dynamixel_hardware_interface/StartController.h>
00045 #include <dynamixel_hardware_interface/StopController.h>
00046 #include <dynamixel_hardware_interface/RestartController.h>
00047 
00048 namespace dynamixel_controller_manager
00049 {
00050 
00051 class ControllerManager
00052 {
00053 
00054 public:
00055     ControllerManager();
00056     virtual ~ControllerManager();
00057     
00058     bool startController(std::string name, std::string port);
00059     bool stopController(std::string name);
00060     bool restartController(std::string name);
00061     
00062 private:
00063     ros::NodeHandle nh_;
00064     ros::NodeHandle private_nh_;
00065     
00066     std::string manager_namespace_;
00067     
00068     double diagnostics_rate_;
00069     ros::Publisher diagnostics_pub_;
00070     
00071     ros::ServiceServer start_controller_server_;
00072     ros::ServiceServer stop_controller_server_;
00073     ros::ServiceServer restart_controller_server_;
00074     
00075     std::map<std::string, dynamixel_hardware_interface::SerialProxy*> serial_proxies_;
00076 
00077     boost::thread* diagnostics_thread_;
00078 
00079     boost::mutex terminate_mutex_;
00080     bool terminate_diagnostics_;
00081 
00082     boost::shared_ptr<pluginlib::ClassLoader<controller::SingleJointController> > sjc_loader_;
00083     boost::shared_ptr<pluginlib::ClassLoader<controller::MultiJointController> > mjc_loader_;
00084     
00085     std::map<std::string, controller::SingleJointController*> sj_controllers_;
00086     std::map<std::string, controller::MultiJointController*> mj_controllers_;
00087     
00088     std::set<std::string> mj_waiting_controllers_;
00089     std::set<std::pair<std::string, std::vector<std::string> > > waiting_mjcs_;
00090     
00091     boost::mutex controllers_lock_;
00092     boost::mutex services_lock_;
00093 
00094     void publishDiagnosticInformation();
00095     void checkDeps();
00096     
00097     bool startControllerSrv(dynamixel_hardware_interface::StartController::Request& req,
00098                             dynamixel_hardware_interface::StartController::Response& res);
00099     
00100     bool stopControllerSrv(dynamixel_hardware_interface::StopController::Request& req,
00101                            dynamixel_hardware_interface::StopController::Response& res);
00102     
00103     bool restartControllerSrv(dynamixel_hardware_interface::RestartController::Request& req,
00104                               dynamixel_hardware_interface::RestartController::Response& res);
00105     
00106 };
00107 
00108 }
00109 
00110 #endif // CONTROLLER_MANAGER_H


dynamixel_hardware_interface
Author(s): Antons Rebguns
autogenerated on Fri Aug 28 2015 10:32:45