neo_relayboard_v3

Summary

The RelayBoardV3 is a small, compact yet powerful microprocessor deployed on our ROX platforms. The RelayBoardV3 is the central hub for all the sensors and actuators on the platform.

The RelayBoardV3 is responsible for the following functionalities:

  • All the motion commands from ROS to the motor controllers are sent through the relayboardv3_node
  • Provides the necessary interface for
    • reading the joint states
    • switching the different pre-configured safety fields on the flexisoft
    • starting and stopping the charging process (not for wired charging)
    • enabling and disabling the onboard digital outputs
    • enabling and disabling the relays
    • reading the battery voltage and current
    • controlling the onboard LEDs
    • reading the Ultrasonic sensor data from the new generation USBoard
    • reading the key switch state
    • reading the emergency stop state
    • reading the platforms ambient temperature
    • reading the possible hardware system errors

Location: https://github.com/neobotix/neo_relayboard_v3

relayboardv3_node

Note

This documentation contains the updates for the version 0.5.0. If you would like to update the version of your Beaglebone, please write to us directly.

The relayboardv3_node is the main and the only node of this ROS 2 package.

Subscribes:
  • /drive/joint_trajectory (trajectory_msgs/JointTrajectory)
    • The joint trajectory to be executed
  • /kinematics_state (neo_msgs2/KinematicsState)
    • The kinematics state of the robot
Publishes:
  • /drive/joint_states (sensor_msgs/JointState)
    • The joint states of the robot
  • /emergency_stop_state (neo_msgs2/EmergencyStopState)
    • The emergency stop state of the robot
  • /battery_state (neo_msgs2/BatteryState)
    • The battery state of the robot
  • /safety_state (neo_msgs2/SafetyState)
    • The flexisoft state of the robot
  • /relayboard_v3/state (neo_msgs2/RelayBoardV3)
    • Provides the state of the relayboards auxillary components which includes the digital inputs, relays, LEDs, key switch, and the temperature sensor
  • /ioboard/data (neo_msgs2/IOBoardData)
    • Provides the state of the IOBoard
  • /usboard/measurements (neo_msgs2/USBoardV2)
    • Provides the data of the Ultrasonic sensors connected to the USBoard
Services:
  • /set_relay (neo_srvs2/ReayBoardSetRelay)
    • Enables or disables the relays
  • /ioboard/set_digital_output (neo_srvs2/IOBoardSetDigitalOutput)
    • Enables or disables the digital outputs
  • /start_charging (std_srvs/Empty)
    • Starts the charging process (not for wired charging)
  • /stop_charging (std_srvs/Empty)
    • Stops the charging process (not for wired charging)
  • /set_safety_field (neo_srvs2/SetSafetyField)
    • Switches the currently active safety field to the one with the given ID. Use field_id = 0 to disable or revert to preset
  • /shutdown_platform (std_srvs/Empty)
    • Does a complete shutdown of the robot
  • /set_safety_mode (neo_srvs2/RelayboardSetSafetyMode)
    • Allows you to switch between the different pre-configured safety modes on the flexisoft using the neo_msgs2/SafetyMode

Parameters:

Note

Depending on the batteries and wallbox, please adjust the parameters in /home/neobotix/ros2_workspace/src/rox/rox_bringup/configs/neo_relayboard_v3/relayboard_v3.yaml of your ROX robots.

board_node:
Type Default
string 192.168.1.80:5554
Description

Specifies the IP address and port of the relayboard for communication.

pilot_config:
Type Default
string /home/neobotix/ros2_workspace/src/neo_relayboard_v3/config/default/rox-argo
Description

The path to the configuration file for the pilot module, likely specific to the robot model (e.g., rox-argo).

agm_batteries_config:
 
Type Default
string /home/neobotix/ros2_workspace/src/neo_relayboard_v3/config/addons/agm-batteries
Description

The path to the configuration file for AGM batteries.

lfp_batteries:
Type Default
bool False
Description

A boolean flag to enable or disable the configuration for Lithium Iron Phosphate (LFP) batteries. Set to True if you have LFP Batteries.

lfp_batteries_config:
 
Type Default
string /home/neobotix/ros2_workspace/src/neo_relayboard_v3/config/addons/lfp-batteries
Description

The path to the configuration file for LFP batteries, only used when lfp_batteries is True.

use_multipowr:
Type Default
bool False
Description

A boolean flag to enable or disable the configuration for the Multipowr wallbox/smart charger. Set to True if you have a wallbox.

multipowr_config:
 
Type Default
string /home/neobotix/ros2_workspace/src/neo_relayboard_v3/config/addons/smart-charger
Description

The path to the configuration file for the Multipowr smart charger, only used when use_multipowr is True.

Building the package

Once the relevant ROS Distribution is sourced, please follow the steps in a terminal:

Initialize the associated submodules

cd your_colcon_workspace/src/neo_relayboard_v3
git submodule update --init

Install the vnx_base

sudo dpkg -i vnx-base/x86_64/vnx-base-1.9.6-x86_64-ubuntu-22.04.deb
cd your_colcon_workspace
colcon build --symlink-install
. install/setup.bash