neo_relayboard_v2-2

Summary

The neo_relayboard_v2 package provides a means to communicate with the physical RelayBoardV2 installed in all mobile platforms.

The neo_relayboard_node publishes status information regarding the mobile platform such as battery voltage, charging current and emergency stop status. Moreover it provides services to control the charging process, the on-demand relays as well as the LCD display.

The drive motors are also connected to the RelayBoardV2 (except MPO-700), hence the drive control commands and drive signals are sent and received over the relayboard_v2_node as well.

Location: https://github.com/neobotix/neo_relayboard_v2-2

neo_relayboard_node

Publishes:

  • /state (neo_msgs2/msg/RelayBoardV2)
  • /battery_state (sensor_msgs/msg/BatteryState)
    • Publishes the battery state of the robot. (Note: Some of the messages such as the battery percentage is applied only for Lithium Batteries and not the AGM batteries)
  • /emergency_stop_state (neo_msgs2/msg/EmergencyStopState)
  • /drives/joint_states (sensor_msgs/msg/joint_states)
    • Publishes the joint_states of the MP-400, MP-500 and MPO-500 robots.
  • /ioboard/data (neo_msgs2/msg/IOBoard) (with IOBoard only)
  • /usboard/measurements (neo_msgs2/msg/USBoard) (with USBoard only)
  • /usboard/sensor (sensor_msgs/msg/Range) (with USBoard only)
    • Publishes the sensor data in sensor_msgs/msg/Range format.

Subscribes:

  • /drives/joinjoint_trajectoryt_states (sensor_msgs/msg/joint_trajectory)
    • Subscribes to the joint_trajectory of neo_kinematics_differential or neo_kinematics_mecanum for executing the joint commands in the motor controller as estimated by the kinematics.
    • Applies only for MP-400, MP-500 (differential) and MPO-500 (Mecanum)

Services:

  • /relayboard_v2/set_LCD_msg (neo_srvs2/srv/RelayBoardSetLCDMsg)
  • /relayboard_v2/set_relay (neo_srvs2/srv/RelayBoardSetRelay)
  • /relayboard_v2/start_charging (std_srvs/srv/Empty)
    • Starts charging process (when connected to automatic charging station)
  • /relayboard_v2/stop_charging (std_srvs/srv/Empty)
    • Stops the charging process (when connected to automatic charging station)
  • /ioboard/set_digital_output

Parameters:

port:
Type Default
string /dev/neo-relayboard
Description

The port that the relayboard_v2 is connected on the Robot PC

request_rate:
Type Default
double 25.0
Description

defines publish frequency as well as frequency of drive commands sent to RelayBoardV2

motor_delay:
Type Default
double 0.0
Description

The motor delay in seconds that needs to be compensated during the joint states estimation

trajectory_timeout:
 
Type Default
double 5.0
Description

The time in seconds after which motors will be stopped if no input is received. If the duration since the last trajectory input exceeds this timeout period, a warning is logged and the motors are stopped to prevent uncontrolled movement

battery.serial_number:
 
Type Default
string “random”
Description

The serial number of the battery

battery.location:
 
Type Default
string “random”
Description

The location of the battery

battery.design_capacity:
 
Type Default
double 50.0
Description

Design capacity of the battery in Ampere-Hour. Will be set by Neobotix according to the battery.

battery.chemistry:
 
Type Default
int 0
Description

Neobotix usually provides either Lithium-Ion or Absorbent Glass Mat batteries. If it is Lithium-Ion, the value will be set to 1. If it is Absorbent Glass Mat battery it will be set to 0. The numbering is based on the sensor_msgs/msg/BatteryState description

ioboard.active:
Type Default
bool false
Description

Set it to True if an IOBoard is connected to the relayboard. After the configuration, please power off the robot and restart the robot, in-order for the relayboard to initilaize and poll data.

usboard.active:
Type Default
bool false
Description

Set it to True if an usboard is connected to the relayboard.

usboard.sensor[n]_active:
 
Type Default
bool false
Description

Depending on the requirements / availablity, set the active sensors.

log:
Type Default
bool false
Description

Set to true if to enable raw binary logging of data stream to file, for debugging

Attention

The entire drive configuration only applies to MP-400, MP-500 and MPO-500

drive2.motor_active:
 
Type Default
bool false
Description

Indicates whether the motor is connected and active.

drive2.homing_active:
 
Type Default
bool false
Description

Indicates whether the homing procedure is active for an omni drive system.

drive2.joint_name:
 
Type Default
string Joint999
Description

The name of the joint, used as the ROS frame_id.

drive2.EncIncrPerRevMot:
 
Type Default
int 0
Description

The number of encoder increments per revolution of the motor.

drive2.VelMeasFrqHz:
 
Type Default
double 0.0
Description

The frequency at which velocity measurements are taken, in Hertz.

drive2.GearRatio:
 
Type Default
double 0.0
Description

The gear ratio of the drive system.

drive2.BeltRatio:
 
Type Default
double 0.0
Description

The belt ratio of the drive system.

drive2.Sign:
Type Default
int 1
Description

The direction of rotation, represented as an integer.

drive2.VelMaxEncIncrS:
 
Type Default
double 0.0
Description

The maximum velocity in encoder increments per second.

drive2.VelPModeEncIncrS:
 
Type Default
double 0.0
Description

The velocity in position mode, in encoder increments per second.

drive2.AccIncrS2:
 
Type Default
double 0.0
Description

The acceleration in encoder increments per second squared.

drive2.DecIncrS2:
 
Type Default
double 0.0
Description

The deceleration in encoder increments per second squared.

drive2.Modulo:
Type Default
double 0.0
Description

The modulo value for the encoder.

Attention

The drive configuration is just an example for one such drive connected to the robot. Please refer an example attached below for a specific type of robot.