Only released in EOL distros:  

kobuki: kobuki_arm | kobuki_auto_docking | kobuki_bumper2pc | kobuki_controller_tutorial | kobuki_driver | kobuki_ftdi | kobuki_keyop | kobuki_node | kobuki_safety_controller | kobuki_testsuite

Package Summary

ROS nodelet for Kobuki: ROS wrapper for the Kobuki driver.

  • Maintainer status: developed
  • Maintainer: Daniel Stonier <stonier AT yujinrobot DOT com>
  • Author: Daniel Stonier <stonier AT yujinrobot DOT com>, Younghun Ju <younghoon.ju AT yujinrobot DOT com>, Jorge Santos Simon <jorge AT yujinrobot DOT com>
  • License: BSD
  • Source: git https://github.com/yujinrobot/kobuki.git (branch: groovy-devel)
kobuki: kobuki_auto_docking | kobuki_bumper2pc | kobuki_controller_tutorial | kobuki_description | kobuki_keyop | kobuki_node | kobuki_random_walker | kobuki_safety_controller | kobuki_testsuite

Package Summary

ROS nodelet for Kobuki: ROS wrapper for the Kobuki driver.

New in groovy

Ros API

Kobuki Nodelet

Provides a control loop and exposes ros api for the kobuki_driver.

Subscribed Topics

~commands/motor_power (kobuki_msgs/MotorPower)
  • Turn on/off Kobuki's motors.
~commands/external_power (kobuki_msgs/ExternalPower)
  • Turn on/off Kobuki's external power sources.
~commands/reset_odometry (std_msgs/Empty)
  • Resets Kobuki odometry
~commands/sound (kobuki_msgs/Sound)
  • Sends a command for playing sounds.
~commands/led1 (kobuki_msgs/Led)
  • Sends a command for controlling the first programmable LED's color.
~commands/led2 (kobuki_msgs/Led)
  • Sends a command for controlling the second programmable LED's color.
~commands/digital_output (kobuki_msgs/DigitalOutput)
  • Sets values for the digital output ports.
~commands/velocity (geometry_msgs/Twist)
  • Sets the desired velocity of the robot.

Published Topics

odom (nav_msgs/Odometry)
  • The odometry of the robot based on the gyro and motor encoders.
diagnostics (diagnostic_msgs/DiagnosticArray)
  • The system diagnostic information published at 1Hz.
joint_states (sensor_msgs/JointState)
  • Updated state for wheel joints.
~events/button (kobuki_msgs/ButtonEvent)
  • Provides a button event, generated whenever a button is pressed or released.
~events/bumper (kobuki_msgs/BumperEvent)
  • Provides a bumper event, generated whenever a bumper is pressed or released.
~events/cliff (kobuki_msgs/CliffEvent)
  • Provides a cliff sensor event, generated whenever the robot approaches or moves away from a cliff.
~events/wheel_drop (kobuki_msgs/WheelDropEvent)
  • Provides a wheel drop event, generated whenever a wheel is dropped (robot fell or was raised) or raised (normal condition).
~events/power_system (kobuki_msgs/PowerSystemEvent)
  • Power system events, generated by important changes in the power system, like plug/unplug to charger, low/critical battery levels or battery charge completed.
~events/robot_state (kobuki_msgs/RobotStateEvent)
  • Provides a robot state event, generated whenever the robot gets online/offline.
~events/digital_input (kobuki_msgs/DigitalInputEvent)
  • Generated whenever digital input ports state changes.
~sensors/imu_data (sensor_msgs/Imu)
  • Gyroscope data messages. Provides both heading and angular velocity.
~sensors/imu_data_raw (sensor_msgs/Imu)
  • Raw data of 3D Gyroscope. Provides angular velocity of x-, y-, and z-axis. But not provides linear accelerations and orientation.
~sensors/dock_ir (kobuki_msgs/DockInfraRed)
  • Docking base ir sensors messages. Generated on the proximity of the docking base to assist the automatic docking.
~sensors/core (kobuki_msgs/SensorState)
  • Kobuki sensor data messages. This topic provides detailed information about the entire state package that is transmitted at 50Hz from the robot.
~version_info (kobuki_msgs/VersionInfo)
  • Contains unique device id, version info and available features for the kobuki platform. Useful for compatibility checking and introspection.

Parameters

~device_port (string, default: /dev/kobuki)
  • Linux USB device port; robots are factory-flashed with '/dev/kobuki', but this name can be easily changed (check kobuki_ftdi package for details).
~wheel_left_joint_name (string, default: wheel_left_joint)
  • Published name of left wheel joint state.
~wheel_right_joint_name (string, default: wheel_right_joint)
  • Published name of right wheel joint state.
~battery_capacity (double, default: 16.5)
  • Battery voltage at full charge.
~battery_low (double, default: 13.5)
  • Battery voltage at first warning (15%).
~battery_dangerous (double, default: 13.2)
  • Battery voltage at critical level (5%).
~cmd_vel_timeout (double, default: 0.6)
  • If a new command isn't received within this many seconds, the base is stopped.
~publish_tf (bool, default: False)
  • Causes node to publish TF from odom to base_link. In most cases this transform is published by robot_pose_ekf; use only when this package is not used.
~odom_frame (string, default: odom)
  • Name of the odometry TF frame.
~base_frame (string, default: base_footprint)
  • Name of the base TF frame.
~acceleration_limiter (bool, default: false)
  • Enable if you want the kobuki to do minimal acceleration smooth to velocity command inputs. Alternatively use a proper velocity smoother as a nodelet alongside the kobuki nodelet.

Report a Bug

Use github to report bugs or request features.

Ros API

Kobuki Nodelet

Provides a control loop and exposes ros api for the kobuki_driver.

Subscribed Topics

~commands/motor_power (kobuki_msgs/MotorPower)
  • Turn on/off Kobuki's motors.
~commands/external_power (kobuki_msgs/ExternalPower)
  • Turn on/off Kobuki's external power sources.
~commands/reset_odometry (std_msgs/Empty)
  • Resets Kobuki odometry
~commands/sound (kobuki_msgs/Sound)
  • Sends a command for playing sounds.
~commands/led1 (kobuki_msgs/Led)
  • Sends a command for controlling the first programmable LED's color.
~commands/led2 (kobuki_msgs/Led)
  • Sends a command for controlling the second programmable LED's color.
~commands/digital_output (kobuki_msgs/DigitalOutput)
  • Sets values for the digital output ports.
~commands/velocity (geometry_msgs/Twist)
  • Sets the desired velocity of the robot.
~commands/controller_info (kobuki_msgs/ControllerInfo)

Published Topics

odom (nav_msgs/Odometry)
  • The odometry of the robot based on the gyro and motor encoders.
diagnostics (diagnostic_msgs/DiagnosticArray)
  • The system diagnostic information published at 1Hz.
joint_states (sensor_msgs/JointState)
  • Updated state for wheel joints.
~events/button (kobuki_msgs/ButtonEvent)
  • Provides a button event, generated whenever a button is pressed or released.
~events/bumper (kobuki_msgs/BumperEvent)
  • Provides a bumper event, generated whenever a bumper is pressed or released.
~events/cliff (kobuki_msgs/CliffEvent)
  • Provides a cliff sensor event, generated whenever the robot approaches or moves away from a cliff.
~events/wheel_drop (kobuki_msgs/WheelDropEvent)
  • Provides a wheel drop event, generated whenever a wheel is dropped (robot fell or was raised) or raised (normal condition).
~events/power_system (kobuki_msgs/PowerSystemEvent)
  • Power system events, generated by important changes in the power system, like plug/unplug to charger, low/critical battery levels or battery charge completed.
~events/robot_state (kobuki_msgs/RobotStateEvent)
  • Provides a robot state event, generated whenever the robot gets online/offline.
~events/digital_input (kobuki_msgs/DigitalInputEvent)
  • Generated whenever digital input ports state changes.
~sensors/imu_data (sensor_msgs/Imu)
  • Gyroscope data messages. Provides both heading and angular velocity.
~sensors/imu_data_raw (sensor_msgs/Imu)
  • Raw data of 3D Gyroscope. Provides angular velocity of x-, y-, and z-axis. But not provides linear accelerations and orientation.
~sensors/dock_ir (kobuki_msgs/DockInfraRed)
  • Docking base ir sensors messages. Generated on the proximity of the docking base to assist the automatic docking.
~sensors/core (kobuki_msgs/SensorState)
  • Kobuki sensor data messages. This topic provides detailed information about the entire state package that is transmitted at 50Hz from the robot.
~version_info (kobuki_msgs/VersionInfo)
  • Contains unique device id, version info and available features for the kobuki platform. Useful for compatibility checking and introspection.
~controller_info (kobuki_msgs/ControllerInfo)
  • Contains PID gains for the wheel velocity controller of the robot. (Default PID Gain: Kp=100, Ki=0.1, Kd=2) It requires firmware version 1.2.0 and above, refer to the kobuki how-tos for upgrade instructions
~debug/raw_data_stream (std_msgs/String)
  • Raw bytestreams received from the robot.
~debug/raw_data_command (std_msgs/String)
  • Raw bytestreams sent to the robot.
~debug/raw_control_command (std_msgs/Int16MultiArray)
  • Contains two velocity commands that received from the kobuki_node and sent to the robot.

Parameters

~device_port (string, default: /dev/kobuki)
  • Linux USB device port; robots are factory-flashed with '/dev/kobuki', but this name can be easily changed (check kobuki_ftdi package for details).
~wheel_left_joint_name (string, default: wheel_left_joint)
  • Published name of left wheel joint state.
~wheel_right_joint_name (string, default: wheel_right_joint)
  • Published name of right wheel joint state.
~battery_capacity (double, default: 16.5)
  • Battery voltage at full charge.
~battery_low (double, default: 13.5)
  • Battery voltage at first warning (15%).
~battery_dangerous (double, default: 13.2)
  • Battery voltage at critical level (5%).
~cmd_vel_timeout (double, default: 0.6)
  • If a new command isn't received within this many seconds, the base is stopped.
~publish_tf (bool, default: False)
  • Causes node to publish TF from odom to base_link. In most cases this transform is published by robot_pose_ekf; use only when this package is not used.
~use_imu_heading (bool, default: True)
  • Use imu readings for heading instead of encoders. That's the normal operation mode for Kobuki, as its gyro is very reliable. Disable only if you want to fuse encoders and imu readings in a more sophisticated way, for example filtering and fussing with robot_pose_ekf.
~odom_frame (string, default: odom)
  • Name of the odometry TF frame.
~base_frame (string, default: base_footprint)
  • Name of the base TF frame.
~acceleration_limiter (bool, default: false)
  • Enable if you want the kobuki to do minimal acceleration smooth to velocity command inputs. Alternatively use a proper velocity smoother as a nodelet alongside the kobuki nodelet.

Report a Bug

Use github to report bugs or request features.

Wiki: kobuki_node (last edited 2017-02-23 22:43:53 by WilliamWoodall)