<<StackHeader(create_autonomy)>> == Packages == * [[ca_description]] - URDF descriptions and meshes for Create and Roomba models. * [[ca_driver]] - ROS driver iRobot Create and Roomba robots. * [[ca_msgs]] - Common message definitions for interfacing with the driver. * [[ca_tools]] - Collection of tools for working with the robots. == Nodes == {{{ #!clearsilver CS/NodeAPI name = ca_driver desc = Communicates and controls a Create or Roomba over serial sub { 0.name = check_led 0.type = std_msgs/Bool 0.desc = Turn on/off ''Check Robot'' LED 1.name = cmd_vel 1.type = geometry_msgs/Twist 1.desc = Drives the robots wheels according to forward velocity (m/s) and angular velocity (Rad/s) 2.name = debris_led 2.type = std_msgs/Bool 2.desc = Turn on/off the blue ''Debris'' LED 3.name = dock 3.type = std_msgs/Empty 3.desc = Activates the demo docking behaviour. Robot enters '''Passive''' mode removing control of the user 4.name = dock_led 4.type = std_msgs/Bool 4.desc = Turn on/off the ''Dock'' LED 5.name = power_led 5.type = std_msgs/UInt8MultiArray 5.desc = 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 6.name = set_ascii 6.type = std_msgs/UInt8MultiArray 6.desc = Set the 4 digit LEDs. Accepts 1 to 4 bytes, each representing an ASCII character to be displayed from left to right 7.name = spot_led 7.type = std_msgs/Bool 7.desc = Turn on/off the ''Spot'' LED 8.name = undock 8.type = std_msgs/Empty 8.desc = Switches the robot to ''Full'' mode giving control back to the user } pub { 0.name = battery/capacity 0.type = std_msgs/Float32 0.desc = The estimated charge capacity of the robots battery (Ah) 1.name = battery/charge 1.type = std_msgs/Float32 1.desc = The estimated charge of the robots battery (Ah) 2.name = battery/charge_ratio 2.type = std_msgs/Float32 2.desc = The estimated charge divided by the estimated capacity of the robots battery 3.name = battery/charging_state 3.type = ca_msgs/ChargingState 3.desc = The charging state of the battery 4.name = battery/current 4.type = std_msgs/Float32 4.desc = Current flowing through the robots battery (A). Positive current implies charging 5.name = battery/temperature 5.type = std_msgs/Int16 5.desc = The temperature of the robots battery (degrees Celsius) 6.name = battery/voltage 6.type = std_msgs/Float32 6.desc = The voltage of the robots battery (V) 7.name = bumper 7.type = ca_msgs/Bumper 7.desc = Bumper state, including light sensors 8.name = clean_button 8.type = std_msgs/Empty 8.desc = A message is published to this topic when the ''Clean'' button is pressed 9.name = day_button 9.type = std_msgs/Empty 9.desc = A message is published to this topic when the ''Day'' button is pressed 10.name = dock_button 10.type = std_msgs/Empty 10.desc = A message is published to this topic when the ''Dock'' button is pressed 11.name = hour_button 11.type = std_msgs/Empty 11.desc = A message is published to this topic when the ''Hour'' button is pressed 12.name = ir_omni 12.type = std_msgs/UInt16 12.desc = The IR character currently being read by the omnidirectional receiver. Vaue of 0 means no character is being received 13.name = joint_states 13.type = sensor_msgs/JointState 13.desc = The states (position, velocity) of the drive wheel joints 14.name = minute_button 14.type = std_msgs/Empty 14.desc = A message is published to this topic when the ''Minute'' button is pressed 15.name = mode 15.type = ca_msgs/Mode 15.desc = The current mode of the robot (See [[https://www.adafruit.com/datasheets/create_2_Open_Interface_Spec.pdf|OI Spec]] for details) 16.name = odom 16.type = nav_msgs/Odometry 16.desc = Odometry based on wheel encoders 17.name = spot_button 17.type = std_msgs/Empty 17.desc = A message is published to this topic when the ''Spot'' button is pressed 18.name = /tf 18.type = tf2_msgs/TFMessage 18.desc = The transform from the odometry frame to the base frame. Only if the parameter '''publish_tf''' is set to `true` 19.name = wheeldrop 19.type = std_msgs/Empty 19.desc = A message is published to this topic if a wheeldrop is detected } param { 0.name = ~base_frame 0.type = string 0.desc = Robot's base frame ID (used in various message headers) 0.default = base_footprint 1.name = ~baud 1.type = int 1.desc = Serial baud rate 1.default = Inferred based on robot model 2.name = ~dev 2.type = string 2.desc = Serial port for connecting to robot 2.default = /dev/ttyUSB0 3.name = ~latch_cmd_duration 3.type = double 3.desc = 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 3.default = 0.2 4.name = ~loop_hz 4.type = double 4.desc = Frequency of internal update loop. This affects the rate at which topics are published 4.default = 10.0 5.name = ~odom_frame 5.type = string 5.desc = Odometry frame ID (used in odometry message header and TF publisher) 5.default = odom 6.name = ~publish_tf 6.type = bool 6.desc = Turn on/off transform publisher from odometry frame to base frame 6.default = true 7.name = ~robot_model 7.type = string 7.desc = The model of robot being controlled (`ROOMBA_400`, `CREATE_1`, or `CREATE_2`). This determines the communication protocol used to interface with base 7.default = CREATE_2 } prov_tf { 0.from = odom 0.to = base_footprint 0.desc = The current robot position in the odometry frame } }}} == Report a Bug == <<GitHubIssues(AutonomyLab/create_autonomy)>> ## AUTOGENERATED DON'T DELETE ## CategoryStack