From ec77068722431e6cc408d0c43886102e947a4696 Mon Sep 17 00:00:00 2001 From: Matt Marcum Date: Fri, 18 Oct 2019 09:42:24 -0400 Subject: [PATCH] For our application, we have been using the Simple Dispatcher. We at times dispatch and complete actions very rapidly. There have been instances where the Simple Dispatcher will drop important messages ('action achieved') because its subscription buffer size for feedback/status is only 1. This can cause our system to abruptly stop dispatching new commands because it is not informed that it has successfully completed the prior action. Increasing the buffer size of the action feedback status from to 1 to 1000 has solved our issue. --- .../src/PlanDispatch/SimplePlanDispatcher.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rosplan_planning_system/src/PlanDispatch/SimplePlanDispatcher.cpp b/rosplan_planning_system/src/PlanDispatch/SimplePlanDispatcher.cpp index cd247774e..9e7d91043 100644 --- a/rosplan_planning_system/src/PlanDispatch/SimplePlanDispatcher.cpp +++ b/rosplan_planning_system/src/PlanDispatch/SimplePlanDispatcher.cpp @@ -187,7 +187,7 @@ namespace KCL_rosplan { std::string feedbackTopic = "action_feedback"; nh.getParam("action_feedback_topic", feedbackTopic); - ros::Subscriber feedback_sub = nh.subscribe(feedbackTopic, 1, &KCL_rosplan::SimplePlanDispatcher::feedbackCallback, &spd); + ros::Subscriber feedback_sub = nh.subscribe(feedbackTopic, 1000, &KCL_rosplan::SimplePlanDispatcher::feedbackCallback, &spd); ROS_INFO("KCL: (%s) Ready to receive", ros::this_node::getName().c_str()); ros::spin();