Describe create_robot here.
Package Summary
ROS driver for iRobot's Create 1 and 2, based on the libcreate C++ library
- Maintainer status: developed
- Maintainer: Jacob Perron <jacobmperron AT gmail DOT com>
- Author: Jacob Perron <jacobmperron AT gmail DOT com>
- License: BSD
- Source: git https://github.com/AutonomyLab/create_robot.git (branch: melodic)
Package Summary
ROS driver for iRobot's Create 1 and 2, based on the libcreate C++ library
- Maintainer status: developed
- Maintainer: Jacob Perron <jacobmperron AT gmail DOT com>
- Author: Jacob Perron <jacobmperron AT gmail DOT com>
- License: BSD
- Source: git https://github.com/AutonomyLab/create_robot.git (branch: melodic)
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 serialSubscribed Topics
check_led (std_msgs/Bool)- Turn on/off Check Robot LED
- Drives the robots wheels according to forward velocity (m/s) and angular velocity (Rad/s)
- Turn on/off the blue Debris LED
- Activates the demo docking behaviour. Robot enters Passive mode removing control of the user
- Turn on/off the Dock LED
- 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 the 4 digit LEDs. Accepts 1 to 4 bytes, each representing an ASCII character to be displayed from left to right
- Turn on/off the Spot LED
- 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)
- The estimated charge of the robots battery (Ah)
- The estimated charge divided by the estimated capacity of the robots battery
- The charging state of the battery
- Current flowing through the robots battery (A). Positive current implies charging
- The temperature of the robots battery (degrees Celsius)
- The voltage of the robots battery (V)
- Bumper state, including light sensors
- A message is published to this topic when the Clean button is pressed
- A message is published to this topic when the Day button is pressed
- A message is published to this topic when the Dock button is pressed
- A message is published to this topic when the Hour button is pressed
- The IR character currently being read by the omnidirectional receiver. Vaue of 0 means no character is being received
- The states (position, velocity) of the drive wheel joints
- A message is published to this topic when the Minute button is pressed
- The current mode of the robot (See OI Spec for details)
- Odometry based on wheel encoders
- A message is published to this topic when the Spot button is pressed
- The transform from the odometry frame to the base frame. Only if the parameter publish_tf is set to true
- 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)
- Serial baud rate
- Serial port for connecting to robot
- 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
- Frequency of internal update loop. This affects the rate at which topics are published
- Odometry frame ID (used in odometry message header and TF publisher)
- Turn on/off transform publisher from odometry frame to base frame
- 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
odom → base_footprint- The current robot position in the odometry frame
Report a Bug
Use GitHub to report bugs or submit feature requests. [View active issues]