Go to the documentation of this file.00001
00002
00003 #include <joint_limits_interface/joint_limits.h>
00004 #include <joint_limits_interface/joint_limits_urdf.h>
00005 #include <joint_limits_interface/joint_limits_rosparam.h>
00006
00007 #include <controller_manager/controller_manager.h>
00008 #include <controller_manager_msgs/SwitchController.h>
00009
00010 #include <canopen_motor_node/robot_layer.h>
00011
00012 #include "interface_mapping.h"
00013
00014 using namespace canopen;
00015
00016 InterfaceMapping g_interface_mapping;
00017
00018 void RobotLayer::stopControllers(const std::vector<std::string> controllers){
00019 controller_manager_msgs::SwitchController srv;
00020 srv.request.stop_controllers = controllers;
00021 srv.request.strictness = srv.request.BEST_EFFORT;
00022 boost::thread call(boost::bind(ros::service::call<controller_manager_msgs::SwitchController>, "controller_manager/switch_controller", srv));
00023 call.detach();
00024 }
00025
00026 void RobotLayer::add(const std::string &name, boost::shared_ptr<HandleLayerBase> handle){
00027 LayerGroupNoDiag::add(handle);
00028 handles_.insert(std::make_pair(name, handle));
00029 }
00030
00031 RobotLayer::RobotLayer(ros::NodeHandle nh) : LayerGroupNoDiag<HandleLayerBase>("RobotLayer"), nh_(nh), first_init_(true)
00032 {
00033 registerInterface(&state_interface_);
00034 registerInterface(&pos_interface_);
00035 registerInterface(&vel_interface_);
00036 registerInterface(&eff_interface_);
00037
00038 urdf_.initParam("robot_description");
00039 }
00040
00041 void RobotLayer::handleInit(LayerStatus &status){
00042 if(first_init_){
00043 for(HandleMap::iterator it = handles_.begin(); it != handles_.end(); ++it){
00044 joint_limits_interface::JointLimits limits;
00045 joint_limits_interface::SoftJointLimits soft_limits;
00046
00047 urdf::JointConstSharedPtr joint = getJoint(it->first);
00048
00049 if(!joint){
00050 status.error("joint " + it->first + " not found");
00051 return;
00052 }
00053
00054 bool has_joint_limits = joint_limits_interface::getJointLimits(joint, limits);
00055
00056 has_joint_limits = joint_limits_interface::getJointLimits(it->first, nh_, limits) || has_joint_limits;
00057
00058 bool has_soft_limits = has_joint_limits && joint_limits_interface::getSoftJointLimits(joint, soft_limits);
00059
00060 if(!has_joint_limits){
00061 ROS_WARN_STREAM("No limits found for " << it->first);
00062 }
00063
00064 it->second->registerHandle(state_interface_);
00065
00066 const hardware_interface::JointHandle *h = 0;
00067
00068 it->second->registerHandle(pos_interface_, limits, has_soft_limits ? &soft_limits : 0);
00069 it->second->registerHandle(vel_interface_, limits, has_soft_limits ? &soft_limits : 0);
00070 it->second->registerHandle(eff_interface_, limits, has_soft_limits ? &soft_limits : 0);
00071 }
00072 first_init_ = false;
00073 }
00074 LayerGroupNoDiag::handleInit(status);
00075 }
00076
00077 void RobotLayer::enforce(const ros::Duration &period, bool reset){
00078 for(HandleMap::iterator it = handles_.begin(); it != handles_.end(); ++it){
00079 it->second->enforceLimits(period, reset);
00080 }
00081 }
00082 class ModeLookup {
00083 int default_mode_;
00084 bool has_default_mode_;
00085 std::map<std::string, int> lookup_;
00086 bool has_lookup_;
00087 public:
00088 ModeLookup(ros::NodeHandle &nh_c){
00089 has_default_mode_ = nh_c.getParam("required_drive_mode", default_mode_);
00090 has_lookup_ = nh_c.getParam("required_drive_modes", lookup_);
00091 }
00092 bool hasModes() { return has_default_mode_ || has_lookup_; }
00093 bool hasMixedModes() { return has_lookup_; }
00094 bool getMode(MotorBase::OperationMode &om, const std::string &key) {
00095 std::map<std::string, int>::iterator f = lookup_.find(key);
00096 if(f != lookup_.end()){
00097 om = MotorBase::OperationMode(f->second);
00098 return true;
00099 }else if (has_default_mode_) {
00100 om = MotorBase::OperationMode(default_mode_);
00101 return true;
00102 }
00103 return false;
00104 }
00105 };
00106 bool RobotLayer::prepareSwitch(const std::list<hardware_interface::ControllerInfo> &start_list, const std::list<hardware_interface::ControllerInfo> &stop_list) {
00107
00108 (void) &hardware_interface::RobotHW::prepareSwitch;
00109
00110
00111 for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it = stop_list.begin(); controller_it != stop_list.end(); ++controller_it){
00112
00113 if(switch_map_.find(controller_it->name) == switch_map_.end()){
00114 ROS_ERROR_STREAM(controller_it->name << " was not started before");
00115 return false;
00116 }
00117 }
00118
00119
00120 for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it = start_list.begin(); controller_it != start_list.end(); ++controller_it){
00121 SwitchContainer to_switch;
00122 ros::NodeHandle nh(nh_, controller_it->name);
00123 ModeLookup ml(nh);
00124
00125 std::set<std::string> claimed_interfaces;
00126
00127 if(controller_it->claimed_resources.size() > 0){
00128 for (std::vector<hardware_interface::InterfaceResources>::const_iterator cres_it = controller_it->claimed_resources.begin(); cres_it != controller_it->claimed_resources.end(); ++cres_it){
00129 for (std::set<std::string>::const_iterator res_it = cres_it->resources.begin(); res_it != cres_it->resources.end(); ++res_it){
00130 claimed_interfaces.insert(cres_it->hardware_interface);
00131 if(!ml.hasModes()){
00132 ROS_ERROR_STREAM("Please set required_drive_mode(s) for controller " << controller_it->name);
00133 return false;
00134 }
00135 if(claimed_interfaces.size() > 1 && !ml.hasMixedModes()){
00136 ROS_ERROR_STREAM("controller "<< controller_it->name << " has mixed interfaces, please set required_drive_modes.");
00137 return false;
00138 }
00139
00140 boost::unordered_map< std::string, boost::shared_ptr<HandleLayerBase> >::const_iterator h_it = handles_.find(*res_it);
00141
00142 const std::string & joint = *res_it;
00143
00144 if(h_it == handles_.end()){
00145 ROS_ERROR_STREAM(joint << " not found");
00146 return false;
00147 }
00148 SwitchData sd;
00149 sd.enforce_limits = nh.param("enforce_limits", true);
00150
00151 if(!ml.getMode(sd.mode, joint)){
00152 ROS_ERROR_STREAM("could not determine drive mode for " << joint);
00153 return false;
00154 }
00155
00156 if(g_interface_mapping.hasConflict(cres_it->hardware_interface, sd.mode)){
00157 ROS_ERROR_STREAM(cres_it->hardware_interface << " cannot be provided in mode " << sd.mode);
00158 return false;
00159 }
00160
00161 HandleLayerBase::CanSwitchResult res = h_it->second->canSwitch(sd.mode);
00162
00163 switch(res){
00164 case HandleLayerBase::NotSupported:
00165 ROS_ERROR_STREAM("Mode " << sd.mode << " is not available for " << joint);
00166 return false;
00167 case HandleLayerBase::NotReadyToSwitch:
00168 ROS_ERROR_STREAM(joint << " is not ready to switch mode");
00169 return false;
00170 case HandleLayerBase::ReadyToSwitch:
00171 case HandleLayerBase::NoNeedToSwitch:
00172 sd.handle = h_it->second;
00173 to_switch.push_back(sd);
00174 }
00175 }
00176 }
00177 }
00178 switch_map_.insert(std::make_pair(controller_it->name, to_switch));
00179 }
00180
00181
00182 boost::unordered_set<boost::shared_ptr<HandleLayerBase> > to_stop;
00183 std::vector<std::string> failed_controllers;
00184 for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it = stop_list.begin(); controller_it != stop_list.end(); ++controller_it){
00185 SwitchContainer &to_switch = switch_map_.at(controller_it->name);
00186 for(RobotLayer::SwitchContainer::iterator it = to_switch.begin(); it != to_switch.end(); ++it){
00187 to_stop.insert(it->handle);
00188 }
00189 }
00190 for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it = start_list.begin(); controller_it != start_list.end(); ++controller_it){
00191 SwitchContainer &to_switch = switch_map_.at(controller_it->name);
00192 bool okay = true;
00193 for(RobotLayer::SwitchContainer::iterator it = to_switch.begin(); it != to_switch.end(); ++it){
00194 it->handle->switchMode(MotorBase::No_Mode);
00195 }
00196 for(RobotLayer::SwitchContainer::iterator it = to_switch.begin(); it != to_switch.end(); ++it){
00197 if(!it->handle->switchMode(it->mode)){
00198 failed_controllers.push_back(controller_it->name);
00199 ROS_ERROR_STREAM("Could not switch one joint for " << controller_it->name << ", will stop all related joints and the controller.");
00200 for(RobotLayer::SwitchContainer::iterator stop_it = to_switch.begin(); stop_it != to_switch.end(); ++stop_it){
00201 to_stop.insert(stop_it->handle);
00202 }
00203 okay = false;
00204 break;
00205 }else{
00206 it->handle->enableLimits(it->enforce_limits);
00207 }
00208 to_stop.erase(it->handle);
00209 }
00210 }
00211 for(boost::unordered_set<boost::shared_ptr<HandleLayerBase> >::iterator it = to_stop.begin(); it != to_stop.end(); ++it){
00212 (*it)->switchMode(MotorBase::No_Mode);
00213 }
00214 if(!failed_controllers.empty()){
00215 stopControllers(failed_controllers);
00216
00217 }
00218
00219 return true;
00220 }
00221
00222 void RobotLayer::doSwitch(const std::list<hardware_interface::ControllerInfo> &start_list, const std::list<hardware_interface::ControllerInfo> &stop_list) {
00223 std::vector<std::string> failed_controllers;
00224 for (std::list<hardware_interface::ControllerInfo>::const_iterator controller_it = start_list.begin(); controller_it != start_list.end(); ++controller_it){
00225 try{
00226 SwitchContainer &to_switch = switch_map_.at(controller_it->name);
00227 for(RobotLayer::SwitchContainer::iterator it = to_switch.begin(); it != to_switch.end(); ++it){
00228 if(!it->handle->forwardForMode(it->mode)){
00229 failed_controllers.push_back(controller_it->name);
00230 ROS_ERROR_STREAM("Could not switch one joint for " << controller_it->name << ", will stop all related joints and the controller.");
00231 for(RobotLayer::SwitchContainer::iterator stop_it = to_switch.begin(); stop_it != to_switch.end(); ++stop_it){
00232 it->handle->switchMode(MotorBase::No_Mode);
00233 }
00234 break;
00235 }
00236 }
00237
00238 }catch(const std::out_of_range&){
00239 ROS_ERROR_STREAM("Conttroller " << controller_it->name << "not found, will stop it");
00240 failed_controllers.push_back(controller_it->name);
00241 }
00242 }
00243 if(!failed_controllers.empty()){
00244 stopControllers(failed_controllers);
00245 }
00246 }