遗留问题
- Timer、WallTimer、SteadyTime,有什么区别。
- 若在ros::shutdown时调用shutdownTimerManagers,会使得下一次ros::init后,cartographer栅格图像都收不到了,为什么。
- 线程使用chromium,当结束chromium后再销毁线程,什么为libros.lib时没问题,libros.dll时则有问题。
一、系统中TimerManager种类
定时器涉及到两种类:TimerManager、Timer/WallTimer/SteadyTime。TimerManager是个模板类。
template<class T, class D, class E> class TimerManager { static TimerManager& global() { static TimerManager<T, D, E> global; return global; } };
根据不同模板类型,会有不同的class TimerManager,目前看有三种。
- TimerManager<SteadyTime, WallDuration, SteadyTimerEvent>。它还有个typedef为的类型:InternalTimerManager。
- TimerManager<WallTime, WallDuration, WallTimerEvent>。示例:cartographer_occupancy_grid_node每隔1秒发布栅格地图。
- TimerManager<Time, Duration, TimerEvent>::global()。示例:cartographer_node每隔0.005秒发布坐标系变换关系。
Timer/WallTimer/SteadyTime对应定时器,它对应TimerManager的第一个模板参数T。针对种类是T的定时器,它要访问TimerManager时,统一用静态方法global()。举个例子,T时WallTime时,此类定时器由TimerManager<WallTime, WallDuration, WallTimerEvent>负责管理,当它要访问这个TimerManager时,使用TimerManager<WallTime, WallDuration, WallTimerEvent>::global()。
由于global()使用静态变量存储TimerManager,TimerManager实例是以着静态变量的方式存在于ros系统,而且最多三个。
二、相关线程
针对三种T,NodeHandler提供对应的创建定时器方法:createSteadyTimer、createWallTimer、createTimer。
使用者根据需要调用NodeHandler.create<xxx>Timer()创建个定时器,一个定时器一定属于某个TimerManager,对属于同一种TimerManager的定时器,它们共同使用一个线程,TimerManager管理着这个线程。由于系统中存在三种TimerManager,意味ros系统会最多存在三个和定时器相关的线程。
因为TimerManager实例以着静态变量的方式存在于ros系统,所以即使调用了ros::shutdown(),默认行为是不会销毁掉这些TimerManager,自然也就不会销毁它们内中的线程。
如果调用ros::shutdown()时意味着该进程结束了,即app要终止,不销毁TimerManager线程不会造成问题。但如果进程不会结束,那就须要修改ros::shutdown()行为了,让销毁这三个线程。
创建线程使用chromium,须要在chromium被停掉前销毁掉这三个线程。!libros是静态库时没有问题,dll才须要。
void shutdownTimerManagers() { if (getInternalTimerManager().get() != nullptr) { getInternalTimerManager()->shutdown(); } TimerManager<WallTime, WallDuration, WallTimerEvent>::global().shutdown(); TimerManager<Time, Duration, TimerEvent>::global().shutdown(); }
三、boost::bind改为std::bind时,带参数TimerCallback的createTimer报错
<libros>/include/actionlib/server/action_server_imp.h template<class ActionSpec> void ActionServer<ActionSpec>::initialize() { ... if (status_frequency > 0) { status_timer_ = node_.createTimer(ros::Duration(1.0 / status_frequency), boost::bind(&ActionServer::publishStatus, this, _1)); } ... }
把当中“boost::bind”改为“std::bind”后,报错。
1>move_base.cpp 1>C:\ddksample\studio\apps-src\apps\external\libros\include\actionlib\server\action_server_imp.h(178,14): error C2672: 'std::bind': no matching overloaded function found 1>(compiling source file '../../external/libros/move_base/src/move_base.cpp')
可代码,是有第2个参数是“std::function<void(const TimerEvent&)>”的createTimer版本。
typedef std::function<void(const TimerEvent&)> TimerCallback; Timer createTimer(Duration period, const TimerCallback& callback, bool oneshot = false, bool autostart = true) const;
ros库中有在调用这版本的createTimer,像amcl_node.cpp,而且不报错。到现在,没找到这报错原因,修改方法是用另一个版本的createTiner。
status_timer_ = node_.createTimer(ros::Duration(1.0 / status_frequency), &ActionServer::publishStatus, this); template<class T> Timer createTimer(Duration period, void(T::*callback)(const TimerEvent&), T* obj, bool oneshot = false, bool autostart = true) const { return createTimer(period, std::bind(callback, obj, _1), oneshot, autostart); }
这个版本就是让在createTimer内生成TimerCallback。或许吧,在调用createTimer时,尽量不用带参数TimerCallback的,改用多个“obj”。