@@ -233,30 +233,28 @@ def _on_joy(self, msg):
233
233
Args:
234
234
msg(Joy): a joystick input message
235
235
"""
236
-
237
- self ._controls ['btnLeft' ] = (msg .buttons [0 ] == 1 )
236
+ self ._controls ['btnLeft' ] = (msg .buttons [2 ] == 1 )
238
237
self ._controls ['btnUp' ] = (msg .buttons [3 ] == 1 )
239
- self ._controls ['btnDown' ] = (msg .buttons [1 ] == 1 )
240
- self ._controls ['btnRight' ] = (msg .buttons [2 ] == 1 )
238
+ self ._controls ['btnDown' ] = (msg .buttons [0 ] == 1 )
239
+ self ._controls ['btnRight' ] = (msg .buttons [1 ] == 1 )
241
240
242
- self ._controls ['dPadUp' ] = (msg .axes [5 ] > 0.5 )
243
- self ._controls ['dPadDown' ] = (msg .axes [5 ] < - 0.5 )
244
- self ._controls ['dPadLeft' ] = (msg .axes [4 ] > 0.5 )
245
- self ._controls ['dPadRight' ] = (msg .axes [4 ] < - 0.5 )
241
+ self ._controls ['dPadUp' ] = (msg .axes [7 ] > 0.5 )
242
+ self ._controls ['dPadDown' ] = (msg .axes [7 ] < - 0.5 )
243
+ self ._controls ['dPadLeft' ] = (msg .axes [6 ] > 0.5 )
244
+ self ._controls ['dPadRight' ] = (msg .axes [6 ] < - 0.5 )
246
245
247
246
self ._controls ['leftStickHorz' ] = msg .axes [0 ]
248
247
self ._controls ['leftStickVert' ] = msg .axes [1 ]
249
- self ._controls ['rightStickHorz' ] = msg .axes [2 ]
250
- self ._controls ['rightStickVert' ] = msg .axes [3 ]
248
+ self ._controls ['rightStickHorz' ] = msg .axes [3 ]
249
+ self ._controls ['rightStickVert' ] = msg .axes [4 ]
251
250
252
251
self ._controls ['leftBumper' ] = (msg .buttons [4 ] == 1 )
253
252
self ._controls ['rightBumper' ] = (msg .buttons [5 ] == 1 )
254
- self ._controls ['leftTrigger' ] = (msg .buttons [6 ] == 1 )
255
- self ._controls ['rightTrigger' ] = (msg .buttons [7 ] == 1 )
256
-
257
- self ._controls ['function1' ] = (msg .buttons [8 ] == 1 )
258
- self ._controls ['function2' ] = (msg .buttons [9 ] == 1 )
253
+ self ._controls ['leftTrigger' ] = (msg .axes [2 ] < 0.0 )
254
+ self ._controls ['rightTrigger' ] = (msg .axes [5 ] < 0.0 )
259
255
256
+ self ._controls ['function1' ] = (msg .buttons [6 ] == 1 )
257
+ self ._controls ['function2' ] = (msg .buttons [7 ] == 1 )
260
258
261
259
class PS3Controller (Joystick ):
262
260
"""
0 commit comments