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.
neo_relayboard_node¶
Publishes:
- /state (neo_msgs2/msg/RelayBoardV2)
- Publishes the relayboard state. More details on RelayBoardV2.msg
- /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)
- Publishes the status of the emergency stop of the robot. More details on EmergencyStopState.msg
- /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)
- Publishes the IOBoard data. More details on IOBoard.msg
- /usboard/measurements (neo_msgs2/msg/USBoard) (with USBoard only)
- Publishes the raw sensor data for the Usboard More details on USBoard.msg
- /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)
- Sets the first line on the LCD display for the next 30 seconds. More details on RelayBoardSetLCDMsg.srv
- /relayboard_v2/set_relay (neo_srvs2/srv/RelayBoardSetRelay)
- <id (0 to 3)> <true/false>
- Controls the 4 on-demand relays. More details on RelayBoardSetRelay.srv
- /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
- <id (0 to 15)> <true/false>
- Controls the 16 digital outputs, when IOBoard is connected. More details on IOBoardSetDigOut.srv
Parameters:
port: |
|
||||
---|---|---|---|---|---|
request_rate: |
|
||||
motor_delay: |
|
||||
trajectory_timeout: | |||||
|
|||||
battery.serial_number: | |||||
|
|||||
battery.location: | |||||
|
|||||
battery.design_capacity: | |||||
|
|||||
battery.chemistry: | |||||
|
|||||
ioboard.active: |
|
||||
usboard.active: |
|
||||
usboard.sensor[n]_active: | |||||
|
|||||
log: |
|
Attention
The entire drive configuration only applies to MP-400, MP-500 and MPO-500
drive2.motor_active: | |||||
---|---|---|---|---|---|
|
|||||
drive2.homing_active: | |||||
|
|||||
drive2.joint_name: | |||||
|
|||||
drive2.EncIncrPerRevMot: | |||||
|
|||||
drive2.VelMeasFrqHz: | |||||
|
|||||
drive2.GearRatio: | |||||
|
|||||
drive2.BeltRatio: | |||||
|
|||||
drive2.Sign: |
|
||||
drive2.VelMaxEncIncrS: | |||||
|
|||||
drive2.VelPModeEncIncrS: | |||||
|
|||||
drive2.AccIncrS2: | |||||
|
|||||
drive2.DecIncrS2: | |||||
|
|||||
drive2.Modulo: |
|
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.