MiRo-Training
The aim of the project is to develop a software architecture for interacting with Miro using vocal and gestural commands.
 All Classes Files Functions Variables
sleep.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 ################################################################
4 
5 import rospy
6 from std_msgs.msg import String
7 from sensor_msgs.msg import Image,CompressedImage,Range,Imu
8 from geometry_msgs.msg import Twist,Pose
9 
10 import miro_msgs
11 from miro_msgs.msg import platform_config,platform_sensors,platform_state,platform_mics,platform_control,core_state,core_control,core_config,bridge_config,bridge_stream
12 
13 import opencv_apps
14 from opencv_apps.msg import CircleArrayStamped
15 
16 import math
17 import numpy
18 import time
19 import sys
20 from miro_constants import miro
21 
22 from datetime import datetime
23 
24 ## \file sleep.py
25 ## \brief The node sleep.py implements the action corresponding to the command "Sleep"
26 ## @n Miro closes its eyes, lights up in acquamarine, lowers its tail and inclines and moves down its head.
27 
28 ## \brief The class SleepMode implements the sleeping behavior
29 class SleepMode():
30 
31  def __init__(self):
32 
33  ## Node rate
34  self.rate = rospy.get_param('rate',200)
35 
36  ## Publisher to the topic /miro_sleep a message of type platform_control which correspont to the sleep action
37  self.pub_platform_control = rospy.Publisher('/miro_sleep',platform_control,queue_size=0)
38 
39  ## Function that sets the parameters of the structure platform_control corresponding to action "Sleep"
40  def miro_sleep(self):
41 
42  r = rospy.Rate(self.rate)
43  q = platform_control()
44 
45  while True:
46  try:
47  q.eyelid_closure = 1.0
48  q.lights_raw = [0,255,255,0,0,0,0,0,0,0,0,0,0,0,0,0,255,255] #white color
49  q.tail = -1.0
50  q.ear_rotate = [0.0,0.0]
51  q.body_config = [0.0,0.8,0.3,0.02]
52  q.body_config_speed = [0.0,-1.0,-1.0,-1.0]
53  self.pub_platform_control.publish(q)
54  except KeyboardInterrupt:
55 
56  self.pub_platform_control.publish(q)
57  break
58  r.sleep()
59 
60 
61 
62 if __name__== '__main__':
63  rospy.init_node('sleep', disable_signals=True)
64  sleep = SleepMode()
65  sleep.miro_sleep()
def miro_sleep
Function that sets the parameters of the structure platform_control corresponding to action "Sleep"...
Definition: sleep.py:40
pub_platform_control
Publisher to the topic /miro_sleep a message of type platform_control which correspont to the sleep a...
Definition: sleep.py:37
The class SleepMode implements the sleeping behavior.
Definition: sleep.py:29
rate
Node rate.
Definition: sleep.py:34