Describe create_robot here.

create_robot: create_bringup | create_description | create_driver | create_msgs

Package Summary

ROS driver for iRobot's Create 1 and 2, based on the libcreate C++ library

create_robot: create_bringup | create_description | create_driver | create_msgs

Package Summary

ROS driver for iRobot's Create 1 and 2, based on the libcreate C++ library

Packages

  • create_bringup - Launch and configuration files for common accessories when working with Create/Roomba platforms.

  • create_description - URDF descriptions and meshes for Create and Roomba models.

  • create_driver - ROS driver iRobot Create and Roomba robots.

  • create_msgs - Common message definitions for interfacing with the driver.

Nodes

create_driver

Communicates and controls a Create or Roomba over serial

Subscribed Topics

check_led (std_msgs/Bool)
  • Turn on/off Check Robot LED
cmd_vel (geometry_msgs/Twist)
  • Drives the robots wheels according to forward velocity (m/s) and angular velocity (Rad/s)
debris_led (std_msgs/Bool)
  • Turn on/off the blue Debris LED
dock (std_msgs/Empty)
  • Activates the demo docking behaviour. Robot enters Passive mode removing control of the user
dock_led (std_msgs/Bool)
  • Turn on/off the Dock LED
power_led (std_msgs/UInt8MultiArray)
  • Set the Power LED color and intensity. Accepts 1 or 2 bytes in the form of an array. The first byte represents the color between green (0) and red (255) and the second (default: 255) represents the intensity
set_ascii (std_msgs/UInt8MultiArray)
  • Set the 4 digit LEDs. Accepts 1 to 4 bytes, each representing an ASCII character to be displayed from left to right
spot_led (std_msgs/Bool)
  • Turn on/off the Spot LED
undock (std_msgs/Empty)
  • Switches the robot to Full mode giving control back to the user

Published Topics

battery/capacity (std_msgs/Float32)
  • The estimated charge capacity of the robots battery (Ah)
battery/charge (std_msgs/Float32)
  • The estimated charge of the robots battery (Ah)
battery/charge_ratio (std_msgs/Float32)
  • The estimated charge divided by the estimated capacity of the robots battery
battery/charging_state (ca_msgs/ChargingState)
  • The charging state of the battery
battery/current (std_msgs/Float32)
  • Current flowing through the robots battery (A). Positive current implies charging
battery/temperature (std_msgs/Int16)
  • The temperature of the robots battery (degrees Celsius)
battery/voltage (std_msgs/Float32)
  • The voltage of the robots battery (V)
bumper (ca_msgs/Bumper)
  • Bumper state, including light sensors
clean_button (std_msgs/Empty)
  • A message is published to this topic when the Clean button is pressed
day_button (std_msgs/Empty)
  • A message is published to this topic when the Day button is pressed
dock_button (std_msgs/Empty)
  • A message is published to this topic when the Dock button is pressed
hour_button (std_msgs/Empty)
  • A message is published to this topic when the Hour button is pressed
ir_omni (std_msgs/UInt16)
  • The IR character currently being read by the omnidirectional receiver. Vaue of 0 means no character is being received
joint_states (sensor_msgs/JointState)
  • The states (position, velocity) of the drive wheel joints
minute_button (std_msgs/Empty)
  • A message is published to this topic when the Minute button is pressed
mode (ca_msgs/Mode)
  • The current mode of the robot (See OI Spec for details)
odom (nav_msgs/Odometry)
  • Odometry based on wheel encoders
spot_button (std_msgs/Empty)
  • A message is published to this topic when the Spot button is pressed
/tf (tf2_msgs/TFMessage)
  • The transform from the odometry frame to the base frame. Only if the parameter publish_tf is set to true
wheeldrop (std_msgs/Empty)
  • A message is published to this topic if a wheeldrop is detected

Parameters

~base_frame (string, default: base_footprint)
  • Robot's base frame ID (used in various message headers)
~baud (int, default: Inferred based on robot model)
  • Serial baud rate
~dev (string, default: /dev/ttyUSB0)
  • Serial port for connecting to robot
~latch_cmd_duration (double, default: 0.2)
  • Number of seconds without receiving a velocity command before the robot stops moving. Warning: If communication with the base is severed completely, it may latch the last command and can only be stopped by reconnecting and restarting the driver
~loop_hz (double, default: 10.0)
  • Frequency of internal update loop. This affects the rate at which topics are published
~odom_frame (string, default: odom)
  • Odometry frame ID (used in odometry message header and TF publisher)
~publish_tf (bool, default: true)
  • Turn on/off transform publisher from odometry frame to base frame
~robot_model (string, default: CREATE_2)
  • The model of robot being controlled (ROOMBA_400, CREATE_1, or CREATE_2). This determines the communication protocol used to interface with base

Provided tf Transforms

odombase_footprint
  • The current robot position in the odometry frame

Report a Bug

Use GitHub to report bugs or submit feature requests. [View active issues]

Wiki: create_robot (last edited 2022-10-04 16:29:49 by JacobPerron)