@@ -39,7 +39,7 @@ async def wrapper(self, update: Update, context: CallbackContext):
39
39
"ROS Bridge initialized to another chat_id. Type /start to connect to this chat_id"
40
40
)
41
41
else :
42
- callback_function (self , update , context )
42
+ await callback_function (self , update , context )
43
43
44
44
return wrapper
45
45
@@ -58,7 +58,7 @@ def wrapper(self, msg):
58
58
rospy .logerr ("ROS Bridge not initialized, dropping message of type %s" , msg ._type )
59
59
else :
60
60
try :
61
- callback_function (self , msg )
61
+ asyncio . run ( callback_function (self , msg ) )
62
62
except TimedOut as e :
63
63
rospy .logerr ("Telegram timeout: %s" , e )
64
64
@@ -114,11 +114,11 @@ def _shutdown(self, reason: str):
114
114
Sending a message to the current chat id on destruction.
115
115
"""
116
116
if self ._telegram_chat_id :
117
- self ._telegram_app .bot .send_message (
117
+ asyncio . run ( self ._telegram_app .bot .send_message (
118
118
self ._telegram_chat_id ,
119
119
f"Stopping Telegram ROS bridge, ending this chat. Reason of shutdown: { reason } ."
120
120
" Type /start to connect again after starting a new Telegram ROS bridge." ,
121
- )
121
+ ))
122
122
123
123
def spin (self ):
124
124
"""
@@ -196,14 +196,14 @@ async def _telegram_message_callback(self, update: Update, _: CallbackContext):
196
196
self ._from_telegram_string_publisher .publish (String (data = text ))
197
197
198
198
@ros_callback
199
- def _ros_string_callback (self , msg : String ):
199
+ async def _ros_string_callback (self , msg : String ):
200
200
"""
201
201
Called when a new ROS String message is coming in that should be sent to the Telegram conversation
202
202
203
203
:param msg: String message
204
204
"""
205
205
if msg .data :
206
- self ._telegram_app .bot .send_message (self ._telegram_chat_id , msg .data )
206
+ await self ._telegram_app .bot .send_message (self ._telegram_chat_id , msg .data )
207
207
else :
208
208
rospy .logwarn ("Ignoring empty string message" )
209
209
@@ -216,8 +216,8 @@ async def _telegram_photo_callback(self, update: Update, _: CallbackContext):
216
216
:param update: Received update that holds the chat_id and message data
217
217
"""
218
218
rospy .logdebug ("Received image, downloading highest resolution image ..." )
219
- new_file = asyncio . run ( update .message .photo [- 1 ].get_file () )
220
- byte_array = asyncio . run ( new_file .download_as_bytearray () )
219
+ new_file = await update .message .photo [- 1 ].get_file ()
220
+ byte_array = await new_file .download_as_bytearray ()
221
221
rospy .logdebug ("Download complete, publishing ..." )
222
222
223
223
img = cv2 .imdecode (np .asarray (byte_array , dtype = np .uint8 ), cv2 .IMREAD_COLOR )
@@ -232,14 +232,14 @@ async def _telegram_photo_callback(self, update: Update, _: CallbackContext):
232
232
self ._from_telegram_string_publisher .publish (String (data = update .message .caption ))
233
233
234
234
@ros_callback
235
- def _ros_image_callback (self , msg : Image ):
235
+ async def _ros_image_callback (self , msg : Image ):
236
236
"""
237
237
Called when a new ROS Image message is coming in that should be sent to the Telegram conversation
238
238
239
239
:param msg: Image message
240
240
"""
241
241
cv2_img = self ._cv_bridge .imgmsg_to_cv2 (msg , "bgr8" )
242
- self ._telegram_app .bot .send_photo (
242
+ await self ._telegram_app .bot .send_photo (
243
243
self ._telegram_chat_id ,
244
244
photo = BytesIO (cv2 .imencode (".jpg" , cv2_img )[1 ].tobytes ()),
245
245
caption = msg .header .frame_id ,
@@ -263,16 +263,16 @@ async def _telegram_location_callback(self, update: Update, _: CallbackContext):
263
263
)
264
264
265
265
@ros_callback
266
- def _ros_location_callback (self , msg : NavSatFix ):
266
+ async def _ros_location_callback (self , msg : NavSatFix ):
267
267
"""
268
268
Called when a new ROS NavSatFix message is coming in that should be sent to the Telegram conversation
269
269
270
270
:param msg: NavSatFix that the robot wants to share
271
271
"""
272
- self ._telegram_app .bot .send_location (self ._telegram_chat_id , location = Location (msg .longitude , msg .latitude ))
272
+ await self ._telegram_app .bot .send_location (self ._telegram_chat_id , location = Location (msg .longitude , msg .latitude ))
273
273
274
274
@ros_callback
275
- def _ros_options_callback (self , msg : Options ):
275
+ async def _ros_options_callback (self , msg : Options ):
276
276
"""
277
277
Called when a new ROS Options message is coming in that should be sent to the Telegram conversation
278
278
@@ -284,7 +284,7 @@ def chunks(l, n): # noqa: E741
284
284
for i in range (0 , len (l ), n ):
285
285
yield l [i : i + n ] # noqa: E203
286
286
287
- self ._telegram_app .bot .send_message (
287
+ await self ._telegram_app .bot .send_message (
288
288
self ._telegram_chat_id ,
289
289
text = msg .question ,
290
290
reply_markup = ReplyKeyboardMarkup (
0 commit comments