diff --git a/.nojekyll b/.nojekyll new file mode 100644 index 00000000..e69de29b diff --git a/404.html b/404.html new file mode 100644 index 00000000..11378319 --- /dev/null +++ b/404.html @@ -0,0 +1,1999 @@ + + + +
+ + + + + + + + + + + + + + + + + +The Create® 3 robot is equipped with a docking station to recharge it between experiments.
+Through the ROS 21 APIs users can command docking and undocking autonomous behaviors.
+Warning
+Note that the docking action and sensor topic changed between Galactic and Humble.
+In order for the robot to detect the dock, determine its location, and understand when it is succesfully docked, it is necessary that the docking station is connected to a power source.
+You can command the robot to undock using the following ROS 2 action.
+ros2 action send_goal /undock irobot_create_msgs/action/Undock "{}"
+
The robot will move backward out of the dock and then it will rotate 180 degrees.
+This action will fail if the robot is already undocked.
+You can command the robot to dock using a ROS 2 action.
+ros2 action send_goal /dock irobot_create_msgs/action/DockServo "{}"
+
ros2 action send_goal /dock irobot_create_msgs/action/Dock "{}"
+
The robot will first search for the dock in its immediate surroundings.
+Note that the action will fail if the robot is too far from the dock.
+You can check if the dock is visible by subscribing to the (in Galactic) /dock
(or in Humble) /dock_status
ROS 2 topic.
Then the robot will align with the dock and carefully drive onto it.
+This action will fail if the robot is already docked.
+The Create® 3 robot exposes several docking-related information through its ROS 2 publications. +These should allow users to write their own algorithms taking into account the presence of the dock in the environment and even to write their own docking and undocking procedures.
+The Create® 3 docking station transmit several IR signals. +The Create® 3 robot is equipped with two different sensors that are capable of detecting them.
+ +The robot will publish these signals in the /ir_opcode
ROS 2 topic.
+Each message will contain a time-stamped detection of one of those signals, including the identifier of the sensor that detected it.
In Galactic, more high-level information is produced by the robot in the /dock
ROS 2 topic.
+In Humble and beyond, the topic has been renamed to /dock_status
.
+Here it's possible to quickly know if the robot is able to see the dock from its current location and whether it is currently docked or not.
The Create® 3 robot exposes some actions for simple driving goals that close the loop on odometry position.
+Through the ROS 21 APIs users can command:
+Driving along a specified arc
+Driving in a straight line for a fixed distance
+Navigating to a specified odometry position and orientation
+Rotating a fixed angle
+A cliff event or a wheel stall will trigger a goal to cancel, +otherwise it will run until the robot achieves the odometry goal or it's canceled by the user. +If there is something blocking the robot's path, +the user must intervene to stop the robot, +otherwise it will continue to bump until odometry slip achieves the goal position.
+You can command the robot to drive a fixed angle along an arc defined by radius:
+ros2 action send_goal /drive_arc irobot_create_msgs/action/DriveArc "{angle: 1.57,radius: 0.3,translate_direction: 1,max_translation_speed: 0.3}"
+
The robot will drive forward or backward given the translate direction along an arc defined by radius until it achieves the specified relative heading.
+You can command the robot to drive a fixed distance in a straight line:
+ros2 action send_goal /drive_distance irobot_create_msgs/action/DriveDistance "{distance: 0.5,max_translation_speed: 0.15}"
+
The robot will drive straight until it has traveled the specified distance in odometry frame. +It will drive backwards if distance is negative (be aware of the backup limit).
+You can command the robot to drive to the specified odometry position:
+ros2 action send_goal /navigate_to_position irobot_create_msgs/action/NavigateToPosition "{achieve_goal_heading: true,goal_pose:{pose:{position:{x: 1,y: 0.2,z: 0.0}, orientation:{x: 0.0,y: 0.0, z: 0.0, w: 1.0}}}}"
+
The robot will take a rotate -> translate -> rotate approach to achieve the goal position. +First rotating from its current heading to face the goal position, then driving straight to the goal position, +then optionally rotating to achieve the goal heading.
+You can command the robot to rotate a relative angle from current robot heading:
+ros2 action send_goal /rotate_angle irobot_create_msgs/action/RotateAngle "{angle: 1.57,max_rotation_speed: 0.5}"
+
The robot will rotate either clockwise (negative angle) or counter clockwise (positive angle) until it has achieved the angle offset.
+ + + + + + + + + +The Create® 3 robot is equipped with a variety of sensors that are capable to detect hazards in the environment.
+In particular you will find:
+hazard_detection
topicThe Create® 3 robot will periodically publish on the hazard_detection
ROS 21 topic a vector of all the currently detected hazards.
+If the vector is empty, this means that no hazards are currently being detected.
Each element of the vector will denote a different hazard detection.
+Look at the HazardDetection.msg definition in order to see how to differentiate different types of hazards.
+The header
field of each indivdual detection will provide all the information required to localize it.
+In particular the timestamp will denote when the robot detected the hazard and the frame id will denote the location of the sensor that performed the detection.
Important
+The hazard_detection
topic will also contain a BACKUP_LIMIT
hazard if the robot safety features are preventing it from safely moving further backwards. Look at the safety documentation for details and how to disable it.
No hazards: +
header:
+ stamp:
+ sec: 1688673217
+ nanosec: 973425138
+ frame_id: base_link
+detections: []
+
Many hazards: +
header:
+ stamp:
+ sec: 1688673239
+ nanosec: 782492541
+ frame_id: base_link
+detections:
+- header:
+ stamp:
+ sec: 1688673239
+ nanosec: 782576914
+ frame_id: cliff_side_left
+ type: 2
+- header:
+ stamp:
+ sec: 1688673239
+ nanosec: 782576914
+ frame_id: cliff_front_left
+ type: 2
+- header:
+ stamp:
+ sec: 1688673239
+ nanosec: 782576914
+ frame_id: cliff_front_right
+ type: 2
+- header:
+ stamp:
+ sec: 1688673239
+ nanosec: 782576914
+ frame_id: cliff_side_right
+ type: 2
+- header:
+ stamp:
+ sec: 1688673239
+ nanosec: 781947051
+ frame_id: left_wheel
+ type: 3
+- header:
+ stamp:
+ sec: 1688673239
+ nanosec: 781947051
+ frame_id: right_wheel
+ type: 3
+- header:
+ stamp:
+ sec: 1688673239
+ nanosec: 782576914
+ frame_id: base_link
+ type: 0
+
kidnap_status
topicBy "kidnap" we denote the action of manually lifting the robot and, eventually, placing it back in a location which may be different from the original one.
+The Create® 3 robot combines together different sensors data in order to determine when it's being kidnapped.
+A boolean status will be periodically published on the kidnap_status
topic.
header:
+ stamp:
+ sec: 1688672489
+ nanosec: 526097022
+ frame_id: base_link
+is_kidnapped: false
+
ir_intensity
topic7 sets of IR emitters and receivers are available in the front bumper to detect objects at close range.
+The Create® 3 robot will periodically publish on the ir_intensity
topic the raw intensity readings obtained from these sensors.
+The message will be a vector where each element corresponds to a different sensor.
+The higher the intensity value is, the closer an obstacle is to the robot.
+The header
field of each indivdual detection will provide all the information required to localize it.
+In particular the timestamp will denote when the robot detected the hazard and the frame id will denote the location of the sensor that performed the detection.
header:
+ stamp:
+ sec: 1688673736
+ nanosec: 121692158
+ frame_id: base_link
+readings:
+- header:
+ stamp:
+ sec: 1688673736
+ nanosec: 121692158
+ frame_id: ir_intensity_side_left
+ value: 0
+- header:
+ stamp:
+ sec: 1688673736
+ nanosec: 121692158
+ frame_id: ir_intensity_left
+ value: 0
+- header:
+ stamp:
+ sec: 1688673736
+ nanosec: 121692158
+ frame_id: ir_intensity_front_left
+ value: 0
+- header:
+ stamp:
+ sec: 1688673736
+ nanosec: 121692158
+ frame_id: ir_intensity_front_center_left
+ value: 0
+- header:
+ stamp:
+ sec: 1688673736
+ nanosec: 121692158
+ frame_id: ir_intensity_front_center_right
+ value: 5
+- header:
+ stamp:
+ sec: 1688673736
+ nanosec: 121692158
+ frame_id: ir_intensity_front_right
+ value: 0
+- header:
+ stamp:
+ sec: 1688673736
+ nanosec: 121692158
+ frame_id: ir_intensity_right
+ value: 3
+
cliff_intensity
topic4 sets of IR emitters and receivers are available in on the bottom of the robot just behind its front bumper to detect presence or absence of the floor.
+The Create® 3 robot will periodically publish on the cliff_intensity
topic the raw intensity readings obtained from these sensors.
+The message will be a vector where each element corresponds to a different sensor.
+The higher the intensity value is, the more intensely the floor is perceived.
+The header
field of each indivdual detection will provide all the information required to localize it.
+In particular the timestamp will denote the time of the reading and the frame id will denote the location of the sensor that performed the detection.
header:
+ stamp:
+ sec: 1688672489
+ nanosec: 986327471
+ frame_id: base_link
+readings:
+- header:
+ stamp:
+ sec: 1688672489
+ nanosec: 986327471
+ frame_id: cliff_side_left
+value: 2207
+- header:
+ stamp:
+ sec: 1688672489
+ nanosec: 986327471
+ frame_id: cliff_front_left
+value: 2235
+- header:
+ stamp:
+ sec: 1688672489
+ nanosec: 986327471
+ frame_id: cliff_front_right
+value: 2206
+- header:
+ stamp:
+ sec: 1688672489
+ nanosec: 986327471
+ frame_id: cliff_side_right
+value: 2187
+
The Create® 3 robot is equipped with a variety of sensors that are used to detect its motions. +In particular you will find:
+Many details about these messages can be found in the message definitions themselves, which are linked below.
+If you want to implement your own algorithms using the raw sensor readings, you can read them from the following topics:
+imu
topicThe imu
topic produces messages of type sensor_msgs/msg/Imu
.
+As of G.4 / H.1, this topic publishes at 100 Hz.
+Prior to these releases, this topic published at 62.5 Hz.
mouse
topicThe mouse
topic produces messages of type irobot_create_msgs/msg/Mouse
.
+This topic publishes at 62.5 Hz.
wheel_status
topicThe wheel_status
topic produces messages of type irobot_create_msgs/msg/WheelStatus
.
+This topic publishes at 62.5 Hz.
wheel_ticks
topicThe wheel_ticks
topic produces messages of type irobot_create_msgs/msg/WheelTicks
.
+This topic publishes at 62.5 Hz.
+There are 508.8 ticks per wheel rotation.
wheel_vels
topicThe wheel_status
topic produces messages of type irobot_create_msgs/msg/WheelStatus
.
+This topic publishes at 62.5 Hz.
The following topics are computed on-board the Create 3 robot using its raw sensor data.
+odom
topicThe odom
topic produces messages of type nav_msgs/msg/Odometry
.
+The Create® 3 robot fuses the reading from its various sensors in order to produce a dead reckoning estimate of its pose on the odom
topic.
+This topic publishes at 20 Hz.
slip_status
topicThe slip_status
topic produces messages of type irobot_create_msgs/msg/SlipStatus
.
+We denote by "slippage" a loss of efficiency in the wheels.
+This is usually caused by losing traction between the wheels and the ground with the results that the motion detected by the wheels encoders is greater than what the robot actually performed.
We fuse together various sensors in order to compute a boolean estimate of whether the robot is slipping or not and we periodically publish it on the slip_status
topic.
+If you are developing your own state estimation algorithm using the wheels encoders, then it is recommended to inflate the differential motion covariance matrix to take this problem into account.
Note that the optical mouse sensor is not affected by slippage. +This topic publishes at 20 Hz.
+stop_status
topicThe stop_status
topic produces messages of type irobot_create_msgs/msg/StopStatus
.
+The Create® 3 robot will periodically publish a boolean estimate of whether it is currently moving or not on the stop_status
topic.
+This topic publishes at 1 Hz.
All trademarks mentioned are the property of their respective owners. ↩
+With the word "reflex" we denote a set of autonomous reactive behaviors that the Create® 3 robot will trigger when it detects obstacles or hazards.
+Reflexes are high-priority behaviors and will temporarily override any user-provided command for their short duration.
+Reflexes can be enabled or disabled on the Create® 3 using the corresponding ROS 21 parameters exposed by the motion_control
ROS 2 node.
The reflexes_enabled
parameter controls whether reflexes should be executed or not. It accepts boolean values.
+When this parameter is set to false
, no reflexes will be enabled, regardless of their specific parameters values.
This parameter is set to true by default, so reflexes are generally enabled, but note that individual reflexes can be enabled or disabled via their specific parameters described below.
+The reflexes.REFLEX_BUMP
ROS 2 parameter enables (true
) or disables (false
) the bump reflex.
+It will trigger as soon as the robot bumps into an obstacle and it will move the robot away from it.
+The reflex will continue until the robot has cleared the bump.
This reflex is enabled by default.
+The reflexes.REFLEX_CLIFF
ROS 2 parameter enables (true
) or disables (false
) the cliff reflex.
+It will trigger as soon as the robot detects a cliff and it will move the robot away from it.
+The reflex will continue until the robot has cleared the cliff.
This reflex is enabled by default.
+The reflexes.REFLEX_DOCK_AVOID
ROS 2 parameter enables (true
) or disables (false
) the dock avoidance reflex.
+It will trigger as soon as the robot gets close to the dock and tries to move towards it.
+The reflex will stop forward movements.
This reflex is disabled by default.
+The reflexes.REFLEX_GYRO_CAL
ROS 2 parameter enables (true
) or disables (false
) the gyro calibration reflex.
+It will trigger while the robot is stationary and will try to recalibrate the internal gyroscope.
This reflex is enabled by default.
+The reflexes.REFLEX_PANIC
ROS 2 parameter enables (true
) or disables (false
) the panic reflex.
+It will trigger when the robot is trapped and unable to clear obstacles or hazards.
+The reflex will try more aggressive maneuvers to allow the robot to recover from this situation
This reflex is enabled by default.
+The reflexes.REFLEX_PROXIMITY_SLOWDOWN
ROS 2 parameter enables (true
) or disables (false
) the proximity slowdown reflex.
+It will trigger when the robot's IR sensors detect an obstacle in close proximity.
+The reflex will reduce the robot movement speed in order to better prepare for an eventual impact.
This reflex is enabled by default.
+The reflexes.REFLEX_STUCK
ROS 2 parameter enables (true
) or disables (false
) the stuck reflex.
+It will trigger when the robot is stuck, i.e. it's pushing against an obstacle and its wheels are losing traction.
+The reflex will try aggressive maneuvers to allow the robot to recover from this situation
This reflex is enabled by default.
+The reflexes.REFLEX_VIRTUAL_WALL
ROS 2 parameter enables (true
) or disables (false
) the virtual wall reflex.
+It will trigger as soon as the robot detects an iRobot virtual wall it will move the robot away from it.
+The reflex will continue until the robot has cleared the virtual wall.
This reflex is enabled by default.
+The reflexes.REFLEX_WHEEL_DROP
ROS 2 parameter enables (true
) or disables (false
) the wheel drop reflex.
+It will trigger as soon as the robot detects that one of its wheels is fully extended (dropped).
+The robot will drive the other wheel in order to return to a flat surface.
This reflex is enabled by default.
+ + + + + + + + + +The Create® 3 robot is based on ROS 21 and, as such, it exposes all its user-facing APIs through ROS 2 entities (topics, services, actions and parameters).
+The purpose of this page is to give a quick overview of these ROS 2 APIs. +The robot uses standard ROS 2 messages when available and implements custom messages in irobot_create_msgs for data not represented by standard messages. +If you are interested in more details, have a look at the other pages in this section.
+You can see the ROS 2 topics exposed by the Create® 3 robot running the ros2 topic list
command.
$ ros2 topic list -t
+/battery_state [sensor_msgs/msg/BatteryState]
+/cliff_intensity [irobot_create_msgs/msg/IrIntensityVector]
+/cmd_audio [irobot_create_msgs/msg/AudioNoteVector]
+/cmd_lightring [irobot_create_msgs/msg/LightringLeds]
+/cmd_vel [geometry_msgs/msg/Twist]
+/dock [irobot_create_msgs/msg/Dock]
+/hazard_detection [irobot_create_msgs/msg/HazardDetectionVector]
+/imu [sensor_msgs/msg/Imu]
+/interface_buttons [irobot_create_msgs/msg/InterfaceButtons]
+/ir_intensity [irobot_create_msgs/msg/IrIntensityVector]
+/ir_opcode [irobot_create_msgs/msg/IrOpcode]
+/kidnap_status [irobot_create_msgs/msg/KidnapStatus]
+/mouse [irobot_create_msgs/msg/Mouse]
+/odom [nav_msgs/msg/Odometry]
+/parameter_events [rcl_interfaces/msg/ParameterEvent]
+/rosout [rcl_interfaces/msg/Log]
+/slip_status [irobot_create_msgs/msg/SlipStatus]
+/stop_status [irobot_create_msgs/msg/StopStatus]
+/tf [tf2_msgs/msg/TFMessage]
+/tf_static [tf2_msgs/msg/TFMessage]
+/wheel_status [irobot_create_msgs/msg/WheelStatus]
+/wheel_ticks [irobot_create_msgs/msg/WheelTicks]
+/wheel_vels [irobot_create_msgs/msg/WheelVels]
+
Note that the Create® 3 robot will produce data on most of these topics. +On the other hand, some of them can be used by the user to send commands to the Create® 3 robot. +In particular, the Create® 3 robot will subscribe to the following topics:
+/cmd_audio
: use this topic to play specified notes from the robot speaker./cmd_lightring
: use this topic to change the color of the light ring./cmd_vel
: use this topic to command velocities in the robot reference frame.For more details on the content of these topics, please have a look at their corresponding sections.
+ +If you have trouble seeing the topics using ros2 topic list
, ensure that the robot's RMW_IMPLEMENTATION
matches the one on your machine; see Network Configuration for more information about ROS middleware (RMW).
+Additionally, the command line ros2 topic
utility could use stale cached discovery information; try running it with additional arguments ros2 topic list --no-daemon --spin-time 10
to not use the cached information.
You can see the ROS 2 servers exposed by the Create® 3 robot running the ros2 service list
command.
$ ros2 service list -t
+/e_stop [irobot_create_msgs/srv/EStop]
+/motion_control/describe_parameters [rcl_interfaces/srv/DescribeParameters]
+/motion_control/get_parameter_types [rcl_interfaces/srv/GetParameterTypes]
+/motion_control/get_parameters [rcl_interfaces/srv/GetParameters]
+/motion_control/list_parameters [rcl_interfaces/srv/ListParameters]
+/motion_control/set_parameters [rcl_interfaces/srv/SetParameters]
+/motion_control/set_parameters_atomically [rcl_interfaces/srv/SetParametersAtomically]
+/robot_power [irobot_create_msgs/srv/RobotPower]
+/robot_state/change_state [lifecycle_msgs/srv/ChangeState]
+/robot_state/get_available_states [lifecycle_msgs/srv/GetAvailableStates]
+/robot_state/get_available_transitions [lifecycle_msgs/srv/GetAvailableTransitions]
+/robot_state/get_state [lifecycle_msgs/srv/GetState]
+/robot_state/get_transition_graph [lifecycle_msgs/srv/GetAvailableTransitions]
+/static_transform/change_state [lifecycle_msgs/srv/ChangeState]
+/static_transform/describe_parameters [rcl_interfaces/srv/DescribeParameters]
+/static_transform/get_available_states [lifecycle_msgs/srv/GetAvailableStates]
+/static_transform/get_available_transitions [lifecycle_msgs/srv/GetAvailableTransitions]
+/static_transform/get_parameter_types [rcl_interfaces/srv/GetParameterTypes]
+/static_transform/get_parameters [rcl_interfaces/srv/GetParameters]
+/static_transform/get_state [lifecycle_msgs/srv/GetState]
+/static_transform/get_transition_graph [lifecycle_msgs/srv/GetAvailableTransitions]
+/static_transform/list_parameters [rcl_interfaces/srv/ListParameters]
+/static_transform/set_parameters [rcl_interfaces/srv/SetParameters]
+/static_transform/set_parameters_atomically [rcl_interfaces/srv/SetParametersAtomically]
+
You can see the ROS 2 action servers exposed by the Create® 3 robot running the ros2 action list
command.
$ ros2 action list -t
+/audio_note_sequence [irobot_create_msgs/action/AudioNoteSequence]
+/dock [irobot_create_msgs/action/DockServo]
+/drive_arc [irobot_create_msgs/action/DriveArc]
+/drive_distance [irobot_create_msgs/action/DriveDistance]
+/led_animation [irobot_create_msgs/action/LedAnimation]
+/navigate_to_position [irobot_create_msgs/action/NavigateToPosition]
+/rotate_angle [irobot_create_msgs/action/RotateAngle]
+/undock [irobot_create_msgs/action/Undock]
+/wall_follow [irobot_create_msgs/action/WallFollow]
+
For more details on how to use these actions, please have a look at their corresponding sections.
+You can see the ROS 2 parameters exposed by the Create® 3 robot running the ros2 param list
command.
$ ros2 param list
+/motion_control:
+ max_speed
+ min_speed
+ qos_overrides./parameter_events.publisher.depth
+ qos_overrides./parameter_events.publisher.durability
+ qos_overrides./parameter_events.publisher.history
+ qos_overrides./parameter_events.publisher.reliability
+ reflexes.REFLEX_BUMP
+ reflexes.REFLEX_CLIFF
+ reflexes.REFLEX_DOCK_AVOID
+ reflexes.REFLEX_GYRO_CAL
+ reflexes.REFLEX_PANIC
+ reflexes.REFLEX_PROXIMITY_SLOWDOWN
+ reflexes.REFLEX_STUCK
+ reflexes.REFLEX_VIRTUAL_WALL
+ reflexes.REFLEX_WHEEL_DROP
+ reflexes_enabled
+ safety_override
+ use_sim_time
+ wheel_accel_limit
+/robot_state:
+ publish_odom_tfs
+ qos_overrides./tf.publisher.depth
+ qos_overrides./tf.publisher.durability
+ qos_overrides./tf.publisher.history
+ qos_overrides./tf.publisher.reliability
+ use_sim_time
+/static_transform:
+ qos_overrides./tf_static.publisher.depth
+ qos_overrides./tf_static.publisher.history
+ qos_overrides./tf_static.publisher.reliability
+ use_sim_time
+ wheel_base
+ wheels_encoder_resolution
+ wheels_radius
+/system_health:
+ log_period
+ qos_overrides./parameter_events.publisher.depth
+ qos_overrides./parameter_events.publisher.durability
+ qos_overrides./parameter_events.publisher.history
+ qos_overrides./parameter_events.publisher.reliability
+ use_sim_time
+/ui_mgr:
+ lightring_led_brightness
+ qos_overrides./parameter_events.publisher.depth
+ qos_overrides./parameter_events.publisher.durability
+ qos_overrides./parameter_events.publisher.history
+ qos_overrides./parameter_events.publisher.reliability
+ use_sim_time
+
wheel_base
and wheels_encoder_resolution
are read-only parameters that can be used in order to implement your estimation or motion control algorithms.safety_override
parameter allows user to enable/disable safety features (default: none).
+For more details, please have a look at the safety documentation.publish_odom_tfs
parameter allows the user to enable transformations from odom
(boolean, default: true).
+ This parameter cannot be set at runtime; it must be configured from the ROS 2 parameters file on the application configuration page of the webserver, as it is loaded only at application start.wheel_accel_limit
parameter sets acceleration limits in units of mm·s-2 (int between 1 and 900 inclusive, default: 900).lightring_led_brightness
parameter allows user to increase/decrease the brightness of the light ring (int between 10 - 100 inclusive, default: 15).For more details on how to use and configure reflexes, please have a look at the reflexes documentation.
+The Create® 3 robot produces a fused odometry that combines its wheel encoders, IMU, and ground optical flow sensor.
+The robot's coordinate system is right-handed, with x forward, y left, and z up.
+It exposes this coordinate system both through the tf tree and the /odom
publication.
+The /tf
tree from the robot exposes ROS 2 standard transforms odom->base_footprint
and odom->base_link
with corresponding definitions odom, base_footprint, and base_link.
+base_link
is defined to be at the center of rotation of the robot with z height intersecting the floor.
+base_footprint
is the 2D planar representation base_link
with the pitch and roll factors removed from the transform, this can be useful for applications like 2D planar mapping.
+The /odom
publication contains the same position and orientation as base_link
in the form of a nav_msgs/msg/Odometry
message with velocity additionally populated.
+Note: the /odom
-> /base_footprint
and /odom
-> base_link
transformations can be disabled by setting the publish_odom_tfs
parameter to false
.
+The publish_odom_tfs
parameter cannot be set at runtime; it must be configured from the ROS 2 parameters file on the application configuration page of the webserver, as it is loaded only at application start.
$ ros2 topic echo /tf
+transforms:
+- header:
+ stamp:
+ sec: 1646697192
+ nanosec: 702756640
+ frame_id: odom
+ child_frame_id: base_footprint
+ transform:
+ translation:
+ x: -0.00043813258525915444
+ y: -3.853919679386308e-06
+ z: 0.0
+ rotation:
+ x: 0.0
+ y: 0.0
+ z: 2.5629995434428565e-05
+ w: 1.0
+- header:
+ stamp:
+ sec: 1646697192
+ nanosec: 702756640
+ frame_id: odom
+ child_frame_id: base_link
+ transform:
+ translation:
+ x: -0.00043813258525915444
+ y: -3.853919679386308e-06
+ z: 0.0
+ rotation:
+ x: -0.0016827837098389864
+ y: -0.009617267176508904
+ z: 9.441922884434462e-06
+ w: 0.9999523162841797
+
By default, the Create® 3 robot has some safety features enabled. +Their purpose is to make sure that the robot does not get into dangerous sitations and it is able to detect and react properly to cliff hazards.
+Safety features are configurable by the user through a ROS 21 parameter. +This will allow more adventurous users to have full control over the robot.
+Important
+The robot will temporarily re-enable all safety features whenever it is commanded to execute any of the built-in autonomous behaviors.
+The safety_override
parameter exposed by the motion_control
ROS 2 node should be used to control and override safety features.
+It's a string
parameter and it accepts 3 possible values:
none
Safety features are fully enabled. This is the default value.backup_only
Overrides the robot backup limit safety feature, disabling it.full
Safety features are fully disabled.For example, in order to completely disable safety mechanisms:
+ros2 param set /motion_control safety_override full
+
Note that the parameter server will reject changes if there are typos in the new safety value set by the users.
+The following sections briefly describe what the safety features do.
+Attention
+If you disable the backup limit, the robot will not stop if there are cliffs while driving backward!
+The Create® 3 robot is equipped with cliff sensors, but they are located only in the front of the robot. +This means that the robot is not able to detect cliff hazards while driving backward.
+In order to make the robot safe, the robot's default policy is to never move backward further than what would be safe should there be a cliff directly behind the robot. +Under standard circumstances, the robot is allowed to briefly move backward only if it has first traveled forward (i.e. if it has "explored" the space making sure that it does not present cliff hazards).
+If the robot is kidnapped (i.e. first lifted by the user and then placed somewhere), the backup limit will immediately trigger.
+The Create® 3 robot signals to the user when the backup limit is about to be triggered in multiple ways:
+HazardDetectionsVector
ROS 2 message: an hazard of type BACKUP_LIMIT
will be published in the vector.If the user ignores these alerts and keeps driving the robot backward, the robot will suddenly brake and come to a stop.
+From this point, the robot will refuse any backward movement.
+The user will have to drive the robot forward in order to re-enable backward movements.
+As soon as the user drives the robot forward, the lights will go back to the default white color.
+Safe backward movements will not be immediately re-allowed, but rather the robot will have to keep driving forward for a little while.
+This moment will be identified by the BACKUP_LIMIT
hazard disappearing from the HazardDetectionsVector
message.
The backup limit and its related alerts are active only when safety_override = none
.
Attention
+If you increase the speed above the default one, the robot may not be able to stop in time when a cliff is detected!
+In order to stop when a cliff hazard is detected, it is also necessary to make sure that the robot is not driving too fast. +Safety features will thus limit the robot speed.
+You can check the current maximum robot speed through the read-only parameter max_speed
exposed by the motion_control
ROS 2 node.
When safety_override = none
or safety_override = backup_only
the maximum speed will be limited to 0.306 m/s.
By fully disabling safety features, i.e. setting safety_override = full
the robot will be allowed to drive at its true maximum speed of 0.460 m/s.
The robot exposes its commanding acceleration limits through the wheel_accel_limit
parameter on the motion_control
node.
+The velocity commands sent to the wheels will be ramped with the acceleration profile associated with this value.
+The value defaults to its maximum settable 900 mm/s^2
. If using heavier payloads, it is advisable to decrease acceleration limits.
The robot exposes a service with name e_stop
that when sent e_stop_on
true will turn off the robot's wheels.
+The robot will not respond to velocity commands when e_stop_on
is true.
+See EStop.srv
For example, in order to enable the E-Stop:
+ros2 service call /e_stop irobot_create_msgs/srv/EStop "{e_stop_on: true}"
+
There is a wheel_status
topic which publishes WheelStatus.msg
+exposing whether the wheels are enabled (disabled if E-Stop is engaged) and the present PWM duty cycle and current through each wheel.
The Create® 3 robot can interact with the user through its buttons and its light ring.
+Whenever a button on the Create® 3 robot is pressed, its information will be published on the interface_buttons
topic.
+By subscribing to this topic, you will be able to detect when to start your custom policies.
Attention
+The Create® 3 robot uses its light ring to notify the user about critical events. If you override its color, you may not notice these events.
+You can change the color of the light ring on your Create® 3 robot by publishing a corresponding message on the cmd_lightring
topic.
ros2 topic pub /cmd_lightring irobot_create_msgs/msg/LightringLeds "{override_system: true, leds: [{red: 255, green: 0, blue: 0}, {red: 0, green: 255, blue: 0}, {red: 0, green: 0, blue: 255}, {red: 255, green: 255, blue: 0}, {red: 255, green: 0, blue: 255}, {red: 0, green: 255, blue: 255}]}"
+
The easiest way to return lights to the default color (and relinquish their control to the robot) is to publish an empty message on the topic.
+ros2 topic pub /cmd_lightring irobot_create_msgs/msg/LightringLeds "{}"
+
Additionally, an action server named led_animation
can take Blink or Spin animation goals to execute a pattern for a fixed duration.
+See LedAnimation.action.
For example you can run the following:
+ros2 action send_goal led_animation irobot_create_msgs/action/LedAnimation "{animation_type: 1, lightring: {leds: [{red: 255, green: 0, blue: 0}, {red: 0, green: 255, blue: 0}, {red: 0, green: 0, blue: 255}, {red: 255, green: 255, blue: 0}, {red: 255, green: 0, blue: 255}, {red: 0, green: 255, blue: 255}], override_system: true},max_runtime: {sec: 500, nanosec: 0}}"
+
You can play sound out of your Create® 3 robot speakers by publishing a corresponding message on the cmd_audio
topic.
Important
+A best-effort
publisher will not be able to communicate with this subscription as of G.4.4 / H.1.1 as its QOS has been changed to reliable
from best-effort
. See this compatibilty matrix for details.
ros2 topic pub --once /cmd_audio irobot_create_msgs/msg/AudioNoteVector "{append: false, notes: [{frequency: 100, max_runtime: {sec: 1,nanosec: 0}}, {frequency: 50, max_runtime: {sec: 1,nanosec: 0}}]}"
+
This example command will play 2 notes at the given frequencies back to back with the given 1 second length for each note.
+append
is used to dictate the policy if an audio sequence is already playing when a new value comes in on the topic.
append: true
tells the sound manager to play this audio sequence after the current sequence finishes playing.append: false
tell the sound manager to override any currently playing sequence with the new sequence.Publishing an empty notes
vector with append: false
will stop any currently playing audio sequences.
Additionally, an action server named audio_note_sequence
can take an AudioNoteVector and a number of iterations to play it.
+See AudioNoteSequence.action.
The action goal will succeed when the sequence has finished playing so you can coordinate audio runtime with other actions. +If you set iterations to -1, it will play until it is canceled.
+For example you can run the following:
+ros2 action send_goal /audio_note_sequence irobot_create_msgs/action/AudioNoteSequence "{iterations: 3,note_sequence:{append: false, notes: [{frequency: 100, max_runtime: {sec: 1,nanosec: 0}}, {frequency: 50, max_runtime: {sec: 1,nanosec: 0}}]}}"
+
The Create® 3 robot exposes a ROS 21 action server to invoke a wall-following behavior.
+You can command the robot to follow along an obstacle using the following ROS 2 action.
+ros2 action send_goal /wall_follow irobot_create_msgs/action/WallFollow "{follow_side: 1, max_runtime: {sec: 1, nanosec: 0}}"
+
When this behavior is requested, the robot will try to engage with nearby obstacles and, after a successful engagement, it will start following the obstacle along the specified side until the maximum runtime is reached.
+The follow_side
can be specified as left (1) or right (-1) see the action interface for the implementation.
The robot will use a spiraling motion to try to engage with the obstacles.
+The spiral will be clockwise if follow_side
is left (1) or counter-clockwise if follow_side
is right (-1).
This page describes how to use the the Create® 3 robot's actuators using the ROS 21 command line tools.
+Play a happy sequence once: +
ros2 topic pub /cmd_audio irobot_create_msgs/msg/AudioNoteVector "{append: false, notes: [{frequency: 392, max_runtime: {sec: 0,nanosec: 177500000}}, {frequency: 523, max_runtime: {sec: 0,nanosec: 355000000}}, {frequency: 587, max_runtime: {sec: 0,nanosec: 177500000}}, {frequency: 784, max_runtime: {sec: 0,nanosec: 533000000}}]}" -1
+
Play a sad sequence once: +
ros2 topic pub /cmd_audio irobot_create_msgs/msg/AudioNoteVector "{append: false, notes: [{frequency: 369, max_runtime: {sec: 0,nanosec: 355000000}}, {frequency: 300, max_runtime: {sec: 0,nanosec: 533000000}}]}" -1
+
Play a scary sequence forever: +
ros2 action send_goal /audio_note_sequence irobot_create_msgs/action/AudioNoteSequence "{iterations: -1, note_sequence: {append: false, notes: [{frequency: 82, max_runtime: {sec: 1,nanosec: 0}}, {frequency: 87, max_runtime: {sec: 1,nanosec: 0}}]}}"
+
API documentation on the speakers can be found here.
+You can drive around the Create® 3 robot by publishing standard Twist
messages on the /cmd_vel
topic.
ros2 topic pub -r 20 /cmd_vel geometry_msgs/msg/Twist "{linear: {x: 0.2, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}"
+
The Drive Distance action takes a distance in meters and maximum speed in meters per second. +
ros2 action send_goal /drive_distance irobot_create_msgs/action/DriveDistance "{distance: 0.5,max_translation_speed: 0.15}"
+
The Rotate Angle action takes a turn angle in radians and maximum angular speed in radians per second. +
ros2 action send_goal /rotate_angle irobot_create_msgs/action/RotateAngle "{angle: 1.57,max_rotation_speed: 0.5}"
+
The Drive Arc action takes a arc angle in radians, arc radius in meters, translate direction (1 for forward and -1 for rearward) and and maximum translation speed in meters per second. +
$ ros2 action send_goal /drive_arc irobot_create_msgs/action/DriveArc "{angle: 1.57,radius: 0.3,translate_direction: 1,max_translation_speed: 0.3}"
+
The Wall Follow action takes a side (1=left, -1=right) and a maximum duration. +
ros2 action send_goal /wall_follow irobot_create_msgs/action/WallFollow "{follow_side: 1, max_runtime: {sec: 1, nanosec: 0}}"
+
The Navigate to Position action takes a goal position (in meters) and orientation (in radians). The orientation must be specified as part of the message, but it can be ignored by setting achieve_goal_heading
to false
.
+
$ ros2 action send_goal /navigate_to_position irobot_create_msgs/action/NavigateToPosition "{achieve_goal_heading: true,goal_pose:{pose:{position:{x: 1,y: 0.2,z: 0.0}, orientation:{x: 0.0,y: 0.0, z: 0.0, w: 1.0}}}}"
+
If the Create® 3 robot is on its dock, you can undock it with the Undock action:
+ros2 action send_goal /undock irobot_create_msgs/action/Undock "{}"
+
If the Create® 3 robot sees its dock (check the docking documentation for details) you can dock it with:
+ros2 action send_goal /dock irobot_create_msgs/action/DockServo "{}"
+
ros2 action send_goal /dock irobot_create_msgs/action/Dock "{}"
+
If under the robot's control, its light ring will turn yellow when the motors are disabled. +
ros2 service call /e_stop irobot_create_msgs/srv/EStop "{e_stop_on: true}"
+
ros2 service call /e_stop irobot_create_msgs/srv/EStop "{e_stop_on: false}"
+
API documentation on the E-Stop is available here.
+ros2 topic pub /cmd_lightring irobot_create_msgs/msg/LightringLeds "{override_system: true, leds: [{red: 255, green: 0, blue: 0}, {red: 0, green: 255, blue: 0}, {red: 0, green: 0, blue: 255}, {red: 255, green: 255, blue: 0}, {red: 255, green: 0, blue: 255}, {red: 0, green: 255, blue: 255}]}" -1
+
ros2 topic pub /cmd_lightring irobot_create_msgs/msg/LightringLeds "{override_system: false, leds: [{red: 255, green: 0, blue: 0}, {red: 0, green: 255, blue: 0}, {red: 0, green: 0, blue: 255}, {red: 255, green: 255, blue: 0}, {red: 255, green: 0, blue: 255}, {red: 0, green: 255, blue: 255}]}" -1
+
# Note: type 1 is blink and type 2 is spin
+ros2 action send_goal /led_animation irobot_create_msgs/action/LedAnimation "{animation_type: 2,max_runtime:{sec: 10,nanosec: 0},lightring:{override_system: true, leds: [{red: 255, green: 0, blue: 0}, {red: 0, green: 255, blue: 0}, {red: 0, green: 0, blue: 255}, {red: 255, green: 255, blue: 0}, {red: 255, green: 0, blue: 255}, {red: 0, green: 255, blue: 255}]}}"
+
Warning: this turns the robot and payload off immediately +
ros2 service call /robot_power irobot_create_msgs/srv/RobotPower "{}"
+
The create3_examples Github repository contains examples of C++ and Python applications that can be used to control a Create® 3 robot with ROS 21 and develop your navigation application.
+ + + + + + + + + +This page describes how to read the the Create® 3 robot's sensors using the ROS 21 command line tools.
+Reading the robot's sensors is as simple as +
ros2 topic echo {topic}
+
ros2 topic list --no-daemon --spin-time 10
+
A detailed API description for each sensor can be found here.
+These are relatively straighforward, but for fun:
+ros2 topic echo /battery_state
+
ros2 topic echo /interface_buttons
+
ros2 topic echo /dock
+
ros2 topic echo /dock_status
+
ros2 topic echo /ir_opcode
+
ros2 topic echo /ir_intensity
+
ros2 topic echo /odom
+
ros2 topic echo /wheel_status
+
The iRobot® Create® 3 robot1 has two electrical connections exposed via the Adapter Board. +The connections are accessible within the robot once the cargo bay is removed. +The Adapter Board is also visible through the top cover of the robot, where its indicators are visible, and the USB/BLE toggle can be switched.
+ +The unregulated battery port is a JST XH-style connector, with pin 1 as the positive terminal of the battery, and pin 2 as the negative terminal. +These terminals are labeled on the bottom side of the board and are visible with the robot on its back and the cargo bay removed. +The board is capable of supplying a maximum of 2 A of current at the current battery voltage (14.4 V nominal, 12 V min, 16.8 V max), enforced by a PTC resettable fuse in the robot. +This port is always on when the battery is powered on.
+Notice
+Do not back-feed power into the robot through this port, and do not attempt to use the robot without its battery installed.
+The USB-C® connector2 provides a USB 2.0 Host connection into the robot with 5.13 V at 3.0 A provided to power downstream connections. +The power is disabled on this port unless a proper USB-C® downstream device is connected. +The 5 V source powering this port is not guaranteed to stay enabled when the battery reports 0% state of charge (below 12.0 V). +The USB data connection is made only when the USB/BLE toggle switch plunger is slid toward the USB icon.
+The USB-C® port draws its power from the unregulated battery connection which, as mentioned above, is limited to 2 A at the battery voltage. +This means there is only around 28.8 W total power shared between both power outputs (assuming the battery is at 14.4 V). +If power is drawn through the USB-C® connector, then less power is available through the unregulated battery port and vice versa.
+Example
+As an example, if a full 5 V @ 3 A are drawn from the USB-C® port, the battery is currently measuring 14.4 V, and the switching regulator is 90% efficient, then a maximum of 0.84 A3 can be drawn from the unregulated battery port before the resettable fuse will trip (and depending on ambient temperature, even more margin may be necessary).
+The USB/BLE toggle routes the robot's single USB Host connection either to the USB-C® port (useful for connecting to single-board computers with OTG or device ports) or to the on-board Bluetooth® Low Energy4 module. +This module can be used to interact with the iRobot Education Python Web Playground or iRobot Coding app.
+The orange indicator (D3) is illuminated when the USB-C® port is powering a downstream device, whether or not a data connection is being made.
+The yellow indicator (D2) is illuminated when the robot's internal 5 V bus is enabled. There is a hardware error if this LED is extinguished while the green indicator is illuminated.
+The green indicator (D300) is illuminated when the robot's battery is switched on.
+The blue indicator (D6) is illuminated when the BLE radio is turned on. It flashes when it is connected to a host.
+iRobot® and Create® are registered trademarks of iRobot Corporation. ↩
+USB-C® is a trademark of USB Implementers Forum. ↩
+Maximum current computed as: 2 A - (5 V * 3 A / 0.90 / 14.4 V) = 0.84 A ↩
+The Bluetooth® word mark and logos are registered trademarks owned by Bluetooth SIG, Inc. and any use of such marks by iRobot is under license. ↩
+All other trademarks mentioned are the property of their respective owners. ↩
+