From 011167e1d23af85666330a8936c2398f95b65e80 Mon Sep 17 00:00:00 2001 From: Yoshiki Obinata Date: Sat, 27 Aug 2022 13:02:04 +0900 Subject: [PATCH] [jsk_robot_startup] add launch file for smach_to_mail --- .../launch/smach_to_mail.launch | 27 +++++++++++++++++ .../scripts/smach_to_mail.py | 30 +++++++++---------- 2 files changed, 42 insertions(+), 15 deletions(-) create mode 100644 jsk_robot_common/jsk_robot_startup/launch/smach_to_mail.launch diff --git a/jsk_robot_common/jsk_robot_startup/launch/smach_to_mail.launch b/jsk_robot_common/jsk_robot_startup/launch/smach_to_mail.launch new file mode 100644 index 00000000000..3e309799248 --- /dev/null +++ b/jsk_robot_common/jsk_robot_startup/launch/smach_to_mail.launch @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + use_mail: $(arg use_mail) + use_twitter: $(arg use_twitter) + use_google_chat: $(arg use_google_chat) + + + + diff --git a/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py b/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py index a055155b8b4..57779c32550 100755 --- a/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py +++ b/jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py @@ -29,6 +29,9 @@ def __init__(self): rospy.init_node('server_name') # it should be 'smach_to_mail', but 'server_name' # is the default name of smach_ros + self.use_mail = rospy.get_param("~use_mail", True) + self.use_twitter = rospy.get_param("~use_twitter", True) + self.use_google_chat = rospy.get_param("~use_google_chat", True) self.pub_email = rospy.Publisher("email", Email, queue_size=10) self.pub_twitter = rospy.Publisher("tweet", String, queue_size=10) rospy.Subscriber( @@ -47,20 +50,14 @@ def __init__(self): self.sender_address = self.email_info['sender_address'] self.receiver_address = self.email_info['receiver_address'] else: - if rospy.has_param("~sender_address"): + if self.use_mail: self.sender_address = rospy.get_param("~sender_address") - else: - rospy.logerr("Please set rosparam {}/sender_address".format( - rospy.get_name())) - if rospy.has_param("~receiver_address"): self.receiver_address = rospy.get_param("~receiver_address") - else: - rospy.logerr("Please set rosparam {}/receiver_address".format( - rospy.get_name())) - self.gchat_ac = actionlib.SimpleActionClient("/google_chat_ros/send", SendMessageAction) - self.chat_space = rospy.get_param("~google_chat_space", "spaces/AAAARE9CrfA") # default: fetch threaded space - self.gchat_image_dir = rospy.get_param("~google_chat_tmp_image_dir", "/tmp") - self._gchat_thread = None + if self.use_google_chat: + self.gchat_ac = actionlib.SimpleActionClient("/google_chat_ros/send", SendMessageAction) + self.chat_space = rospy.get_param("~google_chat_space") + self.gchat_image_dir = rospy.get_param("~google_chat_tmp_image_dir", "/tmp") + self._gchat_thread = None def _status_cb(self, msg): ''' @@ -142,9 +139,12 @@ def _status_cb(self, msg): for x in self.smach_state_list[caller_id]: rospy.loginfo(" - At {}, Active state is {}{}".format(x['TIME'], x['STATE'], "({})".format(x['INFO']) if x['INFO'] else '')) - self._send_mail(self.smach_state_subject[caller_id], self.smach_state_list[caller_id]) - self._send_twitter(self.smach_state_subject[caller_id], self.smach_state_list[caller_id]) - self._send_google_chat(self.smach_state_subject[caller_id], self.smach_state_list[caller_id]) + if self.use_mail: + self._send_mail(self.smach_state_subject[caller_id], self.smach_state_list[caller_id]) + if self.use_twitter: + self._send_twitter(self.smach_state_subject[caller_id], self.smach_state_list[caller_id]) + if self.use_google_chat: + self._send_google_chat(self.smach_state_subject[caller_id], self.smach_state_list[caller_id]) self.smach_state_list[caller_id] = None def _send_mail(self, subject, state_list):