This node is the interface between the hardware and the high level robot functions. This includes:
There are three micro controller boards in the robot:
The mobile base driver communicate with these via two high speed UARTS, /dev/ttyS1 and /dev/ttyS2.
This board controls the drive motors and the head pan motor. It also gathers input from these sensors: bump, wheel drop, battery power and dock IR receiver.
The status LED (on the power button) is controlled by this board.
The system power is controlled by this board.
Depth sensor reset is controlled by this board.
This board controls the head tilt and eyelids motors. It also gathers data from the cap touch sensor.
This board controls the 15 LEDs in the chest board.
The firmware must be loaded on the two controller boards. The depth sensor needs to be operating and providing depth scans.
/commands/chest_leds mobile_base_driver::ChestLeds
Controls the color of the chest LEDs
/mobile_base/imusensor_msgs::Imu Data from the IMU device (BNO055)
/mobile_base/safety_statusmobile_base_driver::SafetyStatus Safety status from sensors that prevent the robot from hurting itself.
/mobile_base/sensorsmobile_base_driver::Sensors Contains the current state of most of the sensors in the robot.
/mobile_base/touchmobile_base_driver::Touch The cap touch sensor
/mobile_base/powermobile_base_driver::Power The power state, ie., battery charge, dock status.
/mobile_base/stallmobile_base_driver::Stall Motor stall state.
/mobile_base/telescopemobile_base_driver::Telescope IR receivers that detect the dock, one in front and one in the back.
/mobile_base/rear_cliffmobile_base_driver::CliffArray The cliff sensors in the back of the robot. These are only active if the at least one of the drive wheels is being commanded backwards.
/mobile_base/diagnosticsdiagnostic_msgs::DiagnosticArray
/mobile_base/debug_logger`See ROS logging documentation/mobile_base/get_embedded_regsmobile_base_driver::GetEmbeddedRegs Get the value of the specified register
/mobile_base/set_embedded_regsmobile_base_driver::SetEmbeddedRegs Set the value of the specified register
/mobile_base/ir_filter`Unused/mobile_base/safety_clearmobile_base_driver::SafetyClear Clear the specified safety condition
/mobile_base/safety_controlmobile_base_driver::SafetyOverride Override the safety controller for the specified conditions
/mobile_base/pwr_btn_ledmobile_base_driver::PwrBtnLed Set the color of the power button LED
/mobile_base/depth_sensor_resetstd_srvs::Empty Holds the depth sensor in reset for 200ms
/mobile_base/arm_shutdownstd_srvs::Empty Start the shutdown process
/mobile_base/cancel_shutdownstd_srvs::Empty Cancel the shutdown process
/mobile_base/home_head_panstd_srvs::Trigger Causes the pan motor to re-home to the homing sensor
/mobile_base/home_head_tiltstd_srvs::Trigger Causes the tilt motor to re-home to the homing sensor
/mobile_base/home_eyelidsstd_srvs::Trigger Causes the eyelids motor to re-home to the homing sensor
mobile_base/uart1
/dev/ttyS1, used to communicate with the body board
mobile_base/uart2
/dev/rrtS2, used to communicate with the head board and chest light
mobile_base/timing/imu
The polling rate for reading data from the IMU
mobile_base/timing/publish
The ros topic publish rate
mobile_base/timing/ros_control_rate
The main control loop processing rate
mobile_base/timing/error_check_rate
The rate the control board are polled for errors
mobile_base/timing/loop_check_rate_hz
The rate the control boards are polled to check their loop run times
mobile_base/timing/status_update_rate_hz
The rate the power status is monitored to control the status LED on the power button
mobile_base/queue_size
Queue size used for ROS publishers
mobile_base.launch