Go to the documentation of this file.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
00030 #ifndef CONTROLLER_INTERFACE_MULTI_INTERFACE_CONTROLLER_H
00031 #define CONTROLLER_INTERFACE_MULTI_INTERFACE_CONTROLLER_H
00032
00033 #include <algorithm>
00034 #include <sstream>
00035
00036 #include <controller_interface/controller_base.h>
00037 #include <hardware_interface/internal/demangle_symbol.h>
00038 #include <hardware_interface/robot_hw.h>
00039 #include <hardware_interface/hardware_interface.h>
00040 #include <ros/ros.h>
00041
00042 namespace controller_interface
00043 {
00044
00046 namespace internal
00047 {
00048
00049 template <class T>
00050 bool hasInterface(hardware_interface::RobotHW* robot_hw);
00051
00052 template <class T>
00053 void clearClaims(hardware_interface::RobotHW* robot_hw);
00054
00055 template <class T>
00056 void extractInterfaceResources(hardware_interface::RobotHW* robot_hw_in,
00057 hardware_interface::RobotHW* robot_hw_out);
00058
00059 template <class T>
00060 void populateClaimedResources(hardware_interface::RobotHW* robot_hw,
00061 ControllerBase::ClaimedResources& claimed_resources);
00062
00063 template <class T>
00064 std::string enumerateElements(const T& val,
00065 const std::string& delimiter = ", ",
00066 const std::string& prefix = "",
00067 const std::string& suffix = "");
00068
00069 }
00193 template <class T1, class T2 = void, class T3 = void, class T4 = void>
00194 class MultiInterfaceController: public ControllerBase
00195 {
00196 public:
00202 MultiInterfaceController(bool allow_optional_interfaces = false)
00203 : allow_optional_interfaces_(allow_optional_interfaces)
00204 {state_ = CONSTRUCTED;}
00205
00206 virtual ~MultiInterfaceController() {}
00207
00235 virtual bool init(hardware_interface::RobotHW* ,
00236 ros::NodeHandle& )
00237 {return true;}
00238
00265 virtual bool init(hardware_interface::RobotHW* ,
00266 ros::NodeHandle& ,
00267 ros::NodeHandle& )
00268 {return true;}
00269
00270 protected:
00293 virtual bool initRequest(hardware_interface::RobotHW* robot_hw,
00294 ros::NodeHandle& root_nh,
00295 ros::NodeHandle& controller_nh,
00296 ClaimedResources& claimed_resources)
00297 {
00298
00299 if (state_ != CONSTRUCTED){
00300 ROS_ERROR("Cannot initialize this controller because it failed to be constructed");
00301 return false;
00302 }
00303
00304
00305 if (!allow_optional_interfaces_ && !hasRequiredInterfaces(robot_hw)) {return false;}
00306
00307
00308 hardware_interface::RobotHW* robot_hw_ctrl_p = &robot_hw_ctrl_;
00309 extractInterfaceResources(robot_hw, robot_hw_ctrl_p);
00310
00311
00312 clearClaims(robot_hw_ctrl_p);
00313 if (!init(robot_hw_ctrl_p, controller_nh) || !init(robot_hw_ctrl_p, root_nh, controller_nh))
00314 {
00315 ROS_ERROR("Failed to initialize the controller");
00316 return false;
00317 }
00318
00319
00320 claimed_resources.clear();
00321 populateClaimedResources(robot_hw_ctrl_p, claimed_resources);
00322 clearClaims(robot_hw_ctrl_p);
00323
00324
00325
00326
00327
00328 state_ = INITIALIZED;
00329 return true;
00330 }
00331
00332
00333
00340 static bool hasRequiredInterfaces(hardware_interface::RobotHW* robot_hw)
00341 {
00342 using internal::hasInterface;
00343 return hasInterface<T1>(robot_hw) &&
00344 hasInterface<T2>(robot_hw) &&
00345 hasInterface<T3>(robot_hw) &&
00346 hasInterface<T4>(robot_hw);
00347 }
00348
00354 static void clearClaims(hardware_interface::RobotHW* robot_hw)
00355 {
00356 using internal::clearClaims;
00357 clearClaims<T1>(robot_hw);
00358 clearClaims<T2>(robot_hw);
00359 clearClaims<T3>(robot_hw);
00360 clearClaims<T4>(robot_hw);
00361 }
00362
00371 static void extractInterfaceResources(hardware_interface::RobotHW* robot_hw_in,
00372 hardware_interface::RobotHW* robot_hw_out)
00373 {
00374 using internal::extractInterfaceResources;
00375 extractInterfaceResources<T1>(robot_hw_in, robot_hw_out);
00376 extractInterfaceResources<T2>(robot_hw_in, robot_hw_out);
00377 extractInterfaceResources<T3>(robot_hw_in, robot_hw_out);
00378 extractInterfaceResources<T4>(robot_hw_in, robot_hw_out);
00379 }
00380
00389 static void populateClaimedResources(hardware_interface::RobotHW* robot_hw,
00390 ClaimedResources& claimed_resources)
00391 {
00392 using internal::populateClaimedResources;
00393 populateClaimedResources<T1>(robot_hw, claimed_resources);
00394 populateClaimedResources<T2>(robot_hw, claimed_resources);
00395 populateClaimedResources<T3>(robot_hw, claimed_resources);
00396 populateClaimedResources<T4>(robot_hw, claimed_resources);
00397 }
00398
00400 hardware_interface::RobotHW robot_hw_ctrl_;
00401
00403 bool allow_optional_interfaces_;
00404
00405 private:
00406 MultiInterfaceController(const MultiInterfaceController& c);
00407 MultiInterfaceController& operator =(const MultiInterfaceController& c);
00408 };
00409
00410
00411 namespace internal
00412 {
00413
00414 template <class T>
00415 inline bool hasInterface(hardware_interface::RobotHW* robot_hw)
00416 {
00417 T* hw = robot_hw->get<T>();
00418 if (!hw)
00419 {
00420 const std::string hw_name = hardware_interface::internal::demangledTypeName<T>();
00421 ROS_ERROR_STREAM("This controller requires a hardware interface of type '" << hw_name << "', " <<
00422 "but is not exposed by the robot. Available interfaces in robot:\n" <<
00423 enumerateElements(robot_hw->getNames(), "\n", "- '", "'"));
00424 return false;
00425 }
00426 return true;
00427 }
00428
00429
00430 template <>
00431 inline bool hasInterface<void>(hardware_interface::RobotHW* ) {return true;}
00432
00433 template <class T>
00434 void clearClaims(hardware_interface::RobotHW* robot_hw)
00435 {
00436 T* hw = robot_hw->get<T>();
00437 if (hw) {hw->clearClaims();}
00438 }
00439
00440
00441 template <>
00442 inline void clearClaims<void>(hardware_interface::RobotHW* ) {}
00443
00444 template <class T>
00445 inline void extractInterfaceResources(hardware_interface::RobotHW* robot_hw_in,
00446 hardware_interface::RobotHW* robot_hw_out)
00447 {
00448 T* hw = robot_hw_in->get<T>();
00449 if (hw) {robot_hw_out->registerInterface(hw);}
00450 }
00451
00452
00453 template <>
00454 inline void extractInterfaceResources<void>(hardware_interface::RobotHW* ,
00455 hardware_interface::RobotHW* ) {}
00456
00457 template <class T>
00458 inline void populateClaimedResources(hardware_interface::RobotHW* robot_hw,
00459 ControllerBase::ClaimedResources& claimed_resources)
00460 {
00461 T* hw = robot_hw->get<T>();
00462 if (hw)
00463 {
00464 hardware_interface::InterfaceResources iface_res;
00465 iface_res.hardware_interface = hardware_interface::internal::demangledTypeName<T>();
00466 iface_res.resources = hw->getClaims();
00467 claimed_resources.push_back(iface_res);
00468 }
00469 }
00470
00471
00472 template <>
00473 inline void populateClaimedResources<void>(hardware_interface::RobotHW* ,
00474 ControllerBase::ClaimedResources& ) {}
00475
00476 template <class T>
00477 inline std::string enumerateElements(const T& val,
00478 const std::string& delimiter,
00479 const std::string& prefix,
00480 const std::string& suffix)
00481 {
00482 std::string ret;
00483 if (val.empty()) {return ret;}
00484
00485 const std::string sdp = suffix+delimiter+prefix;
00486 std::stringstream ss;
00487 ss << prefix;
00488 std::copy(val.begin(), val.end(), std::ostream_iterator<typename T::value_type>(ss, sdp.c_str()));
00489 ret = ss.str();
00490 if (!ret.empty()) {ret.erase(ret.size() - delimiter.size() - prefix.size());}
00491 return ret;
00492 }
00493
00494 }
00495
00496 }
00497
00498 #endif