Joystick Control
View Package on GitHubOverview
This package can be used to control the movements of any rover in the Interbotix X-Series LoCoBot Family using a SONY PS3 or PS4 controller via Bluetooth. In this demo, the 'arm' (if equipped) and 'pan/tilt' servos work in 'position' control mode, the gripper operates in 'PWM' mode, and the base operates in 'velocity' control mode. Refer to the joystick button map below to see how to operate the robot. Specifically, some of the joystick controls manipulate individual joints while others are used to perform 'inverse kinematics' on all the joints to get the end-effector of the robot (defined at 'ee_gripper_link') to move as if it's in Cartesian space. This is done using the modern_robotics code library offered by Northwestern University.
Structure
As shown above, the interbotix_xslocobot_joy package builds on top of the interbotix_xslocobot_control package. To get familiar with the nodes in the interbotix_xslocobot_control package, please look at its README. The other nodes are described below:
- joy - a ROS driver for a generic Linux joystick; it reads data from a SONY PS3 or PS4
controller joystick over Bluetooth and publishes sensor_msgs/Joy messages to the
/<robot_name>/commands/joy_raw
topic - xslocobot_joy - responsible for reading in raw sensor_msgs/Joy messages from the
/<robot_name>/commands/joy_raw
topic and converting them into LocobotJoy messages; this makes the code more readable and allows users to remap buttons very easily later. The new messages are then published on the/<robot_name>/commands/joy_processed topic
. - xslocobot_robot - responsible for reading in LocobotJoy messages from the
/<robot_name>/commands/joy_processed
topic and publishing joint, gripper, and pan/tilt commands to the xs_sdk node; while the 'waist' joint is directly controlled via the PS3/PS4 joystick, other buttons allow position-ik to be performed using all the arm joints. It also publishes velocity commands to the mobile base.
Usage
After pairing your Bluetooth joystick controller using the Pairing Your Controller Guide, type the following in a terminal (let's say to control the locobot_wx200 robot with no lidar):
$ ros2 launch interbotix_xslocobot_joy xslocobot_joy.launch.py robot_model:=locobot_wx200
A red error message might appear in the screen saying Couldn't open joystick force feedback!
.
This is normal and will not affect the joystick operation. To further customize the launch file at
run-time, look at the table below:
Argument | Description | Default | Choices |
---|---|---|---|
robot_model | model type of the Interbotix LoCoBot such as locobot_base or locobot_wx250s . |
locobot_base , locobot_px100 , locobot_wx200 , locobot_wx250s |
|
robot_name | name of the robot (could be anything but defaults to locobot ). |
locobot |
|
arm_model | the Interbotix Arm model on the LoCoBot; this should never be set manually but rather left to its default value. | PythonExpr('"mobile_" + "' + LaunchConfig(robot_model ) + '".split("_")[1]') |
|
use_rviz | launches RViz if set to true . |
true |
true , false |
rviz_frame | fixed frame in RViz; this should be changed to map or odom if mapping or using local odometry respectively; base_footprint otherwise. |
LaunchConfig(robot_name ) + '/base_footprint' |
|
use_base | if true , the base ROS nodes are launched. |
true |
true , false |
use_lidar | if true , the RPLidar node is launched. |
false |
true , false |
use_camera | if true , the RealSense camera nodes are launched. |
false |
true , false |
mode_configs | the file path to the 'mode config' YAML file. | PythonExpr('"' + LocalVar('FindPackageShare(pkg= interbotix_xslocobot_joy ) + 'config' + 'modes_base.yaml'') + '" if "' + LaunchConfig(robot_model ) + '" == "locobot_base" else "' + LocalVar('FindPackageShare(pkg= interbotix_xslocobot_joy ) + 'config' + 'modes_all.yaml'') + '"') |
|
threshold | value from 0 to 1 defining joystick sensitivity; a larger number means the joystick should be less sensitive. | '0.75' | |
controller | type of controller. | ps4 |
ps4 , ps3 |
launch_driver | true if xslocobot_control should be launched - set to false if you would like to run your own version of this file separately. |
true |
true , false |
xs_driver_logging_level | set the logging level of the X-Series Driver. | INFO |
DEBUG , INFO , WARN , ERROR , FATAL |
use_sim | if true , the DYNAMIXEL simulator node is run; use RViz to visualize the robot's motion; if false , the real DYNAMIXEL driver node is run. |
false |
true , false |
base_type | the base type of the LoCoBot. | EnvVar(INTERBOTIX_XSLOCOBOT_BASE_TYPE ) |
kobuki , create3 |
use_gripper | if true , the default gripper is included in the robot_description ; if false , it is left out; set to false if not using the default gripper. |
true |
true , false |
show_ar_tag | if true , the AR tag mount is included in the robot_description ; if false , it is left out; set to true if using the AR tag mount in your project. |
true |
true , false |
show_gripper_bar | if true , the gripper_bar link is included in the robot_description ; if false , the gripper_bar and finger links are not loaded. Set to false if you have a custom gripper attachment. |
true |
true , false |
show_gripper_fingers | if true , the gripper fingers are included in the robot_description ; if false , the gripper finger links are not loaded. Set to false if you have custom gripper fingers. |
true |
true , false |
external_urdf_loc | the file path to the custom urdf.xacro file that you would like to include in the Interbotix robot's urdf.xacro file. | '' | |
hardware_type | configures the robot_description to use the actual hardware, fake hardware, or hardware simulated in Gazebo. |
actual |
actual , fake , gz_classic |
robot_description | URDF of the robot; this is typically generated by the xacro command. | Command(FindExec(xacro ) + ' ' + LocalVar('FindPackageShare(pkg= interbotix_xslocobot_descriptions ) + 'urdf' + 'locobot.urdf.xacro'') + ' ' + 'arm_model:=' + LaunchConfig(arm_model ) + ' ' + 'robot_name:=' + LaunchConfig(robot_name ) + ' ' + 'base_model:=' + LaunchConfig(base_type ) + ' ' + 'robot_model:=' + LaunchConfig(robot_model ) + ' ' + 'use_gripper:=' + LaunchConfig(use_gripper ) + ' ' + 'show_ar_tag:=' + LaunchConfig(show_ar_tag ) + ' ' + 'show_gripper_bar:=' + LaunchConfig(show_gripper_bar ) + ' ' + 'show_gripper_fingers:=' + LaunchConfig(show_gripper_fingers ) + ' ' + 'use_lidar:=' + LaunchConfig(use_lidar ) + ' ' + 'external_urdf_loc:=' + LaunchConfig(external_urdf_loc ) + ' ' + 'hardware_type:=' + LaunchConfig(hardware_type ) + ' ') |
To understand how the joystick buttons map to controlling the robot, look at the diagram and table below:
Base Control Mode
Button | Action |
---|---|
Left Stick Up/Down | drive the mobile base forward/backward between 0.7 to -0.7 m/s |
R2 | rotate the mobile base clockwise between 0 and -3.14 rad/s |
L2 | rotate the mobile base counterclockwise between 0 and 3.14 rad/s |
Right Stick Up/Down | tilt the camera Up/Down |
Right Stick Left/Right | pan the camera Left/Right |
START/OPTIONS | move the pan/tilt servo to '0' radians |
Arm Control Mode
Button | Action |
---|---|
START/OPTIONS | move robot arm to its Home pose |
SELECT/SHARE | move robot arm to its Sleep pose |
R2 | rotate the 'waist' joint clockwise |
L2 | rotate the 'waist' joint counterclockwise |
Triangle | increase gripper pressure in 0.125 step increments (max is 1) |
X | decrease gripper pressure in 0.125 step increments (min is 0) |
O | open gripper |
Square | close gripper |
Right Stick Up/Down | increase/decrease pitch of the end-effector |
Right Stick Left/Right | increase/decrease roll of the end-effector |
R3 | reverses the Right Stick Left/Right control |
Left Stick Up/Down | move the end-effector (defined at 'ee_gripper_link') vertically in Cartesian space |
Left Stick Left/Right | move the end-effector (defined at 'ee_gripper_link') horizontally in Cartesian space |
L3 | reverses the Left Stick Left/Right control |
R1 | if the arm has 6dof, this moves the end-effector in a negative direction along its own 'y' axis |
L1 | if the arm has 6dof, this moves the end-effector in a positive direction along its own 'y' axis |
Both Modes
Button | Action |
---|---|
D-pad Up | increase the control loop rate in 1 Hz step increments (max of 40) |
D-pad Down | decrease the control loop rate in 1 Hz step increments (min of 10) |
D-pad Left | 'coarse' control - sets the control loop rate to a user-preset 'fast' rate |
D-pad Right | 'fine' control - sets the control loop rate to a user-preset 'slow' rate |
PS | shift to the other Control Mode |