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
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
14 from opencv_apps.msg
import CircleArrayStamped
20 from miro_constants
import miro
22 from datetime
import datetime
34 self.
rate = rospy.get_param(
'rate',200)
42 r = rospy.Rate(self.
rate)
43 q = platform_control()
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]
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:
56 self.pub_platform_control.publish(q)
62 if __name__==
'__main__':
63 rospy.init_node(
'sleep', disable_signals=
True)
def miro_sleep
Function that sets the parameters of the structure platform_control corresponding to action "Sleep"...
pub_platform_control
Publisher to the topic /miro_sleep a message of type platform_control which correspont to the sleep a...
The class SleepMode implements the sleeping behavior.