ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

ps3 controller lag

asked 2013-09-10 07:17:06 -0500

juicedatom gravatar image

Hello everyone, I am writing some code to do some basic bluetooth teleop control of a robot, and for some reason when I try to move forward for an extended period of time it does cuts out until the controller is updated. is this a timeout problem? If so how could I change the timeout?

#!/usr/bin/env python
#
# Simple Joystick Control Node
#  

import rospy
from geometry_msgs.msg  import Twist
from sensor_msgs.msg    import Joy
from actionlib_msgs.msg import GoalID

def joyCB(msg):
  rospy.logdebug("Joy Recieved: [Vx:%f, Wz:%f]"%(msg.axes[linear_axis], 
                                                 msg.axes[rotation_axis]))

  cmd_vel_msg = Twist()
  cmd_vel_msg.linear.x  = msg.axes[linear_axis]   * linear_scale  
  cmd_vel_msg.angular.z = msg.axes[rotation_axis] * rotation_scale
  cmd_vel_pub.publish(cmd_vel_msg)

  # PS3 Triangle Button (12) - abort navigation command
  if msg.buttons[12]:
    nav_abort_pub = rospy.Publisher("/Pioneer3AT/move_base/cancel", GoalID)
    abort_msg = GoalID()
    #abort_msg.stamp = rospy.Time.now()
    #abort_msg.id = ""
    nav_abort_pub.publish(abort_msg)


if __name__ == '__main__':
  rospy.init_node('teleop_joy')

  global cmd_vel_pub
  global linear_axis
  global linear_scale
  global rotation_axis
  global rotation_scale

  linear_axis    = rospy.get_param('linear_axis'   , 1)
  linear_scale   = rospy.get_param('linear_scale'  , 1.0)
  rotation_axis  = rospy.get_param('rotation_axis' , 2)
  rotation_scale = rospy.get_param('rotation_scale', 1.5)

  cmd_vel_pub = rospy.Publisher("cmd_vel", Twist)

  rospy.Subscriber("joy", Joy, joyCB)
  rospy.spin()
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2013-09-14 09:09:29 -0500

Dereck gravatar image

updated 2013-09-15 11:58:53 -0500

If you are using the mux that I provided as part of the pioneer3at package, your 'problem' lays there. Open it up and you will find some timeout values that you can bump up to something reasonable like 10 seconds.

In ROS-H, the ps3joy/joy driver was changed to only send out changes rather than a stream. This caused the mux to fail. In future version of the pioneer3at package I have switched to a different mux which is much better as it is configurable from a yaml file: cmd_vel_mux. I just need to get some time to test the update in the lab before I release it.

EDIT: Fix released, and in case you didn't already have link to my quick start guide: http://goo.gl/kQEyA

You'll have to close rqt_robot_steering to be able to use the ps3 controller for now, but at least it works. ;)

edit flag offensive delete link more
1

answered 2013-09-10 11:09:22 -0500

That sounds like you might be experiencing a feature of the joy node, not a bug. By default, it does not send out new commands when the joystick state is not changing (which is be the case if you press the stick forward all the way). Luckily, this behavior can be switched off via by setting the autorepeat_rate parameter as documented on the joy wiki page.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2013-09-10 07:17:06 -0500

Seen: 353 times

Last updated: Sep 15 '13