The ouijabot is an omnidirectional ground robot platform designed for general experiments in the plane, including 2D SLAM, collaborative manipulation, and pursuit-evasion. The platform's holonomic dynamics allow it to be well-modeled with a single-integrator model, which make it ideal for a wide variety of planar control and navigation tasks.
The hardware consists of 4 DC motors, which drive omnidirectional wheels, and an embedded Linux computer (Raspberry Pi). This project aims to completely open source all software and hardware. All communication is performed using ROS.
Below are the features or capabilities of the ouijabot which are currently supported.
- Open-loop controller which seeks to track a desired robot velocity (combined linear and angular velocity).
- Closed-loop controller, which uses onboard current sensors to generate desired wrench (force and torque).
- Measures current supplied to each motor by the motor drivers.
- Measures current linear acceleration and angular velocity via onboard IMU.
- ROS node which generates and publishes body-frame velocity commands via joystick input.
- ROS node which generates and publishes body-frame force and torque commands via joystick input.
Below we provide general instructions for how to utilize the supported features detailed above. Please see the code for additional details. All nodes typically run in a namespace set by the user's $HOSTNAME
variable.
-
Onboard: run
roslaunch ouijabot velocity_control.launch
to start the velocity control node (velocity_control.py
). The node will subscribe to the topiccmd_vel
, which uses messages of typegeometry_msgs/Twist
.- Arguments:
cmdMode
: flag for desired throttle response of ouijabot. If set to"equal"
, command axes are decoupled; throttle commands in one axis always correspond to the same speed, regardless of other axis commands. If set to"max"
, then any command with l1-norm >= 1 is treated as "full speed"; at least one motor will run at max RPM. Allows for faster speeds overall of the ouijabot, but with less physical intuition behind commands.
- Arguments:
-
Offboard: to teleoperate ouijabot, run
roslaunch ouijabot_telop vel_telop.launch
to launch the velocity command node. The node will read joystick inputs and use them to generate velocity commands, which it publishes tocmd_vel
.- Arguments:
id
: index of ouijabot to be commanded. The node will remap the genericcmd_vel
topic to/ouijabot$(arg id)/cmd_vel
by default. Defaults to1
.velMax_l
: scaling parameter for linear velocity commands. Should range between0
and1
, with1
corresponding to max throttle available in hardware. Defaults to1.0
.velMax_a
: scaling parameter for angular velocity commands. Same behavior as linear velocity scaling; defaults to1.0
.
- Arguments:
-
Onboard: run
roslaunch ouijabot force_control.launch
to launch the force control node (force_control.py
). The node will subscribe to the topiccmd_wrench
which uses messages of typegeometry_msgs/Twist
. It uses onboard current sensors to run a closed-loop PID controller to generate the desired wrench.Note:
params.launch
must be run beforeforce_control.launch
; the PID parameters are set as ROS parameters in this file. This is typically done once, offboard, as part of robot setup. These parameters may easily be tuned by setting the ROS parameters manually. -
Offboard: run
roslaunch ouijabot params.launch
, once, to set force controller parameters. Then runroslaunch ouijabot_telop force_telop.launch
to teleoperate the ouijabot in force control mode. The node will read joystick inputs and use them to generate wrench commands, which it publishes tocmd_wrench
.- Arguments:
id
: index of ouijabot to be commanded. The node will remap the genericcmd_vel
topic to/ouijabot$(arg id)/cmd_vel
by default. Defaults to1
.force_scale
: scaling parameter for max force command, in Newtons. Defaults to100.0
.torque_scale
: scaling parameter for max torque command, in Newton-meters. Defaults to5.0
.
- Arguments:
-
Current sensors: run
roslaunch ouijabot current_read.launch
to run the current sensor nodecurrent_read.py
. The node reads the current sensors on the motor controllers and publishes the values to the topiccurrent
as a vector of floats.Note: *Do not run
current_read.py
at the same time asforce_control.py
; the force control node reads/publishes the current sensors as part of its control loop and the conflicting reads could cause timing errors. -
IMU: run
roslaunch ouijabot imu_read.launch
to run the IMU nodeimu_read.py
. The node will read measurements from the IMU over I2C and publish them to the topicimu
as messages of typesensor_msgs/Imu
.