Niryo_robot_rpi

This package deals with Raspberry Pi related stuff (Button, fans, I/O, leds, …).

Raspberry Pi Node

The ROS Node manages the following components:

  • Physical top button: executes actions when the button is pressed.
  • Digital I/O panel: gets commands and sends the current state of digital I/Os. Also controls tools like the Electromagnet.
  • Robot fans.
  • Led: sets the LED color.
  • ROS log: can remove all previous logs on startup to prevent a lack of disk space in the long run (SD cards do not have infinite storage).

The namespace used is: /niryo_robot_rpi/

Note that this package should not be used when you are using Ned ROS stack on your computer in simulation mode. Executes actions when the button is pressed.

Publisher - Raspberry Pi

RPI Package’s Publishers
Name Message Type Description
pause_state PausePlanExecution Publish the current execution state launched when button is pressed
/niryo_robot/blockly/save_current_point std_msgs/Int32 Publish current point when user is in Blockly page to save block by pressing button
/niryo_robot/rpi/is_button_pressed std_msgs/Bool Publish the button state (true if pressed)
digital_io_state DigitalIOState Publish the I/Os state by giving for each it’s pin / name / mode / state
/niryo_robot/rpi/led_state std_msgs/Int8 Publish the current led color
ros_log_status LogStatus Publish the current log status (log size / available disk / boolean if should delete ros log on startup)

Services - Raspberry Pi

RPI Services
Name Message Type Description
shutdown_rpi SetInt Shutdown the Raspberry Pi
/niryo_robot/rpi/change_button_mode SetInt Change top button mode (autorun program, blockly, nothing, …)
get_digital_io GetDigitalIO Get digital IO state list
set_digital_io_mode SetDigitalIO Set a digital IO to the mode given
set_digital_io_state SetDigitalIO Set a digital IO to the state given
set_led_state std_msgs/SetInt Set led state
set_led_custom_blinker LedBlinker Set the led in blink mode with the color given
purge_ros_logs SetInt Purge ROS log
set_purge_ros_log_on_startup SetInt Modify the permanent settings that tells if robot should purge it’s ROS log at each boot

Services & Messages files - Raspberry Pi

ChangeMotorConfig (Service)

int32[] can_required_motor_id_list
int32[] dxl_required_motor_id_list
---
int32 status
string message

GetDigitalIO (Service)

int32 pin
---
int32 status
string message

int32 pin
string name
int32 mode
int32 state

LedBlinker (Service)

uint8 LED_OFF = 0
uint8 LED_BLUE = 1
uint8 LED_GREEN = 2
uint8 LED_BLUE_GREEN = 3
uint8 LED_RED = 4
uint8 LED_PURPLE = 5
uint8 LED_RED_GREEN = 6
uint8 LED_WHITE = 7

bool activate
uint8 frequency # between 1hz and 100Hz
uint8 color
float32 blinker_duration # 0 for infinite
---
int32 status
string message

SetDigitalIO (Service)

uint8 pin
uint8 value
---
int32 status
string message

DigitalIOState (Service)

# GPIO pin
int32[] pins
# PIN names seen by user to make it simpler
string[] names
# IN/OUT
int32[] modes
# HIGH/LOW
int32[] states

LogStatus (Service)

std_msgs/Header header

# in MB
int32 log_size 
int32 available_disk_size
bool purge_log_on_startup