Skip to content

Commit

Permalink
[jsk_robot_startup] Support dynamic reconfigure in smach_to_mail to s…
Browse files Browse the repository at this point in the history
…end google chat for every state transition
  • Loading branch information
k-okada committed Oct 27, 2023
1 parent 0dfd2b6 commit 56b5448
Show file tree
Hide file tree
Showing 3 changed files with 41 additions and 6 deletions.
1 change: 1 addition & 0 deletions jsk_robot_common/jsk_robot_startup/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@ generate_dynamic_reconfigure_options(
cfg/OdometryFeedbackWrapperReconfigure.cfg
cfg/ConstantHeightFramePublisherReconfigure.cfg
cfg/JointStatesThrottle.cfg
cfg/SmachNotificationReconfigure.cfg
)

add_message_files(
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
#!/usr/bin/env python

from dynamic_reconfigure.parameter_generator_catkin import *

PKG = "jsk_robot_startup"

gen = ParameterGenerator()

gen.add("send_every_transition", bool_t, 0, "Send notification every transition", False)
gen.add("use_mail", bool_t, 0, "Use mail for smach notification", True)
gen.add("use_twitter", bool_t, 0, "Use twitter for smach notification", True)
gen.add("use_google_chat", bool_t, 0, "Use google chat for smach notification", True)

exit(gen.generate(PKG, PKG, "SmachNotificationReconfigure"))
32 changes: 26 additions & 6 deletions jsk_robot_common/jsk_robot_startup/scripts/smach_to_mail.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@
import sys

from cv_bridge import CvBridge
from dynamic_reconfigure.server import Server
from jsk_robot_startup.cfg import SmachNotificationReconfigureConfig
from jsk_robot_startup.msg import Email
from jsk_robot_startup.msg import EmailBody
from sensor_msgs.msg import CompressedImage
Expand All @@ -38,12 +40,10 @@ 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", _enable_google_chat)
self.pub_email = rospy.Publisher("email", Email, queue_size=10)
self.pub_twitter = rospy.Publisher("tweet", String, queue_size=10)
self.reconfigure_server = Server(
SmachNotificationReconfigureConfig, self._reconfigure_cb)
rospy.Subscriber(
"~smach/container_status", SmachContainerStatus, self._status_cb)
rospy.Timer(rospy.Duration(
Expand Down Expand Up @@ -71,6 +71,18 @@ def __init__(self):
self.gchat_image_dir = rospy.get_param("~google_chat_tmp_image_dir", "/tmp")
self._gchat_thread = None

def _reconfigure_cb(self, config, level):
self.use_mail = config['use_mail']
self.use_twitter = config['use_twitter']
self.use_google_chat = config['use_google_chat']
self.send_every_transition = config['send_every_transition']
rospy.loginfo(
"Switched parameters; use_mail: {send_every_transition}, "
"use_twitter: {use_twitter}, "
"use_google_chat: {use_google_chat}, "
"send_every_transition: {send_every_transition}".format(**config))
return config

def _stop_timer_cb(self, event):
'''
If smach does not go to finish/end state,
Expand Down Expand Up @@ -170,6 +182,14 @@ def _status_cb(self, msg):
else:
self.smach_state_list[caller_id].append(status_dict)

# send notification every transition
if (self.send_every_transition
and self.use_google_chat
and not self.smach_state_list[caller_id] is None):
rospy.loginfo("Send every transition called")
self._send_google_chat(
self.smach_state_subject[caller_id], [status_dict])

# If we received END/FINISH status, send email, etc...
if status_str in ["END", "FINISH", "FINISH-SUCCESS", "FINISH-FAILURE"]:
if (caller_id not in self.smach_state_list) or self.smach_state_list[caller_id] is None:
Expand All @@ -185,7 +205,7 @@ def _status_cb(self, msg):
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:
if self.use_google_chat and not self.send_every_transition:
self._send_google_chat(self.smach_state_subject[caller_id], self.smach_state_list[caller_id])
self.smach_state_list[caller_id] = None
self.smach_state_subject[caller_id] = None
Expand Down Expand Up @@ -304,7 +324,7 @@ def _send_google_chat(self, subject, state_list):
result = self.gchat_ac.get_result()
if not self._gchat_thread:
self._gchat_thread = result.message_result.thread_name
rospy.loginfo("Sending google chat messsage: {} to {} chat space".format(text, self.chat_space))
rospy.loginfo("Sending google chat messsage:{} chat space, {} thread".format(self.chat_space, self._gchat_thread))
rospy.logdebug("Google Chat result: {}".format(self.gchat_ac.get_result()))

if __name__ == '__main__':
Expand Down

0 comments on commit 56b5448

Please sign in to comment.