Show EOL distros: 

turtlebot3: turtlebot3_bringup | turtlebot3_description | turtlebot3_example | turtlebot3_navigation | turtlebot3_slam | turtlebot3_teleop

Package Summary

roslaunch scripts for starting the TurtleBot3

ROS Software Maintainer: ROBOTIS

ROBOTIS e-Manual

ROS API

turtlebot3_core

Subscribed Topics

cmd_vel (geometry_msgs/Twist)
  • Control the translational and rotational speed of the robot unit in m/s, rad/s
motor_power (std_msgs/Bool)
  • Dynamixel Torque On/Of
reset (std_msgs/Empty)
  • Reset Odometry and IMU Data. If you want to publish reset topic, type rostopic pub /reset std_msgs/Empty "{}"
sound (turtlebot3_msgs/Sound)
  • Output Beep Sound

Published Topics

battery_state (sensor_msgs/BatteryState)
  • Contains battery voltage and status
cmd_vel_rc100 (geometry_msgs/Twist)
  • Control the translational and rotational speed of the robot with RC100 controller, unit in m/s, rad/s
diagnostics (diagnostic_msgs/DiagnosticArray)
  • Contains self diagnostic information
imu (sensor_msgs/Imu)
  • Topic that includes the attitude of the robot based on the acceleration and gyro sensor
joint_states (sensor_msgs/JointState)
  • The state of a set of torque controlled joints
magnetic_field (sensor_msgs/MagneticField)
  • Measurement of the Magnetic Field vector at a specific location
odom (nav_msgs/Odometry)
  • Contains the Turtlebot3’s odometry information based on the encoder and IMU
sensor_state (turtlebot3_msgs/SensorState)
  • Topic that contains the values of the sensors mounted on the Turtlebot3. You need a turtlebot3_msgs
tf (tf2_msgs/tfMessage)
  • Contains the coordinate transformation such as base_footprint and odom
version_info (turtlebot3_msgs/VersionInfo)
  • Contains the Turtlebot3 hardware, firmware,and software information. You need a turtlebot3_msgs

Parameters

~baud (int, default: 115200)
  • This is baud rate for serial communication
~port (string, default: /dev/ttyACM0)
  • Name of serial port

turtlebot3_diagnostics

Subscribed Topics

imu (sensor_msgs/Imu)
  • Topic that includes the attitude of the robot based on the acceleration and gyro sensor
scan (sensor_msgs/LaserScan)
  • Topic that confirms the scan values of the LiDAR mounted on the Turtlebot3
sensor_state (turtlebot3_msgs/SensorState)
  • Topic that contains the values of the sensors mounted on the Turtlebot3. You need a turtlebot3_msgs
version_info (turtlebot3_msgs/VersionInfo)
  • Contains the Turtlebot3 hardware, firmware,and software information. You need a turtlebot3_msgs

Published Topics

diagnostics (diagnostic_msgs/DiagnosticArray)
  • Contains self diagnostic information

turtlebot3_lds

Published Topics

rpms (std_msgs/Uint16)
  • LDS rotation speed.
scan (sensor_msgs/LaserScan)
  • Topic that confirms the scan values of the LiDAR mounted on the Turtlebot3

Parameters

~frame_id (string, default: base_scan)
  • Set up coordinate of the LDS
~port (string, default: /dev/ttyUSB0)
  • Name of serial port

Wiki: turtlebot3_bringup (last edited 2019-10-25 15:21:25 by esteve)