Skip to content

Latest commit

 

History

History
162 lines (122 loc) · 4.93 KB

Signal.md

File metadata and controls

162 lines (122 loc) · 4.93 KB

Signal

FAQ

问题 1: escalating to SIGTERM 是什么问题?

ROS 尝试使用 SIGINT 来释放进程,但如果一段时间后,进程仍未结束,则使用 SIGTERM 信号来结束进程。

问题 2: 为什么进程无法使用 SIGINIT 正常结束?

进程中的线程可能挂起,而无法接收到 SIGINIT 信号。如何使用日志进行调试,判断线程是否的确在挂起?

#include <ros/ros.h>
#include <thread>
#include <mutex>
#include <condition_variable>

std::mutex mtx;
// 该条件变量不需要赋值
std::condition_variable cv;
bool ready = false;

// waitForEvent 函数等待一个条件变量。它在开始和结束等待时记录日志信息。
void waitForEvent() {
  std::unique_lock<std::mutex> lock(mtx);
  ROS_INFO("Waiting for the event to be set...");    
  // 阻塞当前线程,在这种情况下线程会调用 wait() 进行挂起;
  // 当被 notify_one() 唤醒后,如果 ready 为 True 则停止阻塞
  cv.wait(lock, [] { return ready; });
  // 如果使用 CTRL + C 后,该日志没有打印,则证明的确是挂起了
  ROS_INFO("Finished waiting. Event was set.");
}

// 设置事件的函数
void setEvent() {
  {
    // 给互斥锁上锁,其作用域下的变量都在临界区
    std::lock_guard<std::mutex> lock(mtx);
    ROS_INFO("Setting the event...");
    ready = true;
  }
  // 条件变量 std::condition_variable 的一个成员函数 notify_one() 通知一个等待的线程
  cv.notify_one();
}

int main(int argc, char **argv) {
  ros::init(argc, argv, "multi_threaded_node");
  ros::NodeHandle nh;

  ROS_INFO("Starting threads...");

  std::thread worker(waitForEvent);
  std::thread setter(setEvent);

  worker.join();
  setter.join();

  ROS_INFO("All threads finished.");

  return 0;
}
问题 3: 如何修改 Timeout 触发 SIGTERM 的时间

具体可修改如下配置:

# DEFAULT_TIMEOUT_SIGINT  = 15.0 #seconds
# DEFAULT_TIMEOUT_SIGTERM = 2.0 #seconds

# Melodic
$ sudo vim /opt/ros/melodic/lib/python2.7/dist-packages/roslaunch/nodeprocess.py
# Noetic
$ sudo vim /opt/ros/noetic/lib/python3/dist-packages/roslaunch/nodeprocess.py
问题 4: 一个 ROS 进程怎样才算正常的退出

使用 CTRL + C 的退出:触发 SIGINIT 信号,ros::spin()ros::waitForShutdown() 接收到 SIGTINT 信号后,则停止阻塞以执行后面的语句,从而顺利地执行 main() 函数

int main() {
	
    // ...
    ros::waitForShutdown();
    // ros::spin();

    printf("\033[1;32m[Signal] Receive signal to shutdown\033[0m \n");
    return 0;
}
问题 5: 分析 DLIO 进程无法正确退出的原因?

DLIO 会在 cv_imu_stamp.wait 中挂起,因此会屏蔽 SIGINT 信号,可使用上 ros::ok() + 使用 SIGINT 中断函数解决

if (this->imu_buffer.empty() || this->imu_buffer.front().stamp < end_time) {
  // Wait for the latest IMU data
  std::unique_lock<decltype(mtx_imu)> lock(mtx_imu);
  cv_imu_stamp.wait(lock, [this, &end_time] {
    // ros::ok() is used to prevent the thread from waiting and not exiting
    bool status = this->imu_buffer.front().stamp >= end_time or !ros::ok();
    return status; }
    );
}

void signalINTHandler(int signum) {
  printf("\033[1;32m[Signal] Receive SIGINT signal to shutdown\033[0m \n");
  ros::shutdown();
  cv_imu_stamp.notify_one();
}

int main() {
  // ...
  signal(SIGINT, signalINTHandler);
  // ...
}
问题 6: 节点中断的相关知识点

在 bash 启动的 roslaunch 可以被 kill -s 2(键盘中断)中断,这种中断可以让节点顺利退出
使用 kill -s 9 中断节点或 roslaunch 进程可能会导致节点部分程序资源没有被完全回收,无法正常退出。最终表现为即使对应的进程已经关闭,但依然可以通过 rosnode 看到该节点(该节点没有从 rosmaster 中注销成功),若要通过命令行注销则需要使用 rosnode cleanup

  • 由于 kill -s 9 或者程序资源没有回收完全的原因,即使对应的进程已经关闭,但是还是可以通过 rosnode 看到该节点(该节点没有完全从 rosmaster 中注销成功),若要通过命令行注销则需要使用 rosnode cleanup
  • 使用 kill -s 9 作用于 launch 进程时,其管理的节点可能不会成功退出,因此在 rosnode 中仍然能看到,使用 kill -s 2