<<PackageHeader(turtlebot3_bringup)>> <<TOC(4)>> ''ROS Software Maintainer: [[http://wiki.ros.org/ROBOTIS|ROBOTIS]]'' == ROBOTIS e-Manual == * [[http://turtlebot3.robotis.com/|ROBOTIS e-Manual for TurtleBot3]] == ROS API == {{{ #!clearsilver CS/NodeAPI node.0 { name=turtlebot3_core pub{ 0{ name= battery_state type= sensor_msgs/BatteryState desc= Contains battery voltage and status } 1{ name= cmd_vel_rc100 type= geometry_msgs/Twist desc= Control the translational and rotational speed of the robot with [[http://emanual.robotis.com/docs/en/platform/turtlebot3/teleoperation/#rc100ROBOTIS| RC100]] controller, unit in m/s, rad/s } 2{ name= diagnostics type= diagnostic_msgs/DiagnosticArray desc= Contains self diagnostic information } 3{ name= imu type= sensor_msgs/Imu desc= Topic that includes the attitude of the robot based on the acceleration and gyro sensor } 4{ name= joint_states type= sensor_msgs/JointState desc= The state of a set of torque controlled joints } 5{ name= magnetic_field type= sensor_msgs/MagneticField desc= Measurement of the Magnetic Field vector at a specific location } 6{ name= odom type= nav_msgs/Odometry desc= Contains the Turtlebot3’s odometry information based on the encoder and IMU } 7{ name= sensor_state type= turtlebot3_msgs/SensorState desc= Topic that contains the values of the sensors mounted on the Turtlebot3. You need a [[http://wiki.ros.org/turtlebot3_msgs|turtlebot3_msgs]] } 8{ name= tf type= tf2_msgs/tfMessage desc= Contains the coordinate transformation such as base_footprint and odom } 9{ name= version_info type= turtlebot3_msgs/VersionInfo desc= Contains the Turtlebot3 hardware, firmware,and software information. You need a [[http://wiki.ros.org/turtlebot3_msgs|turtlebot3_msgs]] } } sub{ 0{ name= cmd_vel type= geometry_msgs/Twist desc= Control the translational and rotational speed of the robot unit in m/s, rad/s } 1{ name= motor_power type= std_msgs/Bool desc= Dynamixel Torque On/Of } 2{ name= reset type= std_msgs/Empty desc= Reset Odometry and IMU Data. If you want to publish '''reset''' topic, type '''rostopic pub /reset std_msgs/Empty "{}"''' } 3{ name= sound type= turtlebot3_msgs/Sound desc= Output Beep Sound } } param{ 0{ name= ~baud default= 115200 type= int desc= This is baud rate for serial communication } 1{ name= ~port default= /dev/ttyACM0 type= string desc= Name of serial port } } } }}} {{{ #!clearsilver CS/NodeAPI node.1 { name=turtlebot3_diagnostics pub{ 0{ name= diagnostics type= diagnostic_msgs/DiagnosticArray desc= Contains self diagnostic information } } sub{ 0{ name= imu type= sensor_msgs/Imu desc= Topic that includes the attitude of the robot based on the acceleration and gyro sensor } 1{ name= scan type= sensor_msgs/LaserScan desc= Topic that confirms the scan values of the [[http://emanual.robotis.com/docs/en/platform/turtlebot3/appendix_lds_01/#overview|LiDAR]] mounted on the Turtlebot3 } 2{ name= sensor_state type= turtlebot3_msgs/SensorState desc= Topic that contains the values of the sensors mounted on the Turtlebot3. You need a [[http://wiki.ros.org/turtlebot3_msgs|turtlebot3_msgs]] } 3{ name= version_info type= turtlebot3_msgs/VersionInfo desc= Contains the Turtlebot3 hardware, firmware,and software information. You need a [[http://wiki.ros.org/turtlebot3_msgs|turtlebot3_msgs]] } } } }}} {{{ #!clearsilver CS/NodeAPI node.2 { name=turtlebot3_lds pub{ 0{ name= rpms type= std_msgs/Uint16 desc= LDS rotation speed. } 1{ name= scan type= sensor_msgs/LaserScan desc= Topic that confirms the scan values of the [[http://emanual.robotis.com/docs/en/platform/turtlebot3/appendix_lds_01/#overview|LiDAR]] mounted on the Turtlebot3 } } param{ 0{ name= ~frame_id default= base_scan type= string desc= Set up coordinate of the LDS } 1{ name= ~port default= /dev/ttyUSB0 type= string desc= Name of serial port } } } }}}