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
00029
00030 #include <gtest/gtest.h>
00031
00032 #include <map>
00033 #include <set>
00034 #include <string>
00035 #include <algorithm>
00036 #include <iterator>
00037
00038 #include <controller_manager/controller_manager.h>
00039 #include <hardware_interface/robot_hw.h>
00040 #include <hardware_interface/joint_command_interface.h>
00041
00042 namespace hardware_interface {
00043 bool operator<(hardware_interface::ControllerInfo const& i1, hardware_interface::ControllerInfo const& i2)
00044 {
00045 return i1.name < i2.name;
00046 }
00047 }
00048 template<typename T> T intersect(const T& v1, const T &v2)
00049 {
00050
00051 std::vector<typename T::value_type> sorted1(v1.begin(), v1.end()), sorted2(v2.begin(), v2.end());
00052 T res;
00053
00054 std::sort(sorted1.begin(), sorted1.end());
00055 std::sort(sorted2.begin(), sorted2.end());
00056
00057 std::set_intersection(sorted1.begin(), sorted1.end(), sorted2.begin(), sorted2.end(), std::back_inserter(res));
00058 return res;
00059 }
00060
00061
00062
00063
00064
00065 class SwitchBot : public hardware_interface::RobotHW
00066 {
00067 hardware_interface::JointStateInterface jsi_;
00068 hardware_interface::PositionJointInterface pji_;
00069 hardware_interface::VelocityJointInterface vji_;
00070 hardware_interface::EffortJointInterface eji_;
00071
00072 class Joint
00073 {
00074 double dummy_;
00075 std::set<std::string> interfaces_;
00076 std::string current_;
00077 hardware_interface::JointStateHandle jsh_;
00078 public:
00079 Joint(const std::string &n, hardware_interface::JointStateInterface &iface): jsh_(n, &dummy_, &dummy_, &dummy_)
00080 {
00081 iface.registerHandle(jsh_);
00082 }
00083
00084 template<typename Interface> void registerHandle(Interface &iface, bool can_switch)
00085 {
00086 if(can_switch) interfaces_.insert(hardware_interface::internal::demangledTypeName<Interface>() );
00087 iface.registerHandle(typename Interface::ResourceHandleType(jsh_, &dummy_));
00088 }
00089 bool prepareSwitch(const std::string &n)
00090 {
00091 if(interfaces_.find(n) == interfaces_.end()) return false;
00092 return n >= current_;
00093 }
00094 void doSwitch(const std::string &n)
00095 {
00096 current_ = n;
00097 }
00098 };
00099
00100 std::map<std::string, boost::shared_ptr<Joint> > joints_;
00101
00102 boost::shared_ptr<Joint> makeJoint(const std::string & name)
00103 {
00104 boost::shared_ptr<Joint> j(new Joint(name, jsi_));
00105 joints_.insert(std::make_pair(name, j));
00106 return j;
00107 }
00108
00109 std::vector<std::string> started_;
00110 std::vector<std::string> stopped_;
00111 public:
00112 SwitchBot()
00113 {
00114 boost::shared_ptr<Joint> j;
00115
00116 j = makeJoint("j_pv");
00117
00118 j->registerHandle(pji_, true);
00119 j->registerHandle(vji_, true);
00120 j->registerHandle(eji_, false);
00121
00122 j = makeJoint("j_pe");
00123 j->registerHandle(pji_, true);
00124 j->registerHandle(vji_, false);
00125 j->registerHandle(eji_, true);
00126
00127 j = makeJoint("j_ve");
00128 j->registerHandle(pji_, false);
00129 j->registerHandle(vji_, true);
00130 j->registerHandle(eji_, true);
00131
00132 registerInterface(&pji_);
00133 registerInterface(&vji_);
00134 registerInterface(&eji_);
00135
00136 }
00137
00138 virtual bool prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
00139 const std::list<hardware_interface::ControllerInfo>& stop_list)
00140 {
00141
00142 if(!RobotHW::prepareSwitch(start_list, stop_list))
00143 {
00144 ROS_ERROR("Something is wrong with RobotHW");
00145 return false;
00146 }
00147
00148 if(!intersect(start_list, stop_list).empty())
00149 {
00150 ROS_ERROR_STREAM("start_list and stop_list intersect");
00151 return false;
00152 }
00153
00154 bool j_pe_e = false;
00155 bool j_ve_v = false;
00156
00157 for(std::list<hardware_interface::ControllerInfo>::const_iterator it = start_list.begin(); it != start_list.end(); ++it)
00158 {
00159 if (it->claimed_resources.size() != 1)
00160 {
00161 ROS_FATAL("We expect controllers to claim resoures from only one interface. This should never happen!");
00162 return false;
00163 }
00164 const hardware_interface::InterfaceResources& iface_res = it->claimed_resources.front();
00165 for (std::set<std::string>::const_iterator res_it = iface_res.resources.begin(); res_it != iface_res.resources.end(); ++res_it)
00166 {
00167
00168 if(iface_res.hardware_interface == "hardware_interface::EffortJointInterface" && *res_it == "j_pe") j_pe_e = true;
00169 else if(iface_res.hardware_interface == "hardware_interface::VelocityJointInterface" && *res_it == "j_ve") j_ve_v = true;
00170
00171
00172 try
00173 {
00174 if(!joints_.at(*res_it)->prepareSwitch(iface_res.hardware_interface))
00175 {
00176 ROS_ERROR_STREAM("Cannot switch " << *res_it << " to " << iface_res.hardware_interface);
00177 return false;
00178 }
00179 }
00180 catch(...)
00181 {
00182 ROS_FATAL("This should never happen!");
00183 return false;
00184 }
00185 }
00186 }
00187 return !(j_pe_e && j_ve_v);
00188 }
00189 virtual void doSwitch(const std::list<hardware_interface::ControllerInfo> &start_list, const std::list<hardware_interface::ControllerInfo> &stop_list)
00190 {
00191 RobotHW::doSwitch(start_list, stop_list);
00192
00193 std::map<std::string, std::string> switches;
00194 for(std::list<hardware_interface::ControllerInfo>::const_iterator it = stop_list.begin(); it != stop_list.end(); ++it)
00195 {
00196 started_.erase(std::remove(started_.begin(), started_.end(), it->name), started_.end());
00197 stopped_.push_back(it->name);
00198 const hardware_interface::InterfaceResources& iface_res = it->claimed_resources.front();
00199 for (std::set<std::string>::const_iterator res_it = iface_res.resources.begin(); res_it != iface_res.resources.end(); ++res_it)
00200 {
00201 switches[*res_it] = "";
00202 }
00203 }
00204 for(std::list<hardware_interface::ControllerInfo>::const_iterator it = start_list.begin(); it != start_list.end(); ++it)
00205 {
00206 stopped_.erase(std::remove(stopped_.begin(), stopped_.end(), it->name), stopped_.end());
00207 started_.push_back(it->name);
00208 const hardware_interface::InterfaceResources& iface_res = it->claimed_resources.front();
00209 for (std::set<std::string>::const_iterator res_it = iface_res.resources.begin(); res_it != iface_res.resources.end(); ++res_it)
00210 {
00211 switches[*res_it] = iface_res.hardware_interface;
00212 }
00213 }
00214 for(std::map<std::string, std::string>::iterator it = switches.begin(); it != switches.end(); ++it)
00215 {
00216 joints_[it->first]->doSwitch(it->second);
00217 }
00218 }
00219 bool checkUnqiue() const
00220 {
00221 return intersect(started_, stopped_).empty();
00222 }
00223 bool checkNotRunning() const
00224 {
00225 return started_.empty();
00226 }
00227 };
00228
00229
00230 class DummyControllerLoader: public controller_manager::ControllerLoaderInterface
00231 {
00232 class DummyController : public controller_interface::ControllerBase
00233 {
00234 const std::string type_name;
00235 public:
00236 DummyController(const std::string &name) : type_name(name) {}
00237 virtual void update(const ros::Time& , const ros::Duration& ) {}
00238 virtual bool initRequest(hardware_interface::RobotHW* ,
00239 ros::NodeHandle& ,
00240 ros::NodeHandle& controller_nh,
00241 ClaimedResources& claimed_resources)
00242 {
00243 std::vector<std::string> joints;
00244 if(!controller_nh.getParam("joints", joints))
00245 {
00246 ROS_ERROR("Could not parse joint names");
00247 return false;
00248 }
00249 std::set<std::string> resources(joints.begin(), joints.end());
00250 hardware_interface::InterfaceResources iface_res(getHardwareInterfaceType(), resources);
00251 claimed_resources.assign(1, iface_res);
00252 state_ = INITIALIZED;
00253 return true;
00254 }
00255 virtual std::string getHardwareInterfaceType() const
00256 {
00257 return type_name;
00258 }
00259 };
00260
00261 std::map<std::string, std::string> classes;
00262 void add(const std::string type)
00263 {
00264 classes.insert(std::make_pair("Dummy" + type + "Controller", "hardware_interface::" + type));
00265 }
00266 public:
00267 DummyControllerLoader() : ControllerLoaderInterface("controller_interface::ControllerBase")
00268 {
00269 add("EffortJointInterface");
00270 add("PositionJointInterface");
00271 add("VelocityJointInterface");
00272 }
00273 virtual boost::shared_ptr<controller_interface::ControllerBase> createInstance(const std::string& lookup_name)
00274 {
00275 return boost::shared_ptr<controller_interface::ControllerBase>(new DummyController(classes.at(lookup_name)));
00276 }
00277 virtual std::vector<std::string> getDeclaredClasses()
00278 {
00279 std::vector<std::string> v;
00280 for(std::map<std::string, std::string>::iterator it = classes.begin(); it != classes.end(); ++it)
00281 {
00282 v.push_back(it->first);
00283 }
00284 return v;
00285 }
00286 virtual void reload() {}
00287 };
00288
00289 void update(controller_manager::ControllerManager &cm, const ros::TimerEvent& e)
00290 {
00291 cm.update(e.current_real, e.current_real - e.last_real);
00292 }
00293
00294 class GuardROS
00295 {
00296 public:
00297 ~GuardROS()
00298 {
00299 ros::shutdown();
00300 ros::waitForShutdown();
00301 }
00302 };
00303
00304 TEST(SwitchInterfacesTest, SwitchInterfaces)
00305 {
00306 GuardROS guard;
00307
00308 SwitchBot bot;
00309 ros::NodeHandle nh;
00310
00311 controller_manager::ControllerManager cm(&bot);
00312
00313 cm.registerControllerLoader(boost::make_shared<DummyControllerLoader>());
00314
00315 ros::Timer timer = nh.createTimer(ros::Duration(0.01), boost::bind(update, boost::ref(cm), _1));
00316
00317 ASSERT_TRUE(cm.loadController("group_pos"));
00318 ASSERT_TRUE(cm.loadController("another_group_pos"));
00319 ASSERT_TRUE(cm.loadController("group_vel"));
00320 ASSERT_TRUE(cm.loadController("group_eff"));
00321 ASSERT_TRUE(cm.loadController("single_pos"));
00322 ASSERT_TRUE(cm.loadController("single_eff"));
00323 ASSERT_TRUE(cm.loadController("invalid_group_pos"));
00324 ASSERT_FALSE(cm.loadController("totally_random_name"));
00325
00326 {
00327 std::vector<std::string> start, stop;
00328 start.push_back("invalid_group_pos");
00329 ASSERT_FALSE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00330 }
00331 {
00332 std::vector<std::string> start, stop;
00333 start.push_back("group_pos");
00334 start.push_back("group_vel");
00335 ASSERT_FALSE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00336 }
00337 {
00338 std::vector<std::string> start, stop;
00339 start.push_back("group_pos");
00340 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00341 ASSERT_TRUE(cm.switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00342 }
00343 {
00344 std::vector<std::string> start, stop, next_start;
00345 start.push_back("group_pos");
00346 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00347
00348 next_start.push_back("group_pos");
00349 ASSERT_TRUE(cm.switchController(next_start, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00350
00351 ASSERT_TRUE(cm.switchController(stop, next_start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00352 }
00353 {
00354 std::vector<std::string> start, stop, next_start;
00355 start.push_back("group_pos");
00356 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00357
00358 next_start.push_back("another_group_pos");
00359 ASSERT_TRUE(cm.switchController(next_start, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00360
00361 ASSERT_TRUE(cm.switchController(stop, next_start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00362 }
00363 {
00364 std::vector<std::string> start, stop;
00365 start.push_back("group_vel");
00366 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00367 ASSERT_TRUE(cm.switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00368 }
00369 {
00370 std::vector<std::string> start, stop;
00371 start.push_back("group_eff");
00372 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00373 ASSERT_TRUE(cm.switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00374 }
00375
00376 {
00377 std::vector<std::string> start, stop, next_start;
00378 start.push_back("group_eff");
00379 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00380
00381 next_start.push_back("group_vel");
00382 ASSERT_TRUE(cm.switchController(next_start, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00383
00384 ASSERT_FALSE(cm.switchController(start, next_start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00385
00386 ASSERT_TRUE(cm.switchController(stop, next_start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00387 }
00388
00389 {
00390 std::vector<std::string> start, stop;
00391 start.push_back("single_pos");
00392 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00393 ASSERT_TRUE(cm.switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00394 }
00395 {
00396 std::vector<std::string> start, stop;
00397 start.push_back("single_pos");
00398 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00399 ASSERT_TRUE(cm.switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00400 }
00401 {
00402 std::vector<std::string> start, stop;
00403 start.push_back("single_pos");
00404 start.push_back("group_eff");
00405 ASSERT_FALSE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00406 }
00407 {
00408 std::vector<std::string> start, stop;
00409 start.push_back("single_eff");
00410 start.push_back("group_vel");
00411 ASSERT_FALSE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00412 }
00413 {
00414 std::vector<std::string> start, stop;
00415 start.push_back("single_pos");
00416 start.push_back("group_vel");
00417 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00418 ASSERT_TRUE(cm.switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00419 }
00420 {
00421 std::vector<std::string> start, stop;
00422 start.push_back("single_pos");
00423 start.push_back("group_vel");
00424 start.push_back("totally_random_name");
00425 ASSERT_FALSE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00426 ASSERT_FALSE(cm.switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00427
00428 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::BEST_EFFORT));
00429 ASSERT_TRUE(cm.switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::BEST_EFFORT));
00430 }
00431 {
00432 std::vector<std::string> start, stop;
00433 start.push_back("single_pos");
00434 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00435
00436 ASSERT_TRUE(cm.switchController(start, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00437 ASSERT_TRUE(bot.checkUnqiue());
00438
00439 ASSERT_TRUE(cm.switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00440 }
00441 {
00442 std::vector<std::string> start, stop;
00443 stop.push_back("single_pos");
00444 ASSERT_FALSE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00445 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::BEST_EFFORT));
00446 }
00447 {
00448 std::vector<std::string> start, stop;
00449 start.push_back("single_pos");
00450 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00451 ASSERT_FALSE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
00452 ASSERT_TRUE(cm.switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::BEST_EFFORT));
00453 ASSERT_TRUE(cm.switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
00454 }
00455 ASSERT_TRUE(bot.checkNotRunning());
00456 }
00457
00458 int main(int argc, char **argv)
00459 {
00460 testing::InitGoogleTest(&argc, argv);
00461 ros::init(argc, argv, "controller_manager_switch_test");
00462
00463 ros::AsyncSpinner spinner(1);
00464 spinner.start();
00465 int ret = RUN_ALL_TESTS();
00466 return ret;
00467 }