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.
  • Analog I/O panel: gets commands and sends the current state of analog I/Os.
  • End Effector I/O panel: gets commands and sends the current state of the digital I/Os of the end effector panel on Ned2. Also controls tools like the Electromagnet.
  • Robot fans.
  • Led: sets the LED color.
  • Shutdown Manager: shutdown or reboot the Raspberry.
  • ROS log: can remove all previous logs on start_up to prevent a lack of disk space in the long run (SD cards do not have infinite storage).

It belongs to the ROS namespace: /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 Publishes the current execution state launched when button is pressed
/niryo_robot/blockly/save_current_point std_msgs/Int32 Publishes current point when user is in Blockly page to save block by pressing button
/niryo_robot/rpi/is_button_pressed std_msgs/Bool Publishes the button state (true if pressed)
digital_io_state DigitalIOState Publishes the digital I/Os state by giving for each it’s pin / name / mode / state
analog_io_state AnalogIOState Publishes the analog I/Os state by giving for each it’s pin / name / mode / state
/niryo_robot/rpi/led_state std_msgs/Int8 Publishes the current LED color
ros_log_status LogStatus Publishes 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 Shutdowns the Raspberry Pi
/niryo_robot/rpi/change_button_mode SetInt Changes top button mode (autorun program, blockly, nothing, …)
get_analog_io GetAnalogIO Gets analog IO state list
get_digital_io GetDigitalIO Gets digital IO state list
set_analog_io SetAnalogIO Sets an analog IO to the given value
set_digital_io SetDigitalIO Sets a digital IO to the given value
set_digital_io_mode SetDigitalIO Sets a digital IO to the given mode
set_led_state std_msgs/SetInt Sets LED state
set_led_custom_blinker LedBlinker Sets the LED in blink mode with the color given
purge_ros_logs SetInt Purges ROS log
set_purge_ros_log_on_startup SetInt Modifies the permanent settings that tell if the robot should purge its ROS log at each boot

Services files - Raspberry Pi

ChangeMotorConfig (Service)

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

GetAnalogIO (Service)

string name
---
int32 status
string message

float64 value

GetDigitalIO (Service)

string name
---
int32 status
string message

bool value

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)

string name
bool value

---
int32 status
string message

SetAnalogIO (Service)

string name
float64 value
---
int32 status
string message

SetIOMode (Service)

string name

int8 OUTPUT = 0
int8 INPUT = 1
int8 mode

---
int32 status
string message

SetPullup (Service)

string name
bool enable

---
int32 status
string message

Messages files - Raspberry Pi

AnalogIO

string name
float64 value

AnalogIOState (Topic)

niryo_robot_rpi/AnalogIO[] analog_inputs
niryo_robot_rpi/AnalogIO[] analog_outputs

DigitalIO

string name
bool value

DigitalIOState (Topic)

niryo_robot_rpi/DigitalIO[] digital_inputs
niryo_robot_rpi/DigitalIO[] digital_outputs

LogStatus (Topic)

std_msgs/Header header

# in MB
int32 log_size 
int32 available_disk_size
bool purge_log_on_startup