-
Notifications
You must be signed in to change notification settings - Fork 26
Open
Labels
Milestone
Description
If capability server is launched after another node that calls the "start_capability" service as soon as it's available, capability_server will sometimes store "None" as the PID of the launched capability. You get an error like:
ERROR: service [/capability_server/stop_capability] responded with an error: error processing request: No running launch file with PID of 'None'
Echoing the "events" topic when this happens shows that the "launched" event happens before the "server_ready" event:
header:
seq: 1
stamp:
secs: 1430405899
nsecs: 543864965
frame_id: ''
capability: slam/Localization
provider: slam/localization
type: "launched"
pid: 22241
---
header:
seq: 2
stamp:
secs: 0
nsecs: 0
frame_id: ''
capability: ''
provider: ''
type: "server_ready"
pid: 0
I am able to reproduce this about 25% of the time with the following small node:
#include <ros/ros.h>
#include <capabilities/GetCapabilitySpecs.h>
#include <capabilities/StartCapability.h>
int main(int argc, char **argv)
{
ros::init(argc, argv, "capability_test");
ros::NodeHandle n;
ros::ServiceClient start_capability =
n.serviceClient<capabilities::StartCapability>("capability_server/start_capability");
ros::service::waitForService("capability_server/start_capability");
capabilities::StartCapability start_srv;
start_srv.request.capability = "slam/Localization";
start_capability.call(start_srv);
return 0;
}
I considered listening for the "server_ready" event before trying to call the service, but that causes issues if the client node start long after the "server_ready" event happens because it will miss this event.