couldn't kill node through rosnode kill with moditied (rosnode kill)XMLRPC callback
trying to copy the code from here
here is my code,ctrl + c just work fine:
sig_atomic_t volatile g_request_shutdown = 0;
// Replacement SIGINT handler
void mySigIntHandler(int sig) {
ROS_WARN("Shutdown request received. Reason: SIGINT");
g_request_shutdown = 1;
ros::shutdown();
}
// Replacement "shutdown" XMLRPC callback
void shutdownCallback(XmlRpc::XmlRpcValue& params,
XmlRpc::XmlRpcValue& result) {
int num_params = 0;
if (params.getType() == XmlRpc::XmlRpcValue::TypeArray)
num_params = params.size();
if (num_params > 1) {
std::string reason = params[1];
ROS_WARN("Shutdown request received. Reason: [%s]", reason.c_str());
ros::shutdown();
g_request_shutdown = 1; // Set flag
}
result = ros::xmlrpc::responseInt(1, "", 0);
}
int main(int argc, char** argv) {
ros::init(argc, argv, "robot_decision_node",
ros::init_options::NoSigintHandler);
signal(SIGINT, mySigIntHandler);
// Override XMLRPC shutdown
ros::XMLRPCManager::instance()->unbind("shutdown");
ros::XMLRPCManager::instance()->bind("shutdown", shutdownCallback);
Decision d;
d.Init();
ros::Rate loopRate(10);
while (!g_request_shutdown) {
ros::spinOnce();
}
ROS_INFO("after spin");
ros::shutdown();
return 0;
}
then i got another try, changing from spinOnce() to ros::spin(), but still, ctrl + c works fine ,but rosnode kill failed.here is the new code
sig_atomic_t volatile g_request_shutdown = 0;
// Replacement SIGINT handler
void mySigIntHandler(int sig) {
ROS_WARN("Shutdown request received. Reason: SIGINT");
g_request_shutdown = 1;
ros::shutdown();
}
// Replacement "shutdown" XMLRPC callback
void shutdownCallback(XmlRpc::XmlRpcValue& params,
XmlRpc::XmlRpcValue& result) {
int num_params = 0;
if (params.getType() == XmlRpc::XmlRpcValue::TypeArray)
num_params = params.size();
if (num_params > 1) {
std::string reason = params[1];
ROS_WARN("Shutdown request received. Reason: [%s]", reason.c_str());
ros::shutdown();
g_request_shutdown = 1; // Set flag
}
result = ros::xmlrpc::responseInt(1, "", 0);
}
int main(int argc, char** argv) {
ros::init(argc, argv, "robot_decision_node",
ros::init_options::NoSigintHandler);
signal(SIGINT, mySigIntHandler);
// Override XMLRPC shutdown
ros::XMLRPCManager::instance()->unbind("shutdown");
ros::XMLRPCManager::instance()->bind("shutdown", shutdownCallback);
Decision d;
d.Init();
ros::spin(); // ***change here!!!!***
ROS_INFO("after spin");
ros::shutdown();
return 0;
}
now with commenting the ros::shutdown() in call back ,it's worked fine, but why????
sig_atomic_t volatile g_request_shutdown = 0;
// Replacement SIGINT handler
void mySigIntHandler(int sig) {
ROS_WARN("Shutdown request received. Reason: SIGINT");
g_request_shutdown = 1;
// ros::shutdown(); // change here!!!!!
}
// Replacement "shutdown" XMLRPC callback
void shutdownCallback(XmlRpc::XmlRpcValue& params,
XmlRpc::XmlRpcValue& result) {
int num_params = 0;
if (params.getType() == XmlRpc::XmlRpcValue::TypeArray)
num_params = params.size();
if (num_params > 1) {
std::string reason = params[1];
ROS_WARN("Shutdown request received. Reason: [%s]", reason.c_str());
// ros::shutdown(); // change here!!!!!
g_request_shutdown = 1; // Set flag
}
result = ros::xmlrpc::responseInt(1, "", 0);
}
int main(int argc, char** argv) {
ros::init(argc, argv, "robot_decision_node",
ros::init_options::NoSigintHandler);
signal(SIGINT, mySigIntHandler);
// Override XMLRPC shutdown
ros::XMLRPCManager::instance()->unbind("shutdown");
ros::XMLRPCManager::instance()->bind("shutdown", shutdownCallback);
Decision d;
d.Init();
ros::Rate loopRate(10);
while (!g_request_shutdown) {
ros::spinOnce();
}
ROS_INFO("after spin");
ros::shutdown();
return 0;
}