Wiki

Clone wiki

robobo-programming / ros / Robobo-Sensors

This wiki moved

Please use the new location: https://github.com/mintforpeople/robobo-programming/wiki


Robobo Sensor Topics

The Robobo robot publishes all its sensors as ROS topics. This allows a client program (ROS node) to be suscribed just to the sensors it is interested in.

Robobo has 15 sensor topics:

  • /robot/accel: Linear acceleration sensor.
  • /robot/ambientlight: Ambient light sensor.
  • /robot/battery/base: Battery level of the Robobo base.
  • /robot/battery/phone: Battery level of the smarpthone.
  • /robot/camera/camera_info: Meta information about the robot camera.
  • /robot/camera/image/compressed: Stream of images from the robot camera compressed with compressed_image_transport.
  • /robot/emotion: Notifies changes in the emotion (face) of the robot.
  • /robot/fling: Notifies a fling event in the touch screen (face) of the robot.
  • /robot/irs: Notifies changes in the values of the IR (infrared) sensors located in the Robobo base.
  • /robot/leds: Notifies changes in the color of a led of the Robobo base.
  • /robot/orientation: Gyroscope sensor.
  • /robot/pan: Notifies changes in the position of the pan mechanism of the Robobo base.
  • /robot/tap: Notifies a tap event in the touch screen (face) of the robot.
  • /robot/tilt: Notifies changes in the position of the tilt mechanism of the Robobo base.
  • /robot/wheels: Notifies changes in the position of the wheels of the base.

The complete list of topics can be easily viewed using the "rostopic list" command.

The "rostopic" command is also a powerfull tool to explore the topics and their message types before start programming. For example, "rostopic echo topic" will show all the data received by a topic.

Example of data received from the /robot/tap topic

/robot/pan

Notifies changes in the Robobo base smarpthone horizontal axis.

Message:

A message of type 'std_msgs/Int16' where the 'data' represents the angle of the pan.

Example

Example of /robot/pan


/robot/tilt

Notifies changes in the Robobo base smarpthone vertical axis.

Message:

A message of the 'std_msgs/Int16' where the 'data' represents the angle of the tilt.

Example

Example of /robot/tilt


/robot/wheels

Notifies changes in the Robobo base wheels spped and/or positions.

Message:

A message of type 'robobo_msgs/Wheels' with the next fields: * wheelPosR: Current right wheel encoder position. The value is increased linearly when the robot moves forwards, and decreases, even to negative numbers, when the robot moves backwards. * wheelPosL: Current left wheel encoder position. The value is increased linearly when the robot moves forwards, and decreases, even to negative numbers, when the robot moves backwards. * wheelSpeedR: Current right wheel speed in the range 0..100. * wheelSpeedL: Current left wheel speed in the range 0..100.

Example

Example of /robot/wheels


/robot/leds

Notifies changes in the color of the leds located in the Robobo base.

Message:

A message of type 'robobo_msgs/Led' with the next fields:

  • id: A string that identifies the led. Posible values: Front-C, Front-R, Front-L, Front-RR, Front-LL, Back-C, Back-R, Back-L.
  • r: Float between 0.0 - 1.0 that represents the red value of the led.
  • g: Float between 0.0 - 1.0 that represents the gree value of the led.
  • b: Float between 0.0 - 1.0 that represents the blue value of the led.

Example

Example of /robot/leds


/robot/battery/base

Notifies the current battery level of the Robobo base.

Message

A message of type 'std_msgs/Int8' where the 'data' represents the level of the Robobo base.

Example

Example of /robot/battery/base


/robot/irs

Notifies changes in the raw distance to obstacles detected by the Robobo base IR sensors. The base has eight IR sensors, five in the front and three in the back.

Message

A message of type 'robobo_msgs/IRs' where each field represenst one particular LED of the base.

Each field has the type 'sensor_msgs/Range' where only the next two fields are used:

  • radiation_type: Fixed to 1 because all of them are infrared sensors.
  • range: The raw distance value measured by the infrared sensors.

Each message notifies the current value of all the IR sensors in the base:

  • Back-C: Sensor at the center in the back of the base.
  • Back-L: Sensor at the left of the center in the back of the base.
  • Back-R: Sensor at the right of the center in the back of the base.
  • Front-C: Sensor at the center in the front of the base.
  • Front-L: Sensor at the left in the front of the base.
  • Front-LL: Sensor at left of the left sensor in the front of the base.
  • Front-R: Sensor at the right of the center in the front of the base.
  • Front-RR: Sensor at right of the right sensor in the front of the base.

Example

Example of /robot/irs


/robot/battery/phone

Notifies the current battery level of the smartphone.

Message

A message of type 'std_msgs/Int8' where the 'data' represents the battery level of the smartphone.

Example

Example of /robot/battery/phone


/robot/ambientlight

Notifies the current level of ambient light in Lux units.

Message

A message of type 'std_msgs/Int32' where the 'data' represents the level of ambient light in Lux units.

Example

Example of /robot/ambientlight


/robot/orientation

Notifies changes in the robot (smartphone) gyroscope sensor.

Message

A message of type 'geometry_msgs/Quaternion' that represents the orientation of the smarpthone in free space.

Example

Example of /robot/orientation


/robot/accel

Notifies changes in the robot (smartphone) accelerometer sensor. Only linear acceleration is provided.

Message

A message of type 'geometry_msgs/Accel' where only the 'linear' field is populated with a 'std_msgs/Vector3' message that represents the current linear acceleration of the robot in the three axis.

Example

Example of /robot/accel


/robot/tap

Notifies tap events produced by touching, with one finger, the smartphone touchscreen.

Message

A message of type 'robobo_msgs/Tap' that has two fields:

  • x: A 'std_msgs/Int8' value that represents the coordinate on the x-axis. Coordinates are relative to x-axis of the screen, from 0 (left) to 100 (right).
  • y: A 'std_msgs/Int8' value that represents the coordinate on the y-axis. Coordinates are relative to y-axis of the screen, from 0 (top) to 100 (bottom).

Example

Example of /robot/tap


/robot/fling

Notifies the detection of a drag gesture on the smarpthone touchscreen.

Message

A message of type 'robobo_msgs/Fling' that has three fields:

  • angle: A 'std_msgs/Int16' that represents the angle of the drag. Any integer between 0 and 360.
  • time: A 'std_msgs/Int32' that represents the duration of the drag in milliseconds. Any positive integer.
  • distance: A 'std_msgs/Int16' that represents the drag length measured in pixels. Any positive integer.

Example

Example of /robot/fling


/robot/emotion

Notifies a change in the emotion (face) displayed by the robot.

Message

A message of type 'std_msgs/String' where the 'data' represents the emotion as a string.

Posible values are: happy, laughing, sad, angry, surprised, normal.

Example

Example of /robot/emotion


/robot/camera/image/compressed

Camera images are published in /robot/camera/image/compressed using the compressed_image_transport method. Users can employ these images for processing or to view them in applications such as rqt_image_view or rviz.

Captura de pantalla de 2017-10-26 12-48-11.png

Captura de pantalla de 2017-10-26 12-48-33.png


/robot/unlock/move & /robot/unlock/talk

These two topics, /robot/unlock/move and /robot/unlock/talk are used in combination with /robot/moveWheels, /robot/movePanTilt and /robot/talk services, thus they can't be considered sensor topics.

These topics are used to notify the end of execution of services whose actions may take some time (from milliseconds to even minutes) to complete, like a long movement of the wheels, a long movement of the pan at low speed, or saying a very long "sentence" of text using TTS. In those cases we can associate an unique 'unlockId' to the service call and, when the action finishes, Robobot will notify us by publishing the 'unlockId' in of these topics, depending on the service.

Look for the detailed documentation of each service for more information.

Updated