@@ -68,6 +68,8 @@ class AMSuper : AMLifeCycle
6868 ros::Publisher system_state_pub_;
6969 ros::Publisher super_status_pub_;
7070 ros::Publisher led_pub_;
71+ /* * stops the flight plan when SHUTDOWN state */
72+ ros::Publisher flight_plan_deactivation_pub_;
7173 ros::Subscriber node_state_sub_;
7274 ros::Subscriber operator_command_sub_;
7375 ros::Subscriber controller_state_sub;
@@ -199,6 +201,8 @@ class AMSuper : AMLifeCycle
199201 */
200202 super_status_pub_ = nh_.advertise <brain_box_msgs::Super2Status>(am_super_topics::SUPER_STATUS, 1000 );
201203
204+ flight_plan_deactivation_pub_ = nh_.advertise <std_msgs::Bool>(am_topics::CTRL_FLIGHTPLAN_ACTIVITY_CONTROL, 1000 );
205+
202206 supervisor_.system_state = SuperState::BOOTING;
203207 supervisor_.flt_ctrl_state = SuperNodeMediator::SuperFltCtrlState::INIT;
204208
@@ -330,6 +334,7 @@ class AMSuper : AMLifeCycle
330334 {
331335 supervisor_.status_error = true ;
332336 ROS_ERROR_STREAM (" Manifested node " << nr.name << " changed status to ERROR. Shutting down nodes... [JHRE]" );
337+ stopFlightPlan ();
333338 }
334339 }
335340 if (nr.pid != pid)
@@ -554,6 +559,15 @@ class AMSuper : AMLifeCycle
554559 return success;
555560 }
556561
562+
563+ /* * Send signal to flight controller that flight is over. */
564+ void stopFlightPlan ()
565+ {
566+ std_msgs::Bool msg;
567+ msg.data = false ; // false means deactivate
568+ flight_plan_deactivation_pub_.publish (msg);
569+ }
570+
557571 /* *
558572 * check for state transition based upon current state and values of member fields.
559573 * Will call to modify the system state if transition is necessary. Will also call
0 commit comments