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
kill.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 import random
10 
11 import miro_msgs
12 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
13 
14 import opencv_apps
15 from opencv_apps.msg import CircleArrayStamped
16 
17 import math
18 import numpy
19 import time
20 import sys
21 from miro_constants import miro
22 
23 from datetime import datetime
24 
25 ## \file kill.py
26 ## \brief The node kill.py implements the action corresponding to the command "Kill".
27 ## @n The Robot moves down its head and squint the eyes. It changes its light pattern to Red and emits an aggressive sound.
28 
29 ##\brief The class KillMode implements a angry behavior for the robot
30 
31 class KillMode():
32 
33  def __init__(self):
34 
35  ## Node rate
36  self.rate = rospy.get_param('rate',200)
37  ## Publisher to the topic /miro_kill a message of type platform_control which corresponds to the "Kill" action.
38  self.pub_platform_control = rospy.Publisher('/miro_kill',platform_control,queue_size=0)
39 
40  ## Function that sets the parameters of the structure platform_control corresponding to action "Kill".
41  def miro_kill(self):
42 
43  r = rospy.Rate(self.rate)
44  q = platform_control()
45 
46  while not rospy.is_shutdown():
47 
48  q.eyelid_closure = 0.4
49  q.body_config = [0.0,0.87,0.0,0.75]
50  q.body_config_speed = [0.0,-1.0,-1.0,-1.0]
51  q.lights_raw = [255,0,0,255,0,0,255,0,0,255,0,0,255,0,0,255,0,0]
52  q.tail = 0.68
53  q.ear_rotate = [1.0,1.0]
54  q.sound_index_P2 = 15
55  self.pub_platform_control.publish(q)
56  r.sleep()
57 
58 if __name__== '__main__':
59  rospy.init_node('bad')
60  sad = KillMode()
61  sad.miro_kill()
def miro_kill
Function that sets the parameters of the structure platform_control corresponding to action "Kill"...
Definition: kill.py:41
The class KillMode implements a angry behavior for the robot.
Definition: kill.py:31
pub_platform_control
Publisher to the topic /miro_kill a message of type platform_control which corresponds to the "Kill" ...
Definition: kill.py:38
rate
Node rate.
Definition: kill.py:36