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 Location: https://github.com/neobotix/neo_relayboard_v3 relayboardv3_node ----------------- The relayboardv3_node is the main and the only node of this ROS 2 package. Subscribes: * /joint_trajectory **(trajectory_msgs/JointTrajectory)** - The joint trajectory to be executed * /kinematics_state **(neo_msgs2/KinematicsState)** - The kinematics state of the robot Publishes: * /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