Linux joystick.
More...
Linux joystick.
The linuxjoystick driver reads data from a standard Linux joystick and provides the data via the joystick interface. This driver can also control a position2d device by converting joystick positions to velocity commands.
- Compile-time dependencies
- Provides
- joystick : joystick data
- position2d : joystick data represented as 2-D position data. Raw X-axis, Y-axis and Yaw-axis values are reported as pos[0], pos[1] and pos[3] in the position packet (all other fields are zero).
- Requires
- position2d : if present, joystick positions will be interpreted as velocities and sent as commands to this position2d device. See also max_speed, and deadman_button options below.
- gripper : if present, joystick buttons will be used to control given gripper (open, close, store, retrieve, stop).
- Configuration requests
- Configuration file options
- port (string)
- Default: "/dev/js0"
- The joystick to be used.
- axes (integer tuple)
- Default: [1 2 0]
- Which joystick axes to call the "X" , "Y" and "Yaw" axes, respectively.
- axes_maxima (integer tuple)
- Default: [32767 32767 32767]
- Maximum absolute values attainable on the X, Y and Yaw axes, respectively.
- axes_minima (integer tuple)
- Default: [0 0 0]
- Minimum values on the X and Yaw axes, respectively. Anything smaller in absolute value than this limit will be reported as zero. Useful for implementing a dead zone on a touchy joystick.
- deadman_button (integer)
- Default: -1
- When controlling a position2d device, if deadman_button is >= 0, this joystick button must be depressed for commands to be sent to that device.
- max_speed (float tupple, m / sec or angle / sec)
- Default: [0.5 0.5 30]
- The maximum absolute X and Y translational and rotational velocities to be used when commanding a position device. (Y is only revelant for holonomous robot)
- scale_pos (float tuple)
- Default: [1.0 1.0 1.0]
- Position2d readings scale
- timeout (float)
- Default: 5.0
- Time (in seconds) since receiving a new joystick event after which the underlying position device will be stopped, for safety. Set to 0.0 for no timeout.
- Notes:
- Joysticks use X for side-to-side and Y for forward-back, also their axes are backwards with respect to intuitive driving controls.
- This driver does not swap any axis, you have to handle this in the configuration file options via "axes". However the defaults values should suit your needs.
- This driver reverse the axes so that the joystick respect the intuitive driving controls.
- The Y axis is only revelant for holonomous platform (like the WizBot).
- Examples
Basic configuration
driver
(
name "linuxjoystick"
provides ["joystick:0"]
port "/dev/js0"
)
Provide a position2d interface, instead of a joystick interface.
driver
(
name "linuxjoystick"
provides ["position2d:0"]
port "/dev/js0"
scale_pos [ 0.0001 0.0001 0.0001 ]
)
Controlling a Pioneer, plus remapping joystick axes and setting various limits.
driver
(
name "p2os"
provides ["odometry::position:0"]
port "/dev/usb/tts/0"
)
# 1 m/sec max linear velocity
# 30 deg/sec max angular velocity
# Axis 4 is X
# Axis 3 is Yaw
# Y is not used here
driver
(
name "linuxjoystick"
provides ["joystick:0"]
requires ["odometry::position:0"]
max_speed [1 0 30]
axes [4 -1 3]
axes_minima [5000 0 5000]
port "/dev/js0"
alwayson 1
)
Controlling a WizBot in Gazebo, plus remapping joystick axes.
driver
(
name "gazebo"
provides ["simulation:0"]
plugin "libgazeboplugin"
server_id "default"
)
driver
(
name "gazebo"
provides ["position2d:0"]
gz_id "position_iface_0"
)
# 0.5 m/sec max linear velocity
# 120 deg/sec max angular velocity
# Axis 1 is X
# Axis 2 is Y
# Axis 0 is Yaw
driver
(
name "linuxjoystick"
provides ["joystick:0"]
requires ["position2d:0"]
max_speed [0.5 0.5 120]
axes [1 2 0]
port "/dev/js0"
alwayson 1
)
- Todo:
- Add support for continuously sending commands, which might be needed for position devices that use watchdog timers.
- Author:
- Andrew Howard, Brian Gerkey, Paul Osmialowski