45 #include <controller_manager_msgs/ListControllers.h> 46 #include <controller_manager_msgs/SwitchController.h> 51 #include <boost/bimap.hpp> 86 const std::string
ns_;
88 typedef std::map<std::string, controller_manager_msgs::ControllerState>
ControllersMap;
91 typedef std::map<std::string, ControllerHandleAllocatorPtr>
AllocatorsMap;
94 typedef std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr>
HandleMap;
105 static bool isActive(
const controller_manager_msgs::ControllerState& s)
107 return s.state == std::string(
"running");
121 controller_manager_msgs::ListControllers srv;
124 ROS_WARN_STREAM(
"Failed to read controllers from " << ns_ <<
"controller_manager/list_controllers");
126 managed_controllers_.clear();
127 active_controllers_.clear();
128 for (
size_t i = 0; i < srv.response.controller.size(); ++i)
130 const controller_manager_msgs::ControllerState& c = srv.response.controller[i];
133 active_controllers_.insert(std::make_pair(c.name, c));
138 managed_controllers_.insert(std::make_pair(absname, c));
150 void allocate(
const std::string& name,
const controller_manager_msgs::ControllerState& controller)
152 if (handles_.find(name) == handles_.end())
154 const std::string& type = controller.type;
155 AllocatorsMap::iterator alloc_it = allocators_.find(type);
156 if (alloc_it == allocators_.end())
158 alloc_it = allocators_.insert(std::make_pair(type, loader_.createUniqueInstance(type))).first;
161 std::vector<std::string> resources;
162 #if defined(MOVEIT_ROS_CONTROL_INTERFACE_OLD_ROS_CONTROL) 163 resources = controller.resources;
166 for (std::vector<controller_manager_msgs::HardwareInterfaceResources>::const_iterator hir =
167 controller.claimed_resources.begin();
168 hir != controller.claimed_resources.end(); ++hir)
170 for (std::vector<std::string>::const_iterator
r = hir->resources.begin();
r != hir->resources.end(); ++
r)
172 resources.push_back(*
r);
177 moveit_controller_manager::MoveItControllerHandlePtr handle =
178 alloc_it->second->alloc(name, resources);
180 handles_.insert(std::make_pair(name, handle));
199 : ns_(
ros::NodeHandle(
"~").
param(
"ros_control_namespace",
std::string(
"/")))
200 , loader_(
"moveit_ros_control_interface",
"moveit_ros_control_interface::ControllerHandleAllocator")
202 ROS_INFO_STREAM(
"Started moveit_ros_control_interface::MoveItControllerManager for namespace " << ns_);
210 : ns_(ns), loader_(
"moveit_ros_control_interface",
"moveit_ros_control_interface::ControllerHandleAllocator")
221 boost::mutex::scoped_lock lock(controllers_mutex_);
222 HandleMap::iterator it = handles_.find(name);
223 if (it != handles_.end())
227 return moveit_controller_manager::MoveItControllerHandlePtr();
236 boost::mutex::scoped_lock lock(controllers_mutex_);
239 for (ControllersMap::iterator it = managed_controllers_.begin(); it != managed_controllers_.end(); ++it)
241 names.push_back(it->first);
251 boost::mutex::scoped_lock lock(controllers_mutex_);
254 for (ControllersMap::iterator it = managed_controllers_.begin(); it != managed_controllers_.end(); ++it)
257 names.push_back(it->first);
268 boost::mutex::scoped_lock lock(controllers_mutex_);
269 ControllersMap::iterator it = managed_controllers_.find(name);
270 if (it != managed_controllers_.end())
272 #if defined(MOVEIT_ROS_CONTROL_INTERFACE_OLD_ROS_CONTROL) 273 joints = it->second.resources;
275 for (std::size_t i = 0; i < it->second.claimed_resources.size(); ++i)
277 std::vector<std::string>& resources = it->second.claimed_resources[i].resources;
278 joints.insert(joints.end(), resources.begin(), resources.end());
291 boost::mutex::scoped_lock lock(controllers_mutex_);
295 ControllersMap::iterator it = managed_controllers_.find(name);
296 if (it != managed_controllers_.end())
310 virtual bool switchControllers(
const std::vector<std::string>& activate,
const std::vector<std::string>& deactivate)
312 boost::mutex::scoped_lock lock(controllers_mutex_);
315 typedef boost::bimap<std::string, std::string> resources_bimap;
317 resources_bimap claimed_resources;
320 for (ControllersMap::iterator c = active_controllers_.begin(); c != active_controllers_.end(); ++c)
322 #if defined(MOVEIT_ROS_CONTROL_INTERFACE_OLD_ROS_CONTROL) 323 for (std::vector<std::string>::iterator
r = c->second.resources.begin();
r != c->second.resources.end(); ++
r)
325 claimed_resources.insert(resources_bimap::value_type(c->second.name, *
r));
328 for (std::vector<controller_manager_msgs::HardwareInterfaceResources>::iterator hir =
329 c->second.claimed_resources.begin();
330 hir != c->second.claimed_resources.end(); ++hir)
332 for (std::vector<std::string>::iterator
r = hir->resources.begin();
r != hir->resources.end(); ++
r)
334 claimed_resources.insert(resources_bimap::value_type(c->second.name, *
r));
340 controller_manager_msgs::SwitchController srv;
342 for (std::vector<std::string>::const_iterator it = deactivate.begin(); it != deactivate.end(); ++it)
344 ControllersMap::iterator c = managed_controllers_.find(*it);
345 if (c != managed_controllers_.end())
347 srv.request.stop_controllers.push_back(c->second.name);
348 claimed_resources.right.erase(c->second.name);
352 for (std::vector<std::string>::const_iterator it = activate.begin(); it != activate.end(); ++it)
354 ControllersMap::iterator c = managed_controllers_.find(*it);
355 if (c != managed_controllers_.end())
357 srv.request.start_controllers.push_back(c->second.name);
358 #if defined(MOVEIT_ROS_CONTROL_INTERFACE_OLD_ROS_CONTROL) 359 for (std::vector<std::string>::iterator
r = c->second.resources.begin();
r != c->second.resources.end(); ++
r)
361 resources_bimap::right_const_iterator res = claimed_resources.right.find(*
r);
362 if (res != claimed_resources.right.end())
364 srv.request.stop_controllers.push_back(res->second);
365 claimed_resources.left.erase(res->second);
369 for (std::vector<controller_manager_msgs::HardwareInterfaceResources>::iterator hir =
370 c->second.claimed_resources.begin();
371 hir != c->second.claimed_resources.end(); ++hir)
373 for (std::vector<std::string>::iterator
r = hir->resources.begin();
r != hir->resources.end(); ++
r)
375 resources_bimap::right_const_iterator res = claimed_resources.right.find(*
r);
376 if (res != claimed_resources.right.end())
378 srv.request.stop_controllers.push_back(res->second);
379 claimed_resources.left.erase(res->second);
386 srv.request.strictness = srv.request.STRICT;
388 if (!srv.request.start_controllers.empty() || srv.request.stop_controllers.empty())
395 return srv.response.ok;
431 for (
int i = 0; i < services.
size(); ++i)
433 std::string service = services[i][0];
434 std::size_t found = service.find(
"controller_manager/list_controllers");
435 if (found != std::string::npos)
437 std::string ns = service.substr(0, found);
438 if (controller_managers_.find(ns) == controller_managers_.end())
440 ROS_INFO_STREAM(
"Adding controller_manager interface for node at namespace " << ns);
441 controller_managers_.insert(
442 std::make_pair(ns, std::make_shared<moveit_ros_control_interface::MoveItControllerManager>(ns)));
455 size_t pos = name.find(
'/', 1);
456 if (pos == std::string::npos)
458 return name.substr(0, pos + 1);
469 boost::mutex::scoped_lock lock(controller_managers_mutex_);
472 ControllerManagersMap::iterator it = controller_managers_.find(ns);
473 if (it != controller_managers_.end())
475 return it->second->getControllerHandle(name);
477 return moveit_controller_manager::MoveItControllerHandlePtr();
486 boost::mutex::scoped_lock lock(controller_managers_mutex_);
489 for (ControllerManagersMap::iterator it = controller_managers_.begin(); it != controller_managers_.end(); ++it)
491 it->second->getControllersList(names);
501 boost::mutex::scoped_lock lock(controller_managers_mutex_);
504 for (ControllerManagersMap::iterator it = controller_managers_.begin(); it != controller_managers_.end(); ++it)
506 it->second->getActiveControllers(names);
517 boost::mutex::scoped_lock lock(controller_managers_mutex_);
520 ControllerManagersMap::iterator it = controller_managers_.find(ns);
521 if (it != controller_managers_.end())
523 it->second->getControllerJoints(name, joints);
534 boost::mutex::scoped_lock lock(controller_managers_mutex_);
537 ControllerManagersMap::iterator it = controller_managers_.find(ns);
538 if (it != controller_managers_.end())
540 return it->second->getControllerState(name);
542 return ControllerState();
551 virtual bool switchControllers(
const std::vector<std::string>& activate,
const std::vector<std::string>& deactivate)
553 boost::mutex::scoped_lock lock(controller_managers_mutex_);
555 for (ControllerManagersMap::iterator it = controller_managers_.begin(); it != controller_managers_.end(); ++it)
557 if (!it->second->switchControllers(activate, deactivate))
std::string getAbsName(const std::string &name)
get fully qualified name
MOVEIT_CLASS_FORWARD(ControllerHandleAllocator)
boost::mutex controller_managers_mutex_
std::map< std::string, ControllerHandleAllocatorPtr > AllocatorsMap
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
std::map< std::string, moveit_ros_control_interface::MoveItControllerManagerPtr > ControllerManagersMap
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)
delegates switch to all known interfaces. Stops of first failing switch.
virtual void getActiveControllers(std::vector< std::string > &names)
Read all active, managed controllers from discovered interfaces.
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)
Read resources from cached controller states.
void discover()
Poll ROS master for services and filters all controller_manager/list_controllers instances Throttled ...
virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
Find and return the pre-allocated handle for the given controller.
ControllersMap managed_controllers_
bool call(const std::string &service_name, MReq &req, MRes &res)
ROSCPP_DECL const std::string & getName()
virtual void getControllerJoints(const std::string &name, std::vector< std::string > &joints)
Find appropriate interface and delegate joints query.
virtual void getActiveControllers(std::vector< std::string > &names)
Refresh controller list and output all active, managed controllers.
void discover(bool force=false)
Call list_controllers and populate managed_controllers_ and active_controllers_. Allocates handles if...
MoveItMultiControllerManager discovers all running ros_control node and delegates member function to ...
ROSCPP_DECL const std::string & getNamespace()
virtual void getControllersList(std::vector< std::string > &names)
Read all managed controllers from discovered interfaces.
std::map< std::string, moveit_controller_manager::MoveItControllerHandlePtr > HandleMap
ControllersMap active_controllers_
ROSCPP_DECL bool execute(const std::string &method, const XmlRpc::XmlRpcValue &request, XmlRpc::XmlRpcValue &response, XmlRpc::XmlRpcValue &payload, bool wait_for_master)
static bool isActive(const controller_manager_msgs::ControllerState &s)
Check if given controller is active.
#define ROS_WARN_STREAM(args)
ros::Time controller_managers_stamp_
#define ROS_INFO_STREAM(args)
ros::Time controllers_stamp_
ControllerManagersMap controller_managers_
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
static std::string getNamespace(const std::string &name)
Get namespace (including leading and trailing slashes) from controller name.
void allocate(const std::string &name, const controller_manager_msgs::ControllerState &controller)
Allocates a MoveItControllerHandle instance for the given controller Might create allocator object fi...
virtual bool switchControllers(const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)
Filter lists for managed controller and computes switching set. Stopped list might be extended by uns...
#define ROS_ERROR_STREAM(args)
virtual ControllerState getControllerState(const std::string &name)
Find appropriate interface and delegate state query.
virtual ControllerState getControllerState(const std::string &name)
Refresh controller state and output the state of the given one, only active_ will be set...
std::map< std::string, controller_manager_msgs::ControllerState > ControllersMap
boost::mutex controllers_mutex_
virtual bool isClassAvailable(const std::string &lookup_name)
virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle(const std::string &name)
Find appropriate interface and delegate handle creation.
MoveItControllerManager(const std::string &ns)
Configure interface with namespace.
bool checkTimeout(ros::Time &t, double timeout, bool force=false)
check for timeout
PLUGINLIB_EXPORT_CLASS(moveit_ros_control_interface::MoveItControllerManager, moveit_controller_manager::MoveItControllerManager)
moveit_controller_manager::MoveItControllerManager sub class that interfaces one ros_control controll...
AllocatorsMap allocators_
MoveItControllerManager()
The default constructor. Reads the namespace from ~ros_control_namespace param and defaults to /...
virtual void getControllersList(std::vector< std::string > &names)
Refresh controller list and output all managed controllers.
pluginlib::ClassLoader< ControllerHandleAllocator > loader_