ROS-Thymio: thymio_driver reference
Executable
thymio_driver
Parameters
axis_length
- Type
float
- Default
0.0915
ground.threshold
- Type
float]
- Default
200
left_wheel_joint
- Type
string
- Default
"left_wheel_joint"
right_wheel_joint
- Type
string
- Default
"right_wheel_joint"
odom_frame
- Type
string
- Default
"odom"
odom_max_rate
- Type
float
- Default
-1
robot_frame
- Type
string
- Default
"base_link"
tf_prefix
- Type
string
- Default
""
Publishers
Internal asebaros
topics of type Event
/aseba/events/enable_comm: asebaros_msgs/msg/Event
/aseba/events/play_sound: asebaros_msgs/msg/Event
/aseba/events/play_system_sound: asebaros_msgs/msg/Event
/aseba/events/set_comm_payload: asebaros_msgs/msg/Event
/aseba/events/set_led: asebaros_msgs/msg/Event
/aseba/events/set_led_bottom_left: asebaros_msgs/msg/Event
/aseba/events/set_led_bottom_right: asebaros_msgs/msg/Event
/aseba/events/set_led_gesture: asebaros_msgs/msg/Event
/aseba/events/set_led_top: asebaros_msgs/msg/Event
/aseba/events/set_sound_threshold: asebaros_msgs/msg/Event
/aseba/events/set_speed: asebaros_msgs/msg/Event
/aseba/events/shutdown: asebaros_msgs/msg/Event
Proximity Communication Received
- Topic
comm/rx
- Type
Ground Sensors
- Topic
ground/{left,right}
- Type
sensor_msgs/msg/Range
IMU
- Topic
imu
- Type
sensor_msgs/msg/Imu
Joint States
- Topic
joint_states
- Type
sensor_msgs/msg/JointState
Odometry
- Topic
odom
- Type
nav_msgs/msg/Odometry
Proximity Sensors
- Topic
proximity/{left,center_left,center,center_right,right,rear_left,rear_right}
- Type
sensor_msgs/msg/Range
Proximity Sensors Scan
- Topic
proximity/laser
- Type
sensor_msgs/msg/LaserScan
Remote Controller
- Topic
remote
- Type
std_msgs/msg/Int8
Sound
- Topic
sound
- Type
std_msgs/msg/Float32
Tap
- Topic
tap
- Type
std_msgs/msg/Empty
Temperature
- Topic
temperature
- Type
sensor_msgs/msg/Temperature
Subscribers
Internal asebaros
topics of type Event
aseba/events/accelerometer
aseba/events/button_backward: asebaros_msgs/msg/Event
aseba/events/button_center: asebaros_msgs/msg/Event
aseba/events/button_forward: asebaros_msgs/msg/Event
aseba/events/button_left: asebaros_msgs/msg/Event
aseba/events/button_right: asebaros_msgs/msg/Event
aseba/events/buttons: asebaros_msgs/msg/Event
aseba/events/comm: asebaros_msgs/msg/Event
aseba/events/ground: asebaros_msgs/msg/Event
aseba/events/odometry: asebaros_msgs/msg/Event
aseba/events/proximity: asebaros_msgs/msg/Event
aseba/events/remote: asebaros_msgs/msg/Event
aseba/events/sound: asebaros_msgs/msg/Event
aseba/events/tap: asebaros_msgs/msg/Event
aseba/events/temperature: asebaros_msgs/msg/Event
Alarm
- Topic
alarm
- Type
std_msgs/msg/Bool
Velocity command
- Topic
cmd_vel
- Type
geometry_msgs/msg/Twist
Proximity Communication Enable
- Topic
comm/enable
- Type
std_msgs/msg/Bool
Proximity Communication Transmit
- Topic
comm/tx
- Type
std_msgs/msg/Int16
LED
- Topic
led
- Type
thymio_msgs/msg/Led
Body LED
- Topic
led/body/{bottom_left,bottom_right,top}
- Type
std_msgs/msg/ColorRGBA
LED Gestures
- Topic
led/gesture
- Type
thymio_msgs/msg/LedGesture
- Topic
led/gesture/alive
- Type
std_msgs/msg/Empty
- Topic
led/gesture/blink
- Type
std_msgs/msg/Float32
- Topic
led/gesture/circle
- Type
std_msgs/msg/Float32
- Topic
led/gesture/kit
- Type
std_msgs/msg/Float32
- Topic
led/gesture/off
- Type
std_msgs/msg/Empty
Play Sound
- Topic
sound/play
- Type
Play System Sound
- Topic
sound/play/system
- Type
Set sound threshold
- Topic
sound_threshold
- Type
std_msgs/msg/Float32
Services
Ready
- Service
is_ready
- Type
std_srvs/srv/Empty
multi_thymio_driver
Parameters
All parameters of thymio_driver
launch_model
- Type
string
- Default
""
Subscribers
All subscribers of thymio_driver with a <node_namespace>
for each Thymio connected.
Internal asebaros
topic
- Topic
aseba/nodes
- Type
Publishers
All publishers of thymio_driver with a <node_namespace>
for each Thymio connected.
Launch files
main.launch
Launches the single- or multi- thymio driver and, if configured, includes model.launch[.py for ROS2].
Arguments
axis_length
- Type
float
- Default
0.0935
odom_max_rate
- Type
float
- Default
-1
single
- Type
boolean
- Default
True
name
- Type
string
- Default
""
simulation
- Type
boolean
- Default
False
simulation_has_reduced_api
- Type
boolean
- Default
True
calibration_file
- Type
string
- Default
"$HOME/.ros/thymio_calibration.yaml"
device
- Type
string
- Default
""
port
- Type
integer
- Default
44444
highest_acceptable_protocol_version
- Type
int
- Default
100
emit_motor
- Type
integer (binary)
- Default
1
emit_acc
- Type
integer (binary)
- Default
1
emit_ground_raw
- Type
integer (binary)
- Default
0
emit_proximity
- Type
integer (binary)
- Default
1
enable_prox_comm
- Type
integer (binary)
- Default
1
motor_deadband
- Type
integer (binary)
- Default
10
motor_period
- Type
integer
- Default
5
acc_period
- Type
integer
- Default
2