CrazyRadio.py 7.64 KB
Newer Older
bucyril's avatar
bucyril committed
1
2
3
#!/usr/bin/env python
# -*- coding: utf-8 -*-

4
import roslib; roslib.load_manifest('d_fall_pps')
bucyril's avatar
bucyril committed
5
import rospy
6
from d_fall_pps.msg import ControlCommand
7
from std_msgs.msg import Int32
bucyril's avatar
bucyril committed
8
9
10
11
12
13
14


# General import
import time, sys
import struct
import logging

15
import rosbag
16
from rospkg import RosPack
17
18
19
from std_msgs.msg import Float32
from std_msgs.msg import String

bucyril's avatar
bucyril committed
20
21
22
23
24
25
26
27
28
29
30
# Add library
#sys.path.append("lib")

# CrazyFlie client imports
import cflib

from cflib.crazyflie import Crazyflie
from cflib.crtp.crtpstack import CRTPPacket, CRTPPort

import cflib.drivers.crazyradio

31
# Logging import(*
bucyril's avatar
bucyril committed
32
33
34
35
36
from cflib.crazyflie.log import LogConfig

# Logging settings
logging.basicConfig(level=logging.ERROR)

37
38
39
CONTROLLER_MOTOR = 2
CONTROLLER_ANGLE = 1
CONTROLLER_RATE = 0
40
RAD_TO_DEG = 57.296
41

42
43
44
45
46
47
48
49
# CrazyRadio states:
CONNECTED = 0
CONNECTING = 1
DISCONNECTED = 2

# Commands coming
CMD_RECONNECT = 0

50
51
rp = RosPack()
record_file = rp.get_path('d_fall_pps') + '/LoggingOnboard.bag'
bucyril's avatar
bucyril committed
52
53
rospy.loginfo('afdsasdfasdfsadfasdfasdfasdfasdfasdfasdf')
rospy.loginfo(record_file)
54
bag = rosbag.Bag(record_file, 'w')
55

56
class PPSRadioClient:
bucyril's avatar
bucyril committed
57
    """
58
59
       CrazyRadio client that recieves the commands from the controller and
       sends them in a CRTP package to the crazyflie with the specified
60
       address.
bucyril's avatar
bucyril committed
61
62
63
64
65
66
67
68
69
70
71
    """
    def __init__(self, link_uri):

        # Setpoints to be sent to the CrazyFlie
        self.roll = 0.0
        self.pitch = 0.0
        self.yaw = 0.0
        self.motor1cmd = 0.0
        self.motor2cmd = 0.0
        self.motor3cmd = 0.0
        self.motor4cmd = 0.0
72
        self._status = DISCONNECTED
73
        self.link_uri = link_uri
bucyril's avatar
bucyril committed
74

75
76
        self.status_pub = rospy.Publisher('CrazyRadioStatus', Int32, queue_size=1)

bucyril's avatar
bucyril committed
77
78
79
        # Initialize the CrazyFlie and add callbacks
        self._cf = Crazyflie()

80
        # Add callbacks that get executed depending on the connection _status.
bucyril's avatar
bucyril committed
81
82
83
84
85
        self._cf.connected.add_callback(self._connected)
        self._cf.disconnected.add_callback(self._disconnected)
        self._cf.connection_failed.add_callback(self._connection_failed)
        self._cf.connection_lost.add_callback(self._connection_lost)

86
        self.change_status_to(DISCONNECTED)
bucyril's avatar
bucyril committed
87
88
        # Connect to the Crazyflie
        print "Connecting to %s" % link_uri
89
90
91
92
93
        self.connect()

    def change_status_to(self, new_status):
        self._status = new_status
        self.status_pub.publish(new_status)
94

95
96
    def get_status(self):
        return self._status
97
98

    def connect(self):
99
        self.change_status_to(CONNECTING)
100
101
        rospy.loginfo("connecting...")
        self._cf.open_link(self.link_uri)
roangel's avatar
roangel committed
102

103
    def _data_received_callback(self, timestamp, data, logconf):
104
        #print "log of stabilizer and battery: [%d][%s]: %s" % (timestamp, logconf.name, data)
105
        batteryVolt = Float32()
106
107
108
        stabilizerYaw = Float32()
        stabilizerPitch = Float32()
        stabilizerRoll = Float32()
109
        batteryVolt.data = data["pm.vbat"]
110
111
112
113
114
115
        stabilizerYaw.data = data["stabilizer.yaw"]
        stabilizerPitch.data = data["stabilizer.pitch"]
        bag.write('batteryVoltage', batteryVolt)
        bag.write('stabilizerYaw', stabilizerYaw)
        bag.write('stabilizerPitch', stabilizerPitch)
        bag.write('stabilizerRoll', stabilizerRoll)
116
117

        #publish battery voltage for GUI
118
119
120
        #cfbattery_pub.publish(std_msgs.Float32(batteryVolt.data))
        cfbattery_pub.publish(batteryVolt)

121
122


123
124
    def _logging_error(self, logconf, msg):
        print "Error when logging %s" % logconf.name
bucyril's avatar
bucyril committed
125
126
127
128
129
130

    def _connected(self, link_uri):
        """
            This callback is executed as soon as the connection to the
            quadrotor is established.
        """
131
        self.change_status_to(CONNECTED)
bucyril's avatar
bucyril committed
132
        rospy.loginfo("Connection to %s successful: " % link_uri)
133
134


135
        # Config for Logging
136
        logconf = LogConfig("LoggingTest", 100)
137
138
139
140
        logconf.add_variable("stabilizer.roll", "float");
        logconf.add_variable("stabilizer.pitch", "float");
        logconf.add_variable("stabilizer.yaw", "float");
        logconf.add_variable("pm.vbat", "float");
141

142
143
144
145
146
147
148
149
        self._cf.log.add_config(logconf)
        if logconf.valid:
            logconf.data_received_cb.add_callback(self._data_received_callback)
            logconf.error_cb.add_callback(self._logging_error)
            logconf.start()
            print "logconf valid"
        else:
            print "logconf invalid"
150

bucyril's avatar
bucyril committed
151
152
153
154

    def _connection_failed(self, link_uri, msg):
        """Callback when connection initial connection fails (i.e no Crazyflie
        at the specified address)"""
155
        self.change_status_to(DISCONNECTED)
bucyril's avatar
bucyril committed
156
157
158
159
160
        rospy.logerr("Connection to %s failed: %s" % (link_uri, msg))

    def _connection_lost(self, link_uri, msg):
        """Callback when disconnected after a connection has been made (i.e
        Crazyflie moves out of range)"""
161
        self.change_status_to(DISCONNECTED)
bucyril's avatar
bucyril committed
162
163
164
165
        rospy.logerr("Connection to %s lost: %s" % (link_uri, msg))

    def _disconnected(self, link_uri):
        """Callback when the Crazyflie is disconnected (called in all cases)"""
166
        self.change_status_to(DISCONNECTED)
bucyril's avatar
bucyril committed
167
        rospy.logwarn("Disconnected from %s" % link_uri)
168
169
170
        bag.close()
        rospy.loginfo("bag closed")

bucyril's avatar
bucyril committed
171

172
    def _send_to_commander(self,roll, pitch, yaw, thrust, cmd1, cmd2, cmd3, cmd4, mode):
bucyril's avatar
bucyril committed
173
174
        pk = CRTPPacket()
        pk.port = CRTPPort.COMMANDER
175
        pk.data = struct.pack('<fffHHHHHH', roll * RAD_TO_DEG, pitch * RAD_TO_DEG, yaw * RAD_TO_DEG, thrust, cmd1, cmd2, cmd3, cmd4, mode)
bucyril's avatar
bucyril committed
176
177
        self._cf.send_packet(pk)

178
    def crazyRadioCommandCallback(self, msg):
179
        """Callback to tell CrazyRadio to reconnect"""
180
        print "crazyRadio command received %s" % msg.data
181
        if msg.data == CMD_RECONNECT:            # reconnect, check _status first and then do whatever needs to be done
182
            print "entered reconnect"
183
184
            print "_status: %s" % self._status
            if self.get_status() == DISCONNECTED:
185
186
                print "entered disconnected"
                self.connect()
187

188
189
def controlCommandCallback(data):
    """Callback for controller actions"""
190
    #rospy.loginfo("controller callback : %s, %s, %s", data.roll, data.pitch, data.yaw)
bucyril's avatar
bucyril committed
191

192
    #cmd1..4 must not be 0, as crazyflie onboard controller resets!
193
    #pitch and yaw are inverted on crazyflie controller
194
    cf_client._send_to_commander(data.roll, -data.pitch, -data.yaw, 0, data.motorCmd1, data.motorCmd2, data.motorCmd3, data.motorCmd4, data.onboardControllerType)
195
196
197
198




bucyril's avatar
bucyril committed
199
200
201

if __name__ == '__main__':
    rospy.init_node('CrazyRadio', anonymous=True)
202
    # Initialize the low-level drivers (don't list the debug drivers)
bucyril's avatar
bucyril committed
203
204
    cflib.crtp.init_drivers(enable_debug_driver=False)

205
    #wait until address parameter is set by PPSClient
206
    while not rospy.has_param("~crazyFlieAddress"):
bucyril's avatar
bucyril committed
207
208
        time.sleep(0.05)

209
210
    radio_address = "radio://" + rospy.get_param("~crazyFlieAddress")
    rospy.loginfo("Crazyradio connecting to %s" % radio_address)
211

212
    #use this following two lines to connect without data from CentralManager
roangel's avatar
roangel committed
213
214
215
    # radio_address = "radio://0/72/2M"
    # rospy.loginfo("manual address loaded")

216
217
    global cfbattery_pub
    cfbattery_pub = rospy.Publisher('cfbattery', Float32, queue_size=10)
218

219
    global cf_client
220

221
    cf_client = PPSRadioClient(radio_address)
222
    rospy.Subscriber("PPSClient/crazyRadioCommand", Int32, cf_client.crazyRadioCommandCallback) # allows commands from scripts
223

224
    time.sleep(1.0)
225

226
    rospy.Subscriber("PPSClient/ControlCommand", ControlCommand, controlCommandCallback)
227

228
229
    rospy.spin()
    rospy.loginfo("Turning off crazyflie")
230

231
232
233
    cf_client._send_to_commander(0, 0, 0, 0, 0, 0, 0, 0, CONTROLLER_MOTOR)
    #wait for client to send its commands
    time.sleep(1.0)
234

235
236
    cf_client._cf.close_link()
    rospy.loginfo("Link closed")