实时闭环控制系统(四)
目的
在实现完了自己的控制器后,然后想通过ControllerManager
去load
自己的的控制器。发现按照自己取的名字,并不能load控制,于是仔细看了一下ros_control
源码中,它去 load
controller
的流程。
流程
launch文件和命令行
根据官网的文档介绍
load或者其他操作一共有2个方法
1. Command-line tools
2. Creating launch files
然后,我找到了Command-line tools
的源码(当然 launch文件的解析程序 也在它同目录下)然后这货在调用controller_manager
(这应该是一个python包)里面的controller_manager_interface
的load_controller
方法。
def load_controller(name):
rospy.wait_for_service('controller_manager/load_controller')
s = rospy.ServiceProxy('controller_manager/load_controller', LoadController)
resp = s.call(LoadControllerRequest(name))
if resp.ok:
print "Loaded", name
return True
else:
print "Error when loading", name
return False
这里显示了,这个 load_controller
方法只是简单的调用controller_manager/load_controller
服务,而在我们之前的文章的已经提到,这个服务是controller_manager
提供的。
然后寻找到对应代码。
try{
c_nh = ros::NodeHandle(root_nh_, name);
}
catch(std::exception &e) {
ROS_ERROR("Exception thrown while constructing nodehandle for controller with name '%s':\n%s", name.c_str(), e.what());
return false;
}
catch(...){
ROS_ERROR("Exception thrown while constructing nodehandle for controller with name '%s'", name.c_str());
return false;
}
boost::shared_ptr<controller_interface::ControllerBase> c;
std::string type;
if (c_nh.getParam("type", type))
{
ROS_DEBUG("Constructing controller '%s' of type '%s'", name.c_str(), type.c_str());
try
{
// Trying loading the controller using all of our controller loaders. Exit once we've found the first valid loaded controller
std::list<LoaderPtr>::iterator it = controller_loaders_.begin();
while (!c && it != controller_loaders_.end())
{
std::vector<std::string> cur_types = (*it)->getDeclaredClasses();
for(size_t i=0; i < cur_types.size(); i++){
if (type == cur_types[i]){
c = (*it)->createInstance(type);
}
}
++it;
}
}
所以实际上这个服务的参数里面的name并不是控制器的类型,而只是一个命名空间的东西。 c_nh = ros::NodeHandle(root_nh_, name)
这一句话的作用就是,如果root_nh_
是/
则c_nh
是 /name
见文档。而name命名空间下的type
才是控制器的名字(见c_nh.getParam("type", type)
)。
而且c_nh
这个命名控制是会传进controller
的初始化函数里面。所以我们可以把controller的参数都放在c_nh
这个命名空间下。最后我们的config 文件为:
fake_controller:
type: art_controller/ArtController
因为我们目前只有type参数(即控制器的实际名字), 而art_controller/ArtController
是我们plugin.xml里面配置的名字。然后整个测试程序的launch文件如下:
<?xml version="1.0"?>
<launch>
<rosparam file="$(find art_fake_driver)/config/fake_controller.yaml" command="load" />
<node name="fake_driver" type="art_fake_driver" pkg="art_fake_driver" output="screen"/>
</launch>
那个node就是controller_manager
运行的地方。然后将上面的配置文件load。
其他注意
controller_manager
的各种服务都需要在主程序里面spin
。