diff --git a/combined_robot_hw/src/combined_robot_hw.cpp b/combined_robot_hw/src/combined_robot_hw.cpp index f84ec80f6..13039284f 100644 --- a/combined_robot_hw/src/combined_robot_hw.cpp +++ b/combined_robot_hw/src/combined_robot_hw.cpp @@ -46,9 +46,11 @@ namespace combined_robot_hw ROS_ERROR_STREAM("Could not find '" << param_name << "' parameter (namespace: " << robot_hw_nh.getNamespace() << ")."); return false; } - std::vector::iterator it; - for(it = robots.begin();it != robots.end();it++){ - if (!loadRobotHW(*it)){ + + for (const auto& robot : robots) + { + if (!loadRobotHW(robot)) + { return false; } } @@ -59,7 +61,7 @@ namespace combined_robot_hw const std::list& stop_list) { // Call the prepareSwitch method of the single RobotHW objects. - for (auto const & robot_hw : robot_hw_list_) + for (const auto& robot_hw : robot_hw_list_) { std::list filtered_start_list; std::list filtered_stop_list; @@ -68,7 +70,7 @@ namespace combined_robot_hw filterControllerList(start_list, filtered_start_list, robot_hw); filterControllerList(stop_list, filtered_stop_list, robot_hw); - if (!(robot_hw)->prepareSwitch(filtered_start_list, filtered_stop_list)) + if (!robot_hw->prepareSwitch(filtered_start_list, filtered_stop_list)) return false; } return true; @@ -78,7 +80,7 @@ namespace combined_robot_hw const std::list& stop_list) { // Call the doSwitch method of the single RobotHW objects. - for (auto const & robot_hw : robot_hw_list_) + for (const auto& robot_hw : robot_hw_list_) { std::list filtered_start_list; std::list filtered_stop_list; @@ -87,7 +89,7 @@ namespace combined_robot_hw filterControllerList(start_list, filtered_start_list, robot_hw); filterControllerList(stop_list, filtered_stop_list, robot_hw); - (robot_hw)->doSwitch(filtered_start_list, filtered_stop_list); + robot_hw->doSwitch(filtered_start_list, filtered_stop_list); } } @@ -119,10 +121,9 @@ namespace combined_robot_hw ROS_DEBUG("Constructing robot HW '%s' of type '%s'", name.c_str(), type.c_str()); try { - std::vector cur_types = robot_hw_loader_.getDeclaredClasses(); - for(size_t i=0; i < cur_types.size(); i++) + for (const auto& cur_type : robot_hw_loader_.getDeclaredClasses()) { - if (type == cur_types[i]) + if (type == cur_type) { robot_hw = robot_hw_loader_.createUniqueInstance(type); } @@ -182,9 +183,9 @@ namespace combined_robot_hw void CombinedRobotHW::read(const ros::Time& time, const ros::Duration& period) { // Call the read method of the single RobotHW objects. - for (auto const & robot_hw : robot_hw_list_) + for (const auto& robot_hw : robot_hw_list_) { - (robot_hw)->read(time, period); + robot_hw->read(time, period); } } @@ -192,9 +193,9 @@ namespace combined_robot_hw void CombinedRobotHW::write(const ros::Time& time, const ros::Duration& period) { // Call the write method of the single RobotHW objects. - for (auto const & robot_hw : robot_hw_list_) + for (const auto& robot_hw : robot_hw_list_) { - (robot_hw)->write(time, period); + robot_hw->write(time, period); } } @@ -203,21 +204,21 @@ namespace combined_robot_hw hardware_interface::RobotHWSharedPtr robot_hw) { filtered_list.clear(); - for (auto const & it : list) + for (const auto& controller : list) { hardware_interface::ControllerInfo filtered_controller; - filtered_controller.name = it.name; - filtered_controller.type = it.type; + filtered_controller.name = controller.name; + filtered_controller.type = controller.type; - if (it.claimed_resources.empty()) + if (controller.claimed_resources.empty()) { filtered_list.push_back(filtered_controller); continue; } - for (auto const& res_it : it.claimed_resources) + for (const auto& claimed_resource : controller.claimed_resources) { hardware_interface::InterfaceResources filtered_iface_resources; - filtered_iface_resources.hardware_interface = res_it.hardware_interface; + filtered_iface_resources.hardware_interface = claimed_resource.hardware_interface; std::vector r_hw_ifaces = robot_hw->getNames(); auto const if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), filtered_iface_resources.hardware_interface); @@ -228,12 +229,12 @@ namespace combined_robot_hw std::vector r_hw_iface_resources = robot_hw->getInterfaceResources(filtered_iface_resources.hardware_interface); std::set filtered_resources; - for (auto const& ctrl_res : res_it.resources) + for (const auto& resource : claimed_resource.resources) { - std::vector::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), ctrl_res); + std::vector::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource); if (res_name != r_hw_iface_resources.end()) { - filtered_resources.insert(ctrl_res); + filtered_resources.insert(resource); } } filtered_iface_resources.resources = filtered_resources; diff --git a/combined_robot_hw_tests/src/my_robot_hw_1.cpp b/combined_robot_hw_tests/src/my_robot_hw_1.cpp index e86a8e7a9..2ab9239af 100644 --- a/combined_robot_hw_tests/src/my_robot_hw_1.cpp +++ b/combined_robot_hw_tests/src/my_robot_hw_1.cpp @@ -104,17 +104,17 @@ void MyRobotHW1::write(const ros::Time& /*time*/, const ros::Duration& /*period* bool MyRobotHW1::prepareSwitch(const std::list& start_list, const std::list& /*stop_list*/) { - for (auto const& it : start_list) + for (const auto& controller : start_list) { - if (it.claimed_resources.empty()) + if (controller.claimed_resources.empty()) { continue; } - for (auto const& res_it : it.claimed_resources) + for (const auto& res_it : controller.claimed_resources) { std::vector r_hw_ifaces = this->getNames(); - auto const& if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it.hardware_interface); + std::vector::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it.hardware_interface); if (if_name == r_hw_ifaces.end()) // this hardware_interface is not registered on this RobotHW { ROS_ERROR_STREAM("Bad interface: " << res_it.hardware_interface); @@ -123,13 +123,13 @@ bool MyRobotHW1::prepareSwitch(const std::list r_hw_iface_resources = this->getInterfaceResources(res_it.hardware_interface); - for (auto const& ctrl_res : res_it.resources) + for (const auto& resource : res_it.resources) { - auto const& res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), ctrl_res); + std::vector::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource); if (res_name == r_hw_iface_resources.end()) // this resource is not registered on this RobotHW { - ROS_ERROR_STREAM("Bad resource: " << (ctrl_res)); - std::cout << (ctrl_res); + ROS_ERROR_STREAM("Bad resource: " << resource); + std::cout << resource; return false; } } @@ -141,29 +141,29 @@ bool MyRobotHW1::prepareSwitch(const std::list& start_list, const std::list& /*stop_list*/) { - for (auto const& it : start_list) + for (const auto& controller : start_list) { - if (it.claimed_resources.empty()) + if (controller.claimed_resources.empty()) { continue; } - for (auto const& res_it : it.claimed_resources) + for (const auto& claimed_resource : controller.claimed_resources) { std::vector r_hw_ifaces = this->getNames(); - auto const& if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it.hardware_interface); + std::vector::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), claimed_resource.hardware_interface); if (if_name == r_hw_ifaces.end()) // this hardware_interface is not registered on this RobotHW { - throw hardware_interface::HardwareInterfaceException("Hardware_interface " + res_it.hardware_interface + " is not registered"); + throw hardware_interface::HardwareInterfaceException("Hardware_interface " + claimed_resource.hardware_interface + " is not registered"); } - std::vector r_hw_iface_resources = this->getInterfaceResources(res_it.hardware_interface); - for (auto const& ctrl_res : res_it.resources) + std::vector r_hw_iface_resources = this->getInterfaceResources(claimed_resource.hardware_interface); + for (const auto& resource : claimed_resource.resources) { - auto const& res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), ctrl_res); + std::vector::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource); if (res_name == r_hw_iface_resources.end()) // this resource is not registered on this RobotHW { - throw hardware_interface::HardwareInterfaceException("Resource " + ctrl_res + " is not registered"); + throw hardware_interface::HardwareInterfaceException("Resource " + resource + " is not registered"); } } } diff --git a/combined_robot_hw_tests/src/my_robot_hw_2.cpp b/combined_robot_hw_tests/src/my_robot_hw_2.cpp index 4388be7a4..2283ad881 100644 --- a/combined_robot_hw_tests/src/my_robot_hw_2.cpp +++ b/combined_robot_hw_tests/src/my_robot_hw_2.cpp @@ -86,17 +86,17 @@ void MyRobotHW2::write(const ros::Time& /*time*/, const ros::Duration& /*period* bool MyRobotHW2::prepareSwitch(const std::list& start_list, const std::list& /*stop_list*/) { - for (auto const& it : start_list) + for (const auto& controller : start_list) { - if (it.claimed_resources.empty()) + if (controller.claimed_resources.empty()) { continue; } - for (auto const& res_it : it.claimed_resources) + for (const auto& res_it : controller.claimed_resources) { std::vector r_hw_ifaces = this->getNames(); - auto const& if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it.hardware_interface); + std::vector::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it.hardware_interface); if (if_name == r_hw_ifaces.end()) // this hardware_interface is not registered on this RobotHW { ROS_ERROR_STREAM("Bad interface: " << res_it.hardware_interface); @@ -104,12 +104,12 @@ bool MyRobotHW2::prepareSwitch(const std::list r_hw_iface_resources = this->getInterfaceResources(res_it.hardware_interface); - for (auto const& ctrl_res : res_it.resources) + for (const auto& resource : res_it.resources) { - auto const& res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), ctrl_res); + std::vector::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource); if (res_name == r_hw_iface_resources.end()) // this resource is not registered on this RobotHW { - ROS_ERROR_STREAM("Bad resource: " << ctrl_res); + ROS_ERROR_STREAM("Bad resource: " << resource); return false; } } @@ -121,29 +121,29 @@ bool MyRobotHW2::prepareSwitch(const std::list& start_list, const std::list& /*stop_list*/) { - for (auto const& it : start_list) + for (const auto& controller : start_list) { - if (it.claimed_resources.empty()) + if (controller.claimed_resources.empty()) { continue; } - for (auto const& res_it : it.claimed_resources) + for (const auto& claimed_resource : controller.claimed_resources) { std::vector r_hw_ifaces = this->getNames(); - auto const& if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), res_it.hardware_interface); + std::vector::iterator if_name = std::find(r_hw_ifaces.begin(), r_hw_ifaces.end(), claimed_resource.hardware_interface); if (if_name == r_hw_ifaces.end()) // this hardware_interface is not registered on this RobotHW { - throw hardware_interface::HardwareInterfaceException("Hardware_interface " + res_it.hardware_interface + " is not registered"); + throw hardware_interface::HardwareInterfaceException("Hardware_interface " + claimed_resource.hardware_interface + " is not registered"); } - std::vector r_hw_iface_resources = this->getInterfaceResources(res_it.hardware_interface); - for (auto const& ctrl_res : res_it.resources) + std::vector r_hw_iface_resources = this->getInterfaceResources(claimed_resource.hardware_interface); + for (const auto& resource : claimed_resource.resources) { - auto const& res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), ctrl_res); + std::vector::iterator res_name = std::find(r_hw_iface_resources.begin(), r_hw_iface_resources.end(), resource); if (res_name == r_hw_iface_resources.end()) // this resource is not registered on this RobotHW { - throw hardware_interface::HardwareInterfaceException("Resource " + ctrl_res + " is not registered"); + throw hardware_interface::HardwareInterfaceException("Resource " + resource + " is not registered"); } } } diff --git a/combined_robot_hw_tests/src/my_robot_hw_4.cpp b/combined_robot_hw_tests/src/my_robot_hw_4.cpp index 4f916df64..b31d6c15f 100644 --- a/combined_robot_hw_tests/src/my_robot_hw_4.cpp +++ b/combined_robot_hw_tests/src/my_robot_hw_4.cpp @@ -72,9 +72,9 @@ bool MyRobotHW4::prepareSwitch(const std::list& s // To easily test a failure case, any controller that claims resources on MyRobotHW4 will fail if (!start_list.empty() || !stop_list.empty()) { - for (auto const& it : start_list) + for (const auto& controller : start_list) { - if (it.claimed_resources.empty()) + if (controller.claimed_resources.empty()) { continue; } @@ -110,4 +110,3 @@ void MyRobotHW4::doSwitch(const std::list& s } PLUGINLIB_EXPORT_CLASS( combined_robot_hw_tests::MyRobotHW4, hardware_interface::RobotHW) - diff --git a/controller_manager/src/controller_manager.cpp b/controller_manager/src/controller_manager.cpp index f69a844b5..f3decd564 100644 --- a/controller_manager/src/controller_manager.cpp +++ b/controller_manager/src/controller_manager.cpp @@ -80,18 +80,18 @@ void ControllerManager::update(const ros::Time& time, const ros::Duration& perio // Restart all running controllers if motors are re-enabled if (reset_controllers){ - for (size_t i=0; iisRunning()){ - controllers[i].c->stopRequest(time); - controllers[i].c->startRequest(time); + for (const auto& controller : controllers_lists_[used_by_realtime_]){ + if (controller.c->isRunning()){ + controller.c->stopRequest(time); + controller.c->startRequest(time); } } } // Update all controllers - for (size_t i=0; iupdateRequest(time, period); + for (const auto& controller : controllers_lists_[used_by_realtime_]) + controller.c->updateRequest(time, period); // there are controllers to start/stop if (switch_params_.do_switch) @@ -105,11 +105,10 @@ controller_interface::ControllerBase* ControllerManager::getControllerByName(con // Lock recursive mutex in this context boost::recursive_mutex::scoped_lock guard(controllers_lock_); - auto &controllers = controllers_lists_[current_controllers_list_]; - for (size_t i = 0; i < controllers.size(); ++i) + for (const auto& controller : controllers_lists_[current_controllers_list_]) { - if (controllers[i].info.name == name) - return controllers[i].c.get(); + if (controller.info.name == name) + return controller.c.get(); } return nullptr; } @@ -118,10 +117,9 @@ void ControllerManager::getControllerNames(std::vector &names) { boost::recursive_mutex::scoped_lock guard(controllers_lock_); names.clear(); - auto &controllers = controllers_lists_[current_controllers_list_]; - for (size_t i = 0; i < controllers.size(); ++i) + for (const auto& controller : controllers_lists_[current_controllers_list_]) { - names.push_back(controllers[i].info.name); + names.push_back(controller.info.name); } } @@ -151,7 +149,7 @@ void ControllerManager::manageSwitch(const ros::Time& time) void ControllerManager::stopControllers(const ros::Time& time) { // stop controllers - for (auto &request : stop_request_) + for (const auto& request : stop_request_) { if (request->isRunning()) { @@ -165,7 +163,7 @@ void ControllerManager::startControllers(const ros::Time& time) // start controllers if (robot_hw_->switchResult() == hardware_interface::RobotHW::DONE) { - for (auto &request : start_request_) + for (const auto& request : start_request_) { request->startRequest(time); } @@ -177,7 +175,7 @@ void ControllerManager::startControllers(const ros::Time& time) (switch_params_.timeout > 0.0 && (time - switch_params_.init_time).toSec() > switch_params_.timeout)) { - for (auto &request : start_request_) + for (const auto& request : start_request_) { request->abortRequest(time); } @@ -187,7 +185,7 @@ void ControllerManager::startControllers(const ros::Time& time) // wait controllers else { - for (auto &request : start_request_) + for (const auto& request : start_request_) { request->waitRequest(time); } @@ -197,12 +195,12 @@ void ControllerManager::startControllers(const ros::Time& time) void ControllerManager::startControllersAsap(const ros::Time& time) { // start controllers if possible - for (auto &request : start_request_) + for (const auto& request : start_request_) { if (!request->isRunning()) { // find the info from this controller - for (auto &controller : controllers_lists_[current_controllers_list_]) + for (const auto& controller : controllers_lists_[current_controllers_list_]) { if (request == controller.c.get()) { @@ -262,13 +260,13 @@ bool ControllerManager::loadController(const std::string& name) to.clear(); // Copy all controllers from the 'from' list to the 'to' list - for (size_t i = 0; i < from.size(); ++i) - to.push_back(from[i]); + for (const auto& controller : from) + to.push_back(controller); // Checks that we're not duplicating controllers - for (size_t j = 0; j < to.size(); ++j) + for (const auto& controller : to) { - if (to[j].info.name == name) + if (controller.info.name == name) { to.clear(); ROS_ERROR("A controller named '%s' was already loaded inside the controller manager", name.c_str()); @@ -299,12 +297,9 @@ bool ControllerManager::loadController(const std::string& name) // Trying loading the controller using all of our controller loaders. Exit once we've found the first valid loaded controller for (auto const& it : controller_loaders_) { - if(c) - break; - auto cur_types = it->getDeclaredClasses(); - for(size_t i=0; i < cur_types.size(); i++){ - if (type == cur_types[i]){ - c = it->createInstance(type); + for (const auto& cur_type : (*it)->getDeclaredClasses()){ + if (type == cur_type){ + c = (*it)->createInstance(type); } } } @@ -402,10 +397,10 @@ bool ControllerManager::unloadController(const std::string &name) // Transfers the running controllers over, skipping the one to be removed and the running ones. bool removed = false; - for (size_t i = 0; i < from.size(); ++i) + for (const auto& controller : from) { - if (from[i].info.name == name){ - if (from[i].c->isRunning()){ + if (controller.info.name == name){ + if (controller.c->isRunning()){ to.clear(); ROS_ERROR("Could not unload controller with name '%s' because it is still running", name.c_str()); @@ -414,7 +409,7 @@ bool ControllerManager::unloadController(const std::string &name) removed = true; } else - to.push_back(from[i]); + to.push_back(controller); } // Fails if we could not remove the controllers @@ -464,59 +459,59 @@ bool ControllerManager::switchController(const std::vector& start_c } ROS_DEBUG("switching controllers:"); - for (unsigned int i=0; i& start_c switch_stop_list_.clear(); auto &controllers = controllers_lists_[current_controllers_list_]; - for (size_t i = 0; i < controllers.size(); ++i) + for (const auto& controller : controllers) { bool in_stop_list = false; - for(size_t j = 0; j < stop_request_.size(); j++) + for (const auto& request : stop_request_) { - if (stop_request_[j] == controllers[i].c.get()) + if (request == controller.c.get()) { in_stop_list = true; break; @@ -541,17 +536,17 @@ bool ControllerManager::switchController(const std::vector& start_c } bool in_start_list = false; - for(size_t j = 0; j < start_request_.size(); j++) + for (const auto& request : start_request_) { - if (start_request_[j] == controllers[i].c.get()) + if (request == controller.c.get()) { in_start_list = true; break; } } - const bool is_running = controllers[i].c->isRunning(); - hardware_interface::ControllerInfo &info = controllers[i].info; + const bool is_running = controller.c->isRunning(); + const hardware_interface::ControllerInfo &info = controller.info; if(!is_running && in_stop_list){ // check for double stop if(strictness == controller_manager_msgs::SwitchController::Request::STRICT){ @@ -661,10 +656,10 @@ bool ControllerManager::reloadControllerLibrariesSrv( resp.ok = false; return true; } - for (unsigned int i=0; ireload(); - ROS_INFO("Controller manager: reloaded controller libraries for '%s'", it->getName().c_str()); + controller_loader->reload(); + ROS_INFO("Controller manager: reloaded controller libraries for '%s'", controller_loader->getName().c_str()); } resp.ok = true; @@ -699,13 +694,13 @@ bool ControllerManager::listControllerTypesSrv( boost::mutex::scoped_lock guard(services_lock_); ROS_DEBUG("list types service locked"); - for(auto const& it : controller_loaders_) + for (const auto& controller_loader : controller_loaders_) { - std::vector cur_types = it->getDeclaredClasses(); - for(size_t i=0; i < cur_types.size(); i++) + std::vector cur_types = controller_loader->getDeclaredClasses(); + for (const auto& cur_type : cur_types) { - resp.types.push_back(cur_types[i]); - resp.base_classes.push_back(it->getName()); + resp.types.push_back(cur_type); + resp.base_classes.push_back(controller_loader->getName()); } } @@ -740,12 +735,12 @@ bool ControllerManager::listControllersSrv( cs.claimed_resources.clear(); typedef std::vector ClaimedResVec; typedef ClaimedResVec::const_iterator ClaimedResIt; - const ClaimedResVec& c_res = controllers[i].info.claimed_resources; - for (ClaimedResIt c_res_it = c_res.begin(); c_res_it != c_res.end(); ++c_res_it) + const ClaimedResVec& c_resources = controllers[i].info.claimed_resources; + for (const auto& c_resource : c_resources) { controller_manager_msgs::HardwareInterfaceResources iface_res; - iface_res.hardware_interface = c_res_it->hardware_interface; - std::copy(c_res_it->resources.begin(), c_res_it->resources.end(), std::back_inserter(iface_res.resources)); + iface_res.hardware_interface = c_resource.hardware_interface; + std::copy(c_resource.resources.begin(), c_resource.resources.end(), std::back_inserter(iface_res.resources)); cs.claimed_resources.push_back(iface_res); } diff --git a/controller_manager/test/hwi_switch_test.cpp b/controller_manager/test/hwi_switch_test.cpp index f03161b82..b5b6083c6 100644 --- a/controller_manager/test/hwi_switch_test.cpp +++ b/controller_manager/test/hwi_switch_test.cpp @@ -156,26 +156,26 @@ class SwitchBot : public hardware_interface::RobotHW bool j_pe_e = false; bool j_ve_v = false; - for(std::list::const_iterator it = start_list.begin(); it != start_list.end(); ++it) + for (const auto& controller : start_list) { - if (it->claimed_resources.size() != 1) + if (controller.claimed_resources.size() != 1) { ROS_FATAL("We expect controllers to claim resoures from only one interface. This should never happen!"); return false; } - const hardware_interface::InterfaceResources& iface_res = it->claimed_resources.front(); - for (std::set::const_iterator res_it = iface_res.resources.begin(); res_it != iface_res.resources.end(); ++res_it) + const hardware_interface::InterfaceResources& iface_res = controller.claimed_resources.front(); + for (const auto& resource : iface_res.resources) { // special check - if(iface_res.hardware_interface == "hardware_interface::EffortJointInterface" && *res_it == "j_pe") j_pe_e = true; - else if(iface_res.hardware_interface == "hardware_interface::VelocityJointInterface" && *res_it == "j_ve") j_ve_v = true; + if(iface_res.hardware_interface == "hardware_interface::EffortJointInterface" && resource == "j_pe") j_pe_e = true; + else if(iface_res.hardware_interface == "hardware_interface::VelocityJointInterface" && resource == "j_ve") j_ve_v = true; // per joint check try { - if(!joints_.at(*res_it)->prepareSwitch(iface_res.hardware_interface)) + if(!joints_.at(resource)->prepareSwitch(iface_res.hardware_interface)) { - ROS_ERROR_STREAM("Cannot switch " << *res_it << " to " << iface_res.hardware_interface); + ROS_ERROR_STREAM("Cannot switch " << resource << " to " << iface_res.hardware_interface); return false; } } @@ -193,29 +193,29 @@ class SwitchBot : public hardware_interface::RobotHW RobotHW::doSwitch(start_list, stop_list); // check if member is defined std::map switches; - for(std::list::const_iterator it = stop_list.begin(); it != stop_list.end(); ++it) + for (const auto& controller : stop_list) { - started_.erase(std::remove(started_.begin(), started_.end(), it->name), started_.end()); - stopped_.push_back(it->name); - const hardware_interface::InterfaceResources& iface_res = it->claimed_resources.front(); - for (std::set::const_iterator res_it = iface_res.resources.begin(); res_it != iface_res.resources.end(); ++res_it) + started_.erase(std::remove(started_.begin(), started_.end(), controller.name), started_.end()); + stopped_.push_back(controller.name); + const hardware_interface::InterfaceResources& iface_res = controller.claimed_resources.front(); + for (const auto& resource : iface_res.resources) { - switches[*res_it] = ""; + switches[resource] = ""; } } - for(std::list::const_iterator it = start_list.begin(); it != start_list.end(); ++it) + for (const auto& controller : start_list) { - stopped_.erase(std::remove(stopped_.begin(), stopped_.end(), it->name), stopped_.end()); - started_.push_back(it->name); - const hardware_interface::InterfaceResources& iface_res = it->claimed_resources.front(); - for (std::set::const_iterator res_it = iface_res.resources.begin(); res_it != iface_res.resources.end(); ++res_it) + stopped_.erase(std::remove(stopped_.begin(), stopped_.end(), controller.name), stopped_.end()); + started_.push_back(controller.name); + const hardware_interface::InterfaceResources& iface_res = controller.claimed_resources.front(); + for (const auto& resource : iface_res.resources) { - switches[*res_it] = iface_res.hardware_interface; + switches[resource] = iface_res.hardware_interface; } } - for(std::map::iterator it = switches.begin(); it != switches.end(); ++it) + for (const auto& to_switch : switches) { - joints_[it->first]->doSwitch(it->second); + joints_[to_switch.first]->doSwitch(to_switch.second); } } bool checkUnqiue() const @@ -279,9 +279,9 @@ class DummyControllerLoader: public controller_manager::ControllerLoaderInterfac virtual std::vector getDeclaredClasses() { std::vector v; - for(std::map::iterator it = classes.begin(); it != classes.end(); ++it) + for (const auto& declared_class : classes) { - v.push_back(it->first); + v.push_back(declared_class.first); } return v; } diff --git a/controller_manager_tests/src/effort_test_controller.cpp b/controller_manager_tests/src/effort_test_controller.cpp index 3515ab815..e54abbd13 100644 --- a/controller_manager_tests/src/effort_test_controller.cpp +++ b/controller_manager_tests/src/effort_test_controller.cpp @@ -44,8 +44,8 @@ bool EffortTestController::init(hardware_interface::EffortJointInterface* hw, ro joint_names.push_back("hiDOF_joint2"); } - for (unsigned i=0; igetHandle(joint_names[i])); + for (const auto& joint_name : joint_names) + joint_effort_commands_.push_back(hw->getHandle(joint_name)); return true; } @@ -56,12 +56,7 @@ void EffortTestController::starting(const ros::Time& /*time*/) } void EffortTestController::update(const ros::Time& /*time*/, const ros::Duration& /*period*/) -{ - for (unsigned int i=0; i < joint_effort_commands_.size(); i++) - { - - } -} +{} void EffortTestController::stopping(const ros::Time& /*time*/) { diff --git a/controller_manager_tests/src/pos_eff_controller.cpp b/controller_manager_tests/src/pos_eff_controller.cpp index ae413be54..00e9407ec 100644 --- a/controller_manager_tests/src/pos_eff_controller.cpp +++ b/controller_manager_tests/src/pos_eff_controller.cpp @@ -37,7 +37,6 @@ bool PosEffController::init(hardware_interface::RobotHW* robot_hw, ros::NodeHand std::vector eff_joints; if (!n.getParam("effort_joints", eff_joints)) {return false;} - typedef std::vector::const_iterator NamesIterator; typedef hardware_interface::PositionJointInterface PosIface; typedef hardware_interface::EffortJointInterface EffIface; @@ -46,14 +45,14 @@ bool PosEffController::init(hardware_interface::RobotHW* robot_hw, ros::NodeHand EffIface* eff_iface = robot_hw->get(); // populate command handles (claimed resources) - for (NamesIterator it = pos_joints.begin(); it != pos_joints.end(); it++) + for (const auto& pos_joint : pos_joints) { - pos_cmd_.push_back(pos_iface->getHandle(*it)); + pos_cmd_.push_back(pos_iface->getHandle(pos_joint)); } - for (NamesIterator it = eff_joints.begin(); it != eff_joints.end(); it++) + for (const auto& eff_joint : eff_joints) { - eff_cmd_.push_back(eff_iface->getHandle(*it)); + eff_cmd_.push_back(eff_iface->getHandle(eff_joint)); } return true; diff --git a/controller_manager_tests/src/pos_eff_opt_controller.cpp b/controller_manager_tests/src/pos_eff_opt_controller.cpp index 2866f3d40..a181abb5c 100644 --- a/controller_manager_tests/src/pos_eff_opt_controller.cpp +++ b/controller_manager_tests/src/pos_eff_opt_controller.cpp @@ -37,7 +37,6 @@ bool PosEffOptController::init(hardware_interface::RobotHW* robot_hw, ros::NodeH std::vector eff_joints; if (!n.getParam("effort_joints", eff_joints)) {return false;} - typedef std::vector::const_iterator NamesIterator; typedef hardware_interface::PositionJointInterface PosIface; typedef hardware_interface::EffortJointInterface EffIface; @@ -50,9 +49,9 @@ bool PosEffOptController::init(hardware_interface::RobotHW* robot_hw, ros::NodeH // populate command handles (claimed resources) if (pos_iface) { - for (NamesIterator it = pos_joints.begin(); it != pos_joints.end(); it++) + for (const auto& pos_joint : pos_joints) { - pos_cmd_.push_back(pos_iface->getHandle(*it)); + pos_cmd_.push_back(pos_iface->getHandle(pos_joint)); } } else @@ -62,9 +61,9 @@ bool PosEffOptController::init(hardware_interface::RobotHW* robot_hw, ros::NodeH if (eff_iface) { - for (NamesIterator it = eff_joints.begin(); it != eff_joints.end(); it++) + for (const auto& eff_joint : eff_joints) { - eff_cmd_.push_back(eff_iface->getHandle(*it)); + eff_cmd_.push_back(eff_iface->getHandle(eff_joint)); } } else diff --git a/controller_manager_tests/src/vel_eff_controller.cpp b/controller_manager_tests/src/vel_eff_controller.cpp index 38f6dc2d5..f338726fe 100644 --- a/controller_manager_tests/src/vel_eff_controller.cpp +++ b/controller_manager_tests/src/vel_eff_controller.cpp @@ -37,7 +37,6 @@ bool VelEffController::init(hardware_interface::RobotHW* robot_hw, ros::NodeHand std::vector eff_joints; if (!n.getParam("effort_joints", eff_joints)) {return false;} - typedef std::vector::const_iterator NamesIterator; typedef hardware_interface::VelocityJointInterface VelIface; typedef hardware_interface::EffortJointInterface EffIface; @@ -46,13 +45,13 @@ bool VelEffController::init(hardware_interface::RobotHW* robot_hw, ros::NodeHand EffIface* eff_iface = robot_hw->get(); // populate command handles (claimed resources) - for (NamesIterator it = vel_joints.begin(); it != vel_joints.end(); it++) + for (const auto& vel_joint : vel_joints) { - vel_cmd_.push_back(vel_iface->getHandle(*it)); + vel_cmd_.push_back(vel_iface->getHandle(vel_joint)); } - for (NamesIterator it = eff_joints.begin(); it != eff_joints.end(); it++) + for (const auto& eff_joint : eff_joints) { - eff_cmd_.push_back(eff_iface->getHandle(*it)); + eff_cmd_.push_back(eff_iface->getHandle(eff_joint)); } diff --git a/hardware_interface/include/hardware_interface/internal/interface_manager.h b/hardware_interface/include/hardware_interface/internal/interface_manager.h index 913749ec3..06b2e6eb7 100644 --- a/hardware_interface/include/hardware_interface/internal/interface_manager.h +++ b/hardware_interface/include/hardware_interface/internal/interface_manager.h @@ -54,10 +54,8 @@ struct CheckIsResourceManager { template static void callCM(typename std::vector& managers, C* result, typename C::resource_manager_type*) { - std::vector managers_in; - // we have to typecase back to base class - for(typename std::vector::iterator it = managers.begin(); it != managers.end(); ++it) - managers_in.push_back(static_cast(*it)); + // We have to typecast back to base class + std::vector managers_in(managers.begin(), managers.end()); C::concatManagers(managers_in, result); } @@ -171,9 +169,8 @@ class InterfaceManager } // look for interfaces registered in the registered hardware - for(InterfaceManagerVector::iterator it = interface_managers_.begin(); - it != interface_managers_.end(); ++it) { - T* iface = (*it)->get(); + for (const auto& interface_manager : interface_managers_) { + T* iface = interface_manager->get(); if (iface) iface_list.push_back(iface); } @@ -219,9 +216,9 @@ class InterfaceManager { std::vector out; out.reserve(interfaces_.size()); - for(InterfaceMap::const_iterator it = interfaces_.begin(); it != interfaces_.end(); ++it) + for (const auto& interface : interfaces_) { - out.push_back(it->first); + out.push_back(interface.first); } return out; } diff --git a/hardware_interface/include/hardware_interface/internal/resource_manager.h b/hardware_interface/include/hardware_interface/internal/resource_manager.h index 008a97318..f6a208432 100644 --- a/hardware_interface/include/hardware_interface/internal/resource_manager.h +++ b/hardware_interface/include/hardware_interface/internal/resource_manager.h @@ -80,9 +80,9 @@ class ResourceManager : public ResourceManagerBase { std::vector out; out.reserve(resource_map_.size()); - for(typename ResourceMap::const_iterator it = resource_map_.begin(); it != resource_map_.end(); ++it) + for (const auto& resource_name_and_handle : resource_map_) { - out.push_back(it->first); + out.push_back(resource_name_and_handle.first); } return out; } @@ -136,12 +136,9 @@ class ResourceManager : public ResourceManagerBase static void concatManagers(std::vector& managers, resource_manager_type* result) { - for(typename std::vector::iterator it_man = managers.begin(); - it_man != managers.end(); ++it_man) { - std::vector handle_names = (*it_man)->getNames(); - for(std::vector::iterator it_nms = handle_names.begin(); - it_nms != handle_names.end(); ++it_nms) { - result->registerHandle((*it_man)->getHandle(*it_nms)); + for (const auto& manager : managers) { + for (const auto& handle_name : manager->getNames()) { + result->registerHandle(manager->getHandle(handle_name)); } } } diff --git a/hardware_interface/include/hardware_interface/robot_hw.h b/hardware_interface/include/hardware_interface/robot_hw.h index d0a9253c3..a70340898 100644 --- a/hardware_interface/include/hardware_interface/robot_hw.h +++ b/hardware_interface/include/hardware_interface/robot_hw.h @@ -92,38 +92,31 @@ class RobotHW : public InterfaceManager virtual bool checkForConflict(const std::list& info) const { // Map from resource name to all controllers claiming it - typedef std::map > CtrlInfoMap; - - typedef std::list::const_iterator CtrlInfoIt; - typedef std::vector::const_iterator ClaimedResIt; - typedef std::set::const_iterator ResourceIt; + std::map> resource_map; // Populate a map of all controllers claiming individual resources. // We do this by iterating over every claimed resource of every hardware interface used by every controller - CtrlInfoMap resource_map; - for (CtrlInfoIt info_it = info.begin(); info_it != info.end(); ++info_it) + for (const auto& controller_info : info) { - const std::vector& c_res = info_it->claimed_resources; - for (ClaimedResIt c_res_it = c_res.begin(); c_res_it != c_res.end(); ++c_res_it) + for (const auto& claimed_resource : controller_info.claimed_resources) { - const std::set& iface_resources = c_res_it->resources; - for (ResourceIt resource_it = iface_resources.begin(); resource_it != iface_resources.end(); ++resource_it) + for (const auto& iface_resource : claimed_resource.resources) { - resource_map[*resource_it].push_back(*info_it); + resource_map[iface_resource].push_back(controller_info); } } } // Enforce resource exclusivity policy: No resource can be claimed by more than one controller bool in_conflict = false; - for (CtrlInfoMap::iterator it = resource_map.begin(); it != resource_map.end(); ++it) + for (const auto& resource_name_and_claiming_controllers : resource_map) { - if (it->second.size() > 1) + if (resource_name_and_claiming_controllers.second.size() > 1) { std::string controller_list; - for (CtrlInfoIt controller_it = it->second.begin(); controller_it != it->second.end(); ++controller_it) - controller_list += controller_it->name + ", "; - ROS_WARN("Resource conflict on [%s]. Controllers = [%s]", it->first.c_str(), controller_list.c_str()); + for (const auto& controller : resource_name_and_claiming_controllers.second) + controller_list += controller.name + ", "; + ROS_WARN("Resource conflict on [%s]. Controllers = [%s]", resource_name_and_claiming_controllers.first.c_str(), controller_list.c_str()); in_conflict = true; } } diff --git a/joint_limits_interface/include/joint_limits_interface/joint_limits_interface.h b/joint_limits_interface/include/joint_limits_interface/joint_limits_interface.h index c86b793e3..8fa71eb37 100644 --- a/joint_limits_interface/include/joint_limits_interface/joint_limits_interface.h +++ b/joint_limits_interface/include/joint_limits_interface/joint_limits_interface.h @@ -561,10 +561,9 @@ class JointLimitsInterface : public hardware_interface::ResourceManager::ResourceMap::iterator ItratorType; - for (ItratorType it = this->resource_map_.begin(); it != this->resource_map_.end(); ++it) + for (auto&& resource_name_and_handle : this->resource_map_) { - it->second.enforceLimits(period); + resource_name_and_handle.second.enforceLimits(period); } } /*\}*/ @@ -578,10 +577,9 @@ class PositionJointSaturationInterface : public JointLimitsInterface::ResourceMap::iterator ItratorType; - for (ItratorType it = this->resource_map_.begin(); it != this->resource_map_.end(); ++it) + for (auto&& resource_name_and_handle : this->resource_map_) { - it->second.reset(); + resource_name_and_handle.second.reset(); } } /*\}*/ @@ -595,10 +593,9 @@ class PositionJointSoftLimitsInterface : public JointLimitsInterface::ResourceMap::iterator ItratorType; - for (ItratorType it = this->resource_map_.begin(); it != this->resource_map_.end(); ++it) + for (auto&& resource_name_and_handle : this->resource_map_) { - it->second.reset(); + resource_name_and_handle.second.reset(); } } /*\}*/ diff --git a/transmission_interface/include/transmission_interface/transmission_interface.h b/transmission_interface/include/transmission_interface/transmission_interface.h index f7d8a22e6..0b3b87a22 100644 --- a/transmission_interface/include/transmission_interface/transmission_interface.h +++ b/transmission_interface/include/transmission_interface/transmission_interface.h @@ -180,9 +180,9 @@ class TransmissionHandle private: static bool hasValidPointers(const std::vector& data) { - for (std::vector::const_iterator it = data.begin(); it != data.end(); ++it) + for (const auto& ptr : data) { - if (!(*it)) {return false;} + if (!ptr) {return false;} } return true; } @@ -403,10 +403,9 @@ class TransmissionInterface : public hardware_interface::ResourceManager::ResourceMap::iterator ItratorType; - for (ItratorType it = this->resource_map_.begin(); it != this->resource_map_.end(); ++it) + for (auto&& resource_name_and_handle : this->resource_map_) { - it->second.propagate(); + resource_name_and_handle.second.propagate(); } } /*\}*/ diff --git a/transmission_interface/include/transmission_interface/transmission_interface_loader.h b/transmission_interface/include/transmission_interface/transmission_interface_loader.h index 9279e2ff7..9aaec1b54 100644 --- a/transmission_interface/include/transmission_interface/transmission_interface_loader.h +++ b/transmission_interface/include/transmission_interface/transmission_interface_loader.h @@ -274,7 +274,7 @@ class RequisiteProvider // TODO: There must be a more descriptive name for this } // Get handles to all required resource - for (const ActuatorInfo& info : actuators_info) + for (const auto& info : actuators_info) { try { diff --git a/transmission_interface/src/effort_joint_interface_provider.cpp b/transmission_interface/src/effort_joint_interface_provider.cpp index 9393e9ee0..b9ab5b941 100644 --- a/transmission_interface/src/effort_joint_interface_provider.cpp +++ b/transmission_interface/src/effort_joint_interface_provider.cpp @@ -55,7 +55,7 @@ bool EffortJointInterfaceProvider::updateJointInterfaces(const TransmissionInfo& EffortJointInterface& interface = *(robot_hw->get()); // Register joints on the hardware interface - for (const JointInfo& joint_info : transmission_info.joints_) + for (const auto& joint_info : transmission_info.joints_) { const std::string& name = joint_info.name_; diff --git a/transmission_interface/src/joint_state_interface_provider.cpp b/transmission_interface/src/joint_state_interface_provider.cpp index 8db4b776f..f236c8fc0 100644 --- a/transmission_interface/src/joint_state_interface_provider.cpp +++ b/transmission_interface/src/joint_state_interface_provider.cpp @@ -49,7 +49,7 @@ bool JointStateInterfaceProvider::updateJointInterfaces(const TransmissionInfo& JointStateInterface& interface = *(robot_hw->get()); // Register joints on the hardware interface - for (const JointInfo& joint_info : transmission_info.joints_) + for (const auto& joint_info : transmission_info.joints_) { const std::string& name = joint_info.name_; diff --git a/transmission_interface/src/position_joint_interface_provider.cpp b/transmission_interface/src/position_joint_interface_provider.cpp index 7e71287fb..d0326628e 100644 --- a/transmission_interface/src/position_joint_interface_provider.cpp +++ b/transmission_interface/src/position_joint_interface_provider.cpp @@ -55,7 +55,7 @@ bool PositionJointInterfaceProvider::updateJointInterfaces(const TransmissionInf PositionJointInterface& interface = *(robot_hw->get()); // Register joints on the hardware interface - for (const JointInfo& joint_info : transmission_info.joints_) + for (const auto& joint_info : transmission_info.joints_) { const std::string& name = joint_info.name_; diff --git a/transmission_interface/src/transmission_interface_loader.cpp b/transmission_interface/src/transmission_interface_loader.cpp index 4de72acb0..e3bfbe66d 100644 --- a/transmission_interface/src/transmission_interface_loader.cpp +++ b/transmission_interface/src/transmission_interface_loader.cpp @@ -123,7 +123,7 @@ bool TransmissionInterfaceLoader::load(const std::string& urdf) bool TransmissionInterfaceLoader::load(const std::vector& transmission_info_vec) { - for (const TransmissionInfo& info : transmission_info_vec) + for (const auto& info : transmission_info_vec) { if (!load(info)) {return false;} } @@ -150,7 +150,7 @@ bool TransmissionInterfaceLoader::load(const TransmissionInfo& transmission_info // We currently only deal with transmissions specifying a single hardware interface in the joints assert(!transmission_info.joints_.empty() && !transmission_info.joints_.front().hardware_interfaces_.empty()); const std::vector& hw_ifaces_ref = transmission_info.joints_.front().hardware_interfaces_; // First joint - for (const JointInfo& jnt_info : transmission_info.joints_) + for (const auto& jnt_info : transmission_info.joints_) { // Error out if at least one joint has a different set of hardware interfaces if (hw_ifaces_ref.size() != jnt_info.hardware_interfaces_.size() || @@ -166,7 +166,7 @@ bool TransmissionInterfaceLoader::load(const TransmissionInfo& transmission_info // Load transmission for all specified hardware interfaces bool has_at_least_one_hw_iface = false; - for (const std::string& hw_iface : hw_ifaces_ref) + for (const auto& hw_iface : hw_ifaces_ref) { RequisiteProviderPtr req_provider; try diff --git a/transmission_interface/src/velocity_joint_interface_provider.cpp b/transmission_interface/src/velocity_joint_interface_provider.cpp index 7adfb2fff..a3cca76e0 100644 --- a/transmission_interface/src/velocity_joint_interface_provider.cpp +++ b/transmission_interface/src/velocity_joint_interface_provider.cpp @@ -55,7 +55,7 @@ bool VelocityJointInterfaceProvider::updateJointInterfaces(const TransmissionInf VelocityJointInterface& interface = *(robot_hw->get()); // Register joints on the hardware interface - for (const JointInfo& joint_info : transmission_info.joints_) + for (const auto& joint_info : transmission_info.joints_) { const std::string& name = joint_info.name_; diff --git a/transmission_interface/test/differential_transmission_loader_test.cpp b/transmission_interface/test/differential_transmission_loader_test.cpp index c55e7ff47..14e896910 100644 --- a/transmission_interface/test/differential_transmission_loader_test.cpp +++ b/transmission_interface/test/differential_transmission_loader_test.cpp @@ -113,7 +113,7 @@ TEST(DifferentialTransmissionLoaderTest, InvalidSpec) TransmissionLoaderSharedPtr transmission_loader = loader.create(infos.front().type_); ASSERT_TRUE(nullptr != transmission_loader); - for (const TransmissionInfo& info : infos) + for (const auto& info : infos) { TransmissionSharedPtr transmission; transmission = transmission_loader->load(info); diff --git a/transmission_interface/test/differential_transmission_test.cpp b/transmission_interface/test/differential_transmission_test.cpp index 4d763f278..c6a51c263 100644 --- a/transmission_interface/test/differential_transmission_test.cpp +++ b/transmission_interface/test/differential_transmission_test.cpp @@ -312,7 +312,7 @@ TEST_F(BlackBoxTest, IdentityMap) TransList trans_list = createTestInstances(100); // NOTE: Magic value // Test different transmission configurations... - for (TransList::iterator it = trans_list.begin(); it != trans_list.end(); ++it) + for (auto&& transmission : trans_list) { // ...and for each transmission, different input values RandomDoubleGenerator rand_gen(-1000.0, 1000.0); // NOTE: Magic value @@ -320,7 +320,7 @@ TEST_F(BlackBoxTest, IdentityMap) for (unsigned int i = 0; i < input_value_trials; ++i) { vector input_value = randomVector(2, rand_gen); - testIdentityMap(*it, input_value); + testIdentityMap(transmission, input_value); } } } diff --git a/transmission_interface/test/four_bar_linkage_transmission_loader_test.cpp b/transmission_interface/test/four_bar_linkage_transmission_loader_test.cpp index 101943c62..29188041f 100644 --- a/transmission_interface/test/four_bar_linkage_transmission_loader_test.cpp +++ b/transmission_interface/test/four_bar_linkage_transmission_loader_test.cpp @@ -115,7 +115,7 @@ TEST(FourBarLinkageTransmissionLoaderTest, InvalidSpec) TransmissionLoaderSharedPtr transmission_loader = loader.create(infos.front().type_); ASSERT_TRUE(nullptr != transmission_loader); - for (const TransmissionInfo& info : infos) + for (const auto& info : infos) { TransmissionSharedPtr transmission; transmission = transmission_loader->load(info); diff --git a/transmission_interface/test/four_bar_linkage_transmission_test.cpp b/transmission_interface/test/four_bar_linkage_transmission_test.cpp index bb097e0e3..1bb5162cd 100644 --- a/transmission_interface/test/four_bar_linkage_transmission_test.cpp +++ b/transmission_interface/test/four_bar_linkage_transmission_test.cpp @@ -312,7 +312,7 @@ TEST_F(BlackBoxTest, IdentityMap) TransList trans_list = createTestInstances(100); // NOTE: Magic value // Test different transmission configurations... - for (TransList::iterator it = trans_list.begin(); it != trans_list.end(); ++it) + for (auto&& transmission : trans_list) { // ...and for each transmission, different input values RandomDoubleGenerator rand_gen(-1000.0, 1000.0); // NOTE: Magic value @@ -320,7 +320,7 @@ TEST_F(BlackBoxTest, IdentityMap) for (unsigned int i = 0; i < input_value_trials; ++i) { vector input_value = randomVector(2, rand_gen); - testIdentityMap(*it, input_value); + testIdentityMap(transmission, input_value); } } } diff --git a/transmission_interface/test/simple_transmission_loader_test.cpp b/transmission_interface/test/simple_transmission_loader_test.cpp index ec4cd01ec..ffd9180a2 100644 --- a/transmission_interface/test/simple_transmission_loader_test.cpp +++ b/transmission_interface/test/simple_transmission_loader_test.cpp @@ -95,7 +95,7 @@ TEST(SimpleTransmissionLoaderTest, InvalidSpec) TransmissionLoaderSharedPtr transmission_loader = loader.create(infos.front().type_); ASSERT_TRUE(nullptr != transmission_loader); - for (const TransmissionInfo& info : infos) + for (const auto& info : infos) { TransmissionSharedPtr transmission; transmission = transmission_loader->load(info);