实时闭环控制系统(二)
目的
在实现自己的闭环ros_control
的cotroller
的中,我们需要在cotroller
获取几个的具体的interface的数据,而在ros_control
中controller的默认的init函数中已经变成具体的interface,所以需要去overrideinit
的上一层函数initRequest
的实现,从而达到自己的目标。
ros_controller中的资源管理
这个问题来源于对controller_interface::Controller的initRequest
的观察。在它的120行~128行出现了相关的使用。
hw->clearClaims();
if (!init(hw, controller_nh) || !init(hw, root_nh, controller_nh))
{
ROS_ERROR("Failed to initialize the controller");
return false;
}
hardware_interface::InterfaceResources iface_res(getHardwareInterfaceType(), hw->getClaims());
claimed_resources.assign(1, iface_res);
hw->clearClaims();
其中,此处的hw已经为具体的interface,而不是hardware_interface::RobotHW
的类型。然后它调用了clearClaims()
与getClaims()
,而这2个方法继承于HardwareInterface
类(具体的来讲HardwareResourceManager
继承了HardwareInterface
,而各种详细的interface继承HardwareResourceManager
)。HardwareInterface程序如下:
class HardwareInterface
{
public:
virtual ~HardwareInterface() {}
/** \name Resource management
*\{**/
/// Claim a resource by name
virtual void claim(std::string resource) { claims_.insert(resource); }
/// Clear the resources this interface is claiming
void clearClaims() { claims_.clear(); }
/// Get the list of resources this interface is currently claiming
std::set<std::string> getClaims() const { return claims_; }
/*\}*/
private:
std::set<std::string> claims_;
};
所以实际上clearClaims()
只是为了清空claims_
,而getClaims()
只是为了得到claims_
,说明claims_
在 init()
中发生改变。我们随便打开一个控制器的源码,比如joint_trajectory_controller
,发现与hw相关的东西只有251行的try {joints_[i] = hw->getHandle(joint_names_[i]);}
。所以我们只能去查看getHandle定义,然后发现了
ResourceHandle getHandle(const std::string& name)
{
try
{
ResourceHandle out = this->ResourceManager<ResourceHandle>::getHandle(name);
// If ClaimPolicy type is ClaimResources, the below method claims resources, for DontClaimResources it's a no-op
ClaimPolicy::claim(this, name);
return out;
}
catch(const std::logic_error& e)
{
throw HardwareInterfaceException(e.what());
}
}
而ClaimPolicy::claim(this, name)
定义如下:
struct ClaimResources
{
static void claim(HardwareInterface* hw, const std::string& name) {hw->claim(name);}
};
struct DontClaimResources
{
static void claim(HardwareInterface* /*hw*/, const std::string& /*name*/) {}
};
所以claimed_resources
只是记录了这个控制器使用的某interface的具体的handle的名字,从而达到检查冲突的效果(检查冲突的函数是robot_hw中的checkForConflict
)。不过它只在controller_managerswitchController
中被调用。另外的发现,在于资源管理这货只对要进行写操作的东西。所以对传感器并不在意被多读。
其他东西
controllers_lists_ and current_controllers_list_
这个是controller_manager里面用来切换控制器的东西。 其中controllers_lists_
为一个std::vector<ControllerSpec>
的数组,长度为2,主要是为了方便在不同的控制器组里面切换。而current_controllers_list_
用于表示在update()
函数中使用的std::vector<ControllerSpec>
的index。关于切换的操作,主要是controller_manager提供了switchController
方法,在这里,controllers_lists_
就被用上了,它就是将要切换到的控制器组的ControllerSpec
放在controllers_lists_
空余的那一个位置,然后将please_switch_
置为true,从而在update()
中进行切换(这么操作原因,主要是控制主程序与服务的回调函数不是在一个线程里面)。
ControllerSpec
struct ControllerSpec
55 {
56 hardware_interface::ControllerInfo info;
57 boost::shared_ptr<controller_interface::ControllerBase> c;
58 };
所以它主要包括了一个 hardware_interface::ControllerInfo
与一个controller_interface::ControllerBase
的指针。其中hardware_interface::ControllerInfo
具有一个名为claimed_resources
的成员。它主要管理资源,即为一个InterfaceResource
的vector。然后InterfaceResource
就是存储每个interface与它所包含资源的名字。