File: xbot_msgs/CoreSensor.msg
Raw Message Definition
# Xbot Core Sensor Data Messages
###### MESSAGE ######
Header header
###################
# Timestamp and battery voltage
###################
uint32 time_stamp # milliseconds starting when turning on Xbot (max. 65536, then starts from 0 again)
uint16 left_encoder
uint16 right_encoder
bool ischarging
uint8 battery_percent
uint16 front_echo
uint16 rear_echo
uint16 front_infrared
uint16 rear_infrared
bool motor_enabled
float32 left_motor_current
float32 right_motor_current
uint16 error_state
uint8 version
Compact Message Definition
std_msgs/Header header
uint32 time_stamp
uint16 left_encoder
uint16 right_encoder
bool ischarging
uint8 battery_percent
uint16 front_echo
uint16 rear_echo
uint16 front_infrared
uint16 rear_infrared
bool motor_enabled
float32 left_motor_current
float32 right_motor_current
uint16 error_state
uint8 version