00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00027
00028
00029
00030
00031 #ifndef MECHANISM_CONTROL_H
00032 #define MECHANISM_CONTROL_H
00033
00034 #include <pthread.h>
00035 #include <map>
00036 #include <string>
00037 #include <vector>
00038 #include "ros/ros.h"
00039 #include "pr2_controller_manager/controller_spec.h"
00040 #include <tinyxml/tinyxml.h>
00041 #include <pr2_hardware_interface/hardware_interface.h>
00042 #include <pr2_mechanism_model/robot.h>
00043 #include <realtime_tools/realtime_publisher.h>
00044 #include <ros/node_handle.h>
00045 #include <pr2_controller_interface/controller_provider.h>
00046 #include "pluginlib/class_loader.h"
00047 #include <pr2_mechanism_msgs/ListControllerTypes.h>
00048 #include <pr2_mechanism_msgs/ListControllers.h>
00049 #include <pr2_mechanism_msgs/ReloadControllerLibraries.h>
00050 #include <pr2_mechanism_msgs/LoadController.h>
00051 #include <pr2_mechanism_msgs/UnloadController.h>
00052 #include <pr2_mechanism_msgs/SwitchController.h>
00053 #include <pr2_mechanism_msgs/MechanismStatistics.h>
00054 #include <sensor_msgs/JointState.h>
00055 #include <boost/thread/condition.hpp>
00056
00057
00058 namespace pr2_controller_manager{
00059
00060 class ControllerManager: public pr2_controller_interface::ControllerProvider {
00061
00062 public:
00063 ControllerManager(pr2_hardware_interface::HardwareInterface *hw,
00064 const ros::NodeHandle& nh=ros::NodeHandle());
00065 virtual ~ControllerManager();
00066
00067
00068 void update();
00069
00070
00071 bool initXml(TiXmlElement* config);
00072 bool loadController(const std::string& name);
00073 bool unloadController(const std::string &name);
00074 bool switchController(const std::vector<std::string>& start_controllers,
00075 const std::vector<std::string>& stop_controllers,
00076 const int strictness);
00077
00078
00079 virtual pr2_controller_interface::Controller* getControllerByName(const std::string& name);
00080
00081 pr2_mechanism_model::Robot model_;
00082 pr2_mechanism_model::RobotState *state_;
00083
00084 private:
00085 void getControllerNames(std::vector<std::string> &v);
00086 void getControllerSchedule(std::vector<size_t> &schedule);
00087
00088 ros::NodeHandle controller_node_, cm_node_;
00089 boost::shared_ptr<pluginlib::ClassLoader<pr2_controller_interface::Controller> > controller_loader_;
00090
00091
00092 std::vector<pr2_controller_interface::Controller*> start_request_, stop_request_;
00093 bool please_switch_;
00094 int switch_strictness_;
00095
00096
00097 boost::mutex controllers_lock_;
00098 std::vector<ControllerSpec> controllers_lists_[2];
00099 std::vector<size_t> controllers_scheduling_[2];
00100 int current_controllers_list_, used_by_realtime_;
00101
00102
00103 Statistics pre_update_stats_;
00104 Statistics update_stats_;
00105 Statistics post_update_stats_;
00106
00107
00108 void publishJointState();
00109 void publishMechanismStatistics();
00110 realtime_tools::RealtimePublisher<sensor_msgs::JointState> pub_joint_state_;
00111 realtime_tools::RealtimePublisher<pr2_mechanism_msgs::MechanismStatistics> pub_mech_stats_;
00112 ros::Duration publish_period_joint_state_, publish_period_mechanism_stats_;
00113 ros::Time last_published_joint_state_, last_published_mechanism_stats_;
00114
00115
00116 bool listControllerTypesSrv(pr2_mechanism_msgs::ListControllerTypes::Request &req,
00117 pr2_mechanism_msgs::ListControllerTypes::Response &resp);
00118 bool listControllersSrv(pr2_mechanism_msgs::ListControllers::Request &req,
00119 pr2_mechanism_msgs::ListControllers::Response &resp);
00120 bool switchControllerSrv(pr2_mechanism_msgs::SwitchController::Request &req,
00121 pr2_mechanism_msgs::SwitchController::Response &resp);
00122 bool loadControllerSrv(pr2_mechanism_msgs::LoadController::Request &req,
00123 pr2_mechanism_msgs::LoadController::Response &resp);
00124 bool unloadControllerSrv(pr2_mechanism_msgs::UnloadController::Request &req,
00125 pr2_mechanism_msgs::UnloadController::Response &resp);
00126 bool reloadControllerLibrariesSrv(pr2_mechanism_msgs::ReloadControllerLibraries::Request &req,
00127 pr2_mechanism_msgs::ReloadControllerLibraries::Response &resp);
00128 boost::mutex services_lock_;
00129 ros::ServiceServer srv_list_controllers_, srv_list_controller_types_, srv_load_controller_;
00130 ros::ServiceServer srv_unload_controller_, srv_switch_controller_, srv_reload_libraries_;
00131 bool motors_previously_halted_;
00132 };
00133
00134 }
00135 #endif