@@ -66,7 +66,6 @@ class AMSuper : AMLifeCycle
6666 ros::Publisher super_status_pub_;
6767 ros::Publisher led_pub_;
6868 ros::Subscriber node_state_sub_;
69- ros::Subscriber node_status_sub_;
7069 ros::Subscriber operator_command_sub_;
7170 ros::Subscriber controller_state_sub;
7271 ros::Subscriber diagnostics_sub;
@@ -214,10 +213,6 @@ class AMSuper : AMLifeCycle
214213 * node status via LifeCycle
215214 */
216215 node_state_sub_ = nh_.subscribe (" /node_state" , 100 , &AMSuper::nodeStateCB, this );
217- /* *
218- * legacy node status
219- */
220- node_status_sub_ = nh_.subscribe (" /process/status" , 100 , &AMSuper::statusCB, this );
221216
222217 /* *
223218 * commands from operator
@@ -264,24 +259,6 @@ class AMSuper : AMLifeCycle
264259 LOG_MSG (" /node_state" , rmsg, SU_LOG_LEVEL);
265260 }
266261
267- /* *
268- * process legacy messages from nodes
269- * TODO: mark deprecated due to legacy. use nodeStateCB.
270- */
271- void statusCB (const ros::MessageEvent<brain_box_msgs::NodeStatus const >& event)
272- {
273- const brain_box_msgs::NodeStatus::ConstPtr& rmsg = event.getMessage ();
274-
275- /*
276- * legacy messages don't carry any state or status info so just process as ACTIVE/OK
277- */
278- processState (rmsg->node_name , LifeCycleState::INACTIVE, LifeCycleStatus::OK, rmsg->status , rmsg->value ,
279- rmsg->process_id , event.getReceiptTime ());
280-
281- // TODO: topic name should come from vb_util_lib::topics.
282- LOG_MSG (" /process/status" , rmsg, SU_LOG_LEVEL);
283- }
284-
285262 void controllerStateCB (const ros::MessageEvent<brain_box_msgs::ControllerState const >& event)
286263 {
287264 const brain_box_msgs::ControllerState::ConstPtr& rmsg = event.getMessage ();
@@ -514,7 +491,7 @@ class AMSuper : AMLifeCycle
514491 {
515492 std::stringstream ss;
516493 genSystemState (ss);
517- ROS_INFO_STREAM ( ss.str ());
494+ ROS_INFO_STREAM_THROTTLE (LOG_THROTTLE_S, ss.str ());
518495 }
519496
520497 /* *
0 commit comments