Package Summary

sensehat_ros is a ROS package to interact with Astro Pi Sense HAT sensors, stick and LED matrix.

Package Summary

sensehat_ros is a ROS package to interact with Astro Pi Sense HAT sensors, stick and LED matrix.

Astro PI Sense HAT

Overview

The sensehat_ros ROS package helps integrating the Astro Pi Sense HAT module with the ROS ecosystem. Stick events together with environmental and IMU sensors data are published to ROS topics. Several ROS services are exposed to interact with the device, including the LED matrix.

The package has been tested on Melodic Python 2 and Noetic Python 3 environments. ROS 2 support is on the roadmap, any help would be appreciated. Deployment tests with the Sense HAT device were successfully run on different Raspberry PI models (Pi 2, Pi 3 and Pi 4), either installing ROS on the Raspberry Pi OS or using Docker via the Balena Cloud platform.

Thanks to the sense-emu Python package, the sensehat_ros package can be run without the actual Sense HAT device on several Linux configs. Simulated deployments were tested on x86 Ubuntu Bionic and Debian Buster (via WSL 2) and with Docker on both x86 and QEMU-based arm32v7.

The Sense HAT Emulator GUI can be easily started with the sense_emu_gui command.

debug level log output

Setup

The sensehat_ros package is intended to be installed on a Raspberry PI device equipped with an Astro Pi Sense HAT module and with a supported ROS distro. Binary release is not an option with pip dependencies in the package.xml, so the package have to be built and installed from source.

$ mkdir ~/catkin_ws
$ cd ~/catkin_ws
$ wstool init src
$ wstool set -t src sensehat_ros https://github.com/allxone/sensehat_ros.git --git --version=master
$ wstool up -t src
$ rosdep update
$ rosdep install --from-paths src --ignore-src -r -y
$ catkin_make
$ catkin_make install

Please, follow the Code API documentation link for additional details about building and testing the package.

Usage

Test run

To verify if the sensehat_ros ROS package is working properly a ROS node can be started with a modified logging level.

$ source install/setup.bash
$ roslaunch --screen -v sensehat_ros sensehat_ros.launch DEBUG:=True

The onscreen log output should present sensor data coming from the device (or the emulator): debug level log output

Examples

The package includes two sample client nodes to show how to call services interactively or consume messages from topics.

# Assuming "roslaunch sensehat_ros sensehat_ros.launch" already running in another shell
$ source install/setup.bash

# Example 1: invoking sensehat_ros ROS services
$ rosrun sensehat_ros sample_client
Received Environmental (H: 39.73828125, TH: 20.9375, TP: 20.9520833333, P: 995.614257812)
Reset the Matrix to white
Show some random pixel colors
Reset the Matrix to black

# Example 2: consuming sensehat_ros topics
$ rosrun sensehat_ros sample_listener
[INFO] [1597358715.590474]: Heard Environmental (H: 39.2265625, TH: 20.90625, TP: 20.8791666667, P: 995.602294922)
[INFO] [1597358715.597447]: Heard IMU (Mode: get_orientation_degrees_rpy, X: 67.4909682543, Y: 0.0, Z: 82.490182137)
[INFO] [1597358716.590834]: Heard IMU (Mode: get_orientation_degrees_rpy, X: 67.4909682543, Y: 0.0, Z: 82.490182137)
[INFO] [1597358717.590532]: Heard IMU (Mode: get_orientation_degrees_rpy, X: 67.4909682543, Y: 0.0, Z: 82.490182137)
^C

ROS API

sensehat_ros

ROS node hosting the interface to the Sense HAT API

Published Topics

Environmental (sensehat_ros/Environmental)
  • Sense HAT Environmental sensors data (i.e. humidity, temperature and pressure)
IMU (sensehat_ros/IMU)
  • Sense HAT IMU sensor data (e.g. pitch, roll, yaw).
Stick (sensehat_ros/Stick)
  • Sense HAT Stick events

Services

Clear (sensehat_ros/Clear)
  • Sets all of the 64 LED matrix pixels to the specified RGB color and waits for the specified amount of seconds.
EmulateStick (sensehat_ros/EmulateStick)
  • Remotely triggers a stick event without interacting with the Stick device.
GetCompass (sensehat_ros/)
  • Gets the direction of North from the magnetometer in degrees. Warning: not allowed when imu_publishing=True due to potential set_imu_config interference.
GetEnvironmental (sensehat_ros/GetEnvironmental)
  • gets the current humidity and temperature from the humidity sensor and temperature and pressure from the pressure sensor
GetHumidity (sensehat_ros/GetHumidity)
  • Gets the percentage of relative humidity from the humidity sensor.
GetIMU (sensehat_ros/GetIMU)
  • Queries Sense HAT IMU sensor. Warning: not allowed when imu_publishing=True due to potential set_imu_config interference.
GetPressure (sensehat_ros/GetPressure)
  • Gets the current pressure in Millibars from the pressure sensor.
GetTemperature (sensehat_ros/GetTemperature)
  • Gets the current temperature in degrees Celsius from the humidity sensor.
SetPixels (sensehat_ros/SetPixels)
  • Sets each of the 64 LED matrix pixels to a specific RGB color and waits for the specified amount of seconds.
ShowLetter (sensehat_ros/ShowLetter)
  • Shows a letter on the LED matrix and waits for the specified amount of seconds.
ShowMessage (sensehat_ros/ShowMessage)
  • Scrolls a text message from right to left across the LED matrix and at the specified speed, in the specified colour and background colour.
SwitchLowLight (sensehat_ros/SwitchLowLight)
  • Switches on/off the LED matrix “low light” mode and returns the current state.

Parameters

rotation (int, optional, default: 0)
  • control Sense HAT LED matrix orientation
low_light (bool, optional, default: False)
  • enable Sense HAT low-light mode
calibration (dict, optional, default: {})
  • linear fixing for environmental readings (ex. {"humidity": -20.0})
smoothing (int, optional, default: 0)
  • number of observations to be used for median smoothing (0 = smoothing disabled)
register_services (bool, optional, default: True)
  • control ROS services registration
environmental_publishing (bool, optional, default: True)
  • enable automatic publishing of environmental data (rate controlled by environmental_publishing_rate)
environmental_publishing_rate (float, optional, default: 12)
  • environmental data publication frequency in seconds
IMU_publishing (bool, optional, default: False)
  • enable automatic publishing of IMU data (rate controlled by imu_publishing_rate)
imu_publishing_mode (string, optional, default: get_orientation_degrees_rpy)
  • specify the Sense HAT API function to be used to get x,y,z/roll,pitch,yaw. Valid values are: get_orientation_radians_rpy, get_orientation_degrees_rpy, get_compass_raw_xyz, get_gyroscope_rpy, get_gyroscope_raw_xyz, get_accelerometer_rpy, get_compass_raw_xyz
imu_publishing_rate (float, optional, default: 1)
  • IMU data publication frequency in seconds
stick_publishing (bool, optional, default: True)
  • enable publishing of stick events
stick_sampling (float, optional, default: 0.2)
  • indicates how frequently the Stick is checked for new events

Wiki: sensehat_ros (last edited 2020-08-19 12:43:10 by allxone)