30 #include <gtest/gtest.h> 48 template<
typename T> T
intersect(
const T& v1,
const T &v2)
51 std::vector<typename T::value_type> sorted1(v1.begin(), v1.end()), sorted2(v2.begin(), v2.end());
54 std::sort(sorted1.begin(), sorted1.end());
55 std::sort(sorted2.begin(), sorted2.end());
57 std::set_intersection(sorted1.begin(), sorted1.end(), sorted2.begin(), sorted2.end(), std::back_inserter(res));
84 template<
typename Interface>
void registerHandle(Interface &iface,
bool can_switch)
86 if(can_switch) interfaces_.insert(hardware_interface::internal::demangledTypeName<Interface>() );
87 iface.registerHandle(
typename Interface::ResourceHandleType(jsh_, &dummy_));
91 if(interfaces_.find(n) == interfaces_.end())
return false;
102 std::map<std::string, JointSharedPtr>
joints_;
106 JointSharedPtr j(
new Joint(name, jsi_));
107 joints_.insert(std::make_pair(name, j));
118 j = makeJoint(
"j_pv");
120 j->registerHandle(pji_,
true);
121 j->registerHandle(vji_,
true);
122 j->registerHandle(eji_,
false);
124 j = makeJoint(
"j_pe");
125 j->registerHandle(pji_,
true);
126 j->registerHandle(vji_,
false);
127 j->registerHandle(eji_,
true);
129 j = makeJoint(
"j_ve");
130 j->registerHandle(pji_,
false);
131 j->registerHandle(vji_,
true);
132 j->registerHandle(eji_,
true);
134 registerInterface(&pji_);
135 registerInterface(&vji_);
136 registerInterface(&eji_);
140 virtual bool prepareSwitch(
const std::list<hardware_interface::ControllerInfo>& start_list,
141 const std::list<hardware_interface::ControllerInfo>& stop_list)
146 ROS_ERROR(
"Something is wrong with RobotHW");
150 if(!
intersect(start_list, stop_list).empty())
159 for(std::list<hardware_interface::ControllerInfo>::const_iterator it = start_list.begin(); it != start_list.end(); ++it)
161 if (it->claimed_resources.size() != 1)
163 ROS_FATAL(
"We expect controllers to claim resoures from only one interface. This should never happen!");
167 for (std::set<std::string>::const_iterator res_it = iface_res.
resources.begin(); res_it != iface_res.
resources.end(); ++res_it)
170 if(iface_res.
hardware_interface ==
"hardware_interface::EffortJointInterface" && *res_it ==
"j_pe") j_pe_e =
true;
171 else if(iface_res.
hardware_interface ==
"hardware_interface::VelocityJointInterface" && *res_it ==
"j_ve") j_ve_v =
true;
189 return !(j_pe_e && j_ve_v);
191 virtual void doSwitch(
const std::list<hardware_interface::ControllerInfo> &start_list,
const std::list<hardware_interface::ControllerInfo> &stop_list)
195 std::map<std::string, std::string> switches;
196 for(std::list<hardware_interface::ControllerInfo>::const_iterator it = stop_list.begin(); it != stop_list.end(); ++it)
198 started_.erase(std::remove(started_.begin(), started_.end(), it->name), started_.end());
199 stopped_.push_back(it->name);
201 for (std::set<std::string>::const_iterator res_it = iface_res.
resources.begin(); res_it != iface_res.
resources.end(); ++res_it)
203 switches[*res_it] =
"";
206 for(std::list<hardware_interface::ControllerInfo>::const_iterator it = start_list.begin(); it != start_list.end(); ++it)
208 stopped_.erase(std::remove(stopped_.begin(), stopped_.end(), it->name), stopped_.end());
209 started_.push_back(it->name);
211 for (std::set<std::string>::const_iterator res_it = iface_res.
resources.begin(); res_it != iface_res.
resources.end(); ++res_it)
216 for(std::map<std::string, std::string>::iterator it = switches.begin(); it != switches.end(); ++it)
218 joints_[it->first]->doSwitch(it->second);
223 return intersect(started_, stopped_).empty();
227 return started_.empty();
245 std::vector<std::string> joints;
246 if(!controller_nh.
getParam(
"joints", joints))
248 ROS_ERROR(
"Could not parse joint names");
251 std::set<std::string> resources(joints.begin(), joints.end());
253 claimed_resources.assign(1, iface_res);
254 state_ = INITIALIZED;
264 void add(
const std::string type)
266 classes.insert(std::make_pair(
"Dummy" + type +
"Controller",
"hardware_interface::" + type));
271 add(
"EffortJointInterface");
272 add(
"PositionJointInterface");
273 add(
"VelocityJointInterface");
281 std::vector<std::string> v;
282 for(std::map<std::string, std::string>::iterator it = classes.begin(); it != classes.end(); ++it)
284 v.push_back(it->first);
306 TEST(SwitchInterfacesTest, SwitchInterfaces)
329 std::vector<std::string>
start, stop;
330 start.push_back(
"invalid_group_pos");
331 ASSERT_FALSE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
334 std::vector<std::string>
start, stop;
335 start.push_back(
"group_pos");
336 start.push_back(
"group_vel");
337 ASSERT_FALSE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
340 std::vector<std::string>
start, stop;
341 start.push_back(
"group_pos");
342 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
343 ASSERT_TRUE(cm.
switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
346 std::vector<std::string>
start, stop, next_start;
347 start.push_back(
"group_pos");
348 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
350 next_start.push_back(
"group_pos");
351 ASSERT_TRUE(cm.
switchController(next_start, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
353 ASSERT_TRUE(cm.
switchController(stop, next_start, controller_manager_msgs::SwitchControllerRequest::STRICT));
356 std::vector<std::string>
start, stop, next_start;
357 start.push_back(
"group_pos");
358 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
360 next_start.push_back(
"another_group_pos");
361 ASSERT_TRUE(cm.
switchController(next_start, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
363 ASSERT_TRUE(cm.
switchController(stop, next_start, controller_manager_msgs::SwitchControllerRequest::STRICT));
366 std::vector<std::string>
start, stop;
367 start.push_back(
"group_vel");
368 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
369 ASSERT_TRUE(cm.
switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
372 std::vector<std::string>
start, stop;
373 start.push_back(
"group_eff");
374 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
375 ASSERT_TRUE(cm.
switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
379 std::vector<std::string>
start, stop, next_start;
380 start.push_back(
"group_eff");
381 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
383 next_start.push_back(
"group_vel");
384 ASSERT_TRUE(cm.
switchController(next_start, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
386 ASSERT_FALSE(cm.
switchController(start, next_start, controller_manager_msgs::SwitchControllerRequest::STRICT));
388 ASSERT_TRUE(cm.
switchController(stop, next_start, controller_manager_msgs::SwitchControllerRequest::STRICT));
392 std::vector<std::string>
start, stop;
393 start.push_back(
"single_pos");
394 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
395 ASSERT_TRUE(cm.
switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
398 std::vector<std::string>
start, stop;
399 start.push_back(
"single_pos");
400 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
401 ASSERT_TRUE(cm.
switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
404 std::vector<std::string>
start, stop;
405 start.push_back(
"single_pos");
406 start.push_back(
"group_eff");
407 ASSERT_FALSE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
410 std::vector<std::string>
start, stop;
411 start.push_back(
"single_eff");
412 start.push_back(
"group_vel");
413 ASSERT_FALSE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
416 std::vector<std::string>
start, stop;
417 start.push_back(
"single_pos");
418 start.push_back(
"group_vel");
419 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
420 ASSERT_TRUE(cm.
switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
423 std::vector<std::string>
start, stop;
424 start.push_back(
"single_pos");
425 start.push_back(
"group_vel");
426 start.push_back(
"totally_random_name");
427 ASSERT_FALSE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
428 ASSERT_FALSE(cm.
switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
430 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::BEST_EFFORT));
431 ASSERT_TRUE(cm.
switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::BEST_EFFORT));
434 std::vector<std::string>
start, stop;
435 start.push_back(
"single_pos");
436 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
438 ASSERT_TRUE(cm.
switchController(start, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
441 ASSERT_TRUE(cm.
switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
444 std::vector<std::string>
start, stop;
445 stop.push_back(
"single_pos");
446 ASSERT_FALSE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
447 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::BEST_EFFORT));
450 std::vector<std::string>
start, stop;
451 start.push_back(
"single_pos");
452 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
453 ASSERT_FALSE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::STRICT));
454 ASSERT_TRUE(cm.
switchController(start, stop, controller_manager_msgs::SwitchControllerRequest::BEST_EFFORT));
455 ASSERT_TRUE(cm.
switchController(stop, start, controller_manager_msgs::SwitchControllerRequest::STRICT));
460 int main(
int argc,
char **argv)
462 testing::InitGoogleTest(&argc, argv);
463 ros::init(argc, argv,
"controller_manager_switch_test");
467 int ret = RUN_ALL_TESTS();
int main(int argc, char **argv)
TEST(SwitchInterfacesTest, SwitchInterfaces)
virtual bool initRequest(hardware_interface::RobotHW *, ros::NodeHandle &, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources)
ROS Controller Manager and Runner.
virtual void doSwitch(const std::list< ControllerInfo > &, const std::list< ControllerInfo > &)
bool loadController(const std::string &name)
Load a new controller by name.
bool switchController(const std::vector< std::string > &start_controllers, const std::vector< std::string > &stop_controllers, const int strictness)
Switch multiple controllers simultaneously.
hardware_interface::JointStateHandle jsh_
std::set< std::string > resources
std::set< std::string > interfaces_
virtual controller_interface::ControllerBaseSharedPtr createInstance(const std::string &lookup_name)
std::vector< std::string > stopped_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::vector< hardware_interface::InterfaceResources > ClaimedResources
hardware_interface::PositionJointInterface pji_
T intersect(const T &v1, const T &v2)
virtual std::vector< std::string > getDeclaredClasses()
virtual bool prepareSwitch(const std::list< ControllerInfo > &start_list, const std::list< ControllerInfo > &stop_list)
std::vector< std::string > started_
std::map< std::string, JointSharedPtr > joints_
void add(const std::string type)
virtual void doSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
boost::shared_ptr< Joint > JointSharedPtr
void doSwitch(const std::string &n)
bool checkNotRunning() const
const std::string type_name
hardware_interface::EffortJointInterface eji_
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
boost::shared_ptr< ControllerBase > ControllerBaseSharedPtr
DummyController(const std::string &name)
JointSharedPtr makeJoint(const std::string &name)
virtual bool prepareSwitch(const std::list< hardware_interface::ControllerInfo > &start_list, const std::list< hardware_interface::ControllerInfo > &stop_list)
void registerHandle(const JointStateHandle &handle)
void update(controller_manager::ControllerManager &cm, const ros::TimerEvent &e)
Joint(const std::string &n, hardware_interface::JointStateInterface &iface)
std::map< std::string, std::string > classes
void registerHandle(Interface &iface, bool can_switch)
bool getParam(const std::string &key, std::string &s) const
virtual void update(const ros::Time &, const ros::Duration &)
bool prepareSwitch(const std::string &n)
ROSCPP_DECL void shutdown()
void registerControllerLoader(ControllerLoaderInterfaceSharedPtr controller_loader)
Register a controller loader.
Abstract Controller Loader Interface.
#define ROS_ERROR_STREAM(args)
void update(const ros::Time &time, const ros::Duration &period, bool reset_controllers=false)
Update all active controllers.
virtual std::string getHardwareInterfaceType() const
std::string hardware_interface
hardware_interface::VelocityJointInterface vji_
ROSCPP_DECL void waitForShutdown()
bool operator<(hardware_interface::ControllerInfo const &i1, hardware_interface::ControllerInfo const &i2)
hardware_interface::JointStateInterface jsi_