Niryo_robot_status¶
Robot status Node¶
The ROS Node is listening to the topics of the robot to deduce the current state of the robot. It manages the status of the robot, the status of the logs and informs about the overheating of the Raspberry PI and the out of limit joints.
It belongs to the ROS namespace: /niryo_robot_status/
.
Name | Description | Troubleshoot |
---|---|---|
SHUTDOWN |
The robot is being shut down | |
FATAL_ERROR |
ROS crash | Please restart the robot |
MOTOR_ERROR |
Motor voltage error, overheating, overload | Check the error code on Niryo Studio.
Restart the robot and check the wiring.
If the problem persists, contact customer service
|
COLLISION |
Arm collision detected | Restart your movement or switch to learning mode to remove this error. |
USER_PROGRAM_ERROR |
User program error | Launch a movement or switch to learning mode to remove this error. |
UNKNOWN |
Node not initialized | |
BOOTING |
ROS a and the Raspberry are booting up | If the startup seems to timeout, restart the robot electrically.
If the problem persists, update the robot with ssh,
change the SD card or contact customer service.
|
UPDATE |
Robot update in progress | Just wait and be patient :) |
CALIBRATION_NEEDED |
New calibration requested | Run a new calibration before processing any movement. |
CALIBRATION_IN_PROGRESS |
Calibration in progress | If the calibration fails or takes longer than 30 seconds.
The status will return to
CALIBRATION_NEED. |
LEARNING_MODE |
Free motion enabled, the torques are disabled | |
STANDBY |
Free motion disabled, the torques are enabled
and no user program is running
|
|
MOVING |
A single motion or jog is being processed
and no user program is running
|
|
RUNNING_AUTONOMOUS |
A user program is running and the torques are enabled | |
RUNNING_DEBUG |
A debug procedure is running | A short press on the top button cancels it. |
PAUSE |
User program error | A short press on the top button resumes the program,
a long press (on Ned2) or a double press (on Ned and One)
cancels the program execution.
After 30 seconds, the program stops automatically.
|
LEARNING_MODE_AUTONOMOUS |
A user program is running and the torques are disabled |
Publisher - Robot Status¶
Name | Message Type | Latch Mode | Description |
---|---|---|---|
/niryo_robot_status/robot_status |
RobotStatus | True |
Publish the robot, log, overheating and out of bounds status. |
Services - Robot Status¶
Name | Message Type | Description |
---|---|---|
/niryo_robot_status/advertise_shutdown |
Trigger | Notify of a shutdown request |
Subscribers - Robot Status¶
Topic name | Message type | Description |
---|---|---|
/niryo_robot_hardware_interface/hardware_status |
HardwareStatus | Detection of a motor or end effector panel error, raspberry overheating |
niryo_robot_rpi/pause_state |
PausePlanExecution | Detection of the pause state |
/niryo_robot_arm_commander/is_active |
std_msgs/Bool | Detection of a motion |
/niryo_robot_arm_commander/is_debug_motor_active |
std_msgs/Bool | Detection of a debug procedure |
/niryo_robot/jog_interface/is_enabled |
std_msgs/Bool | Detection of a jog motion |
/niryo_robot_programs_manager/program_is_running |
ProgramIsRunning | Detection of a user program |
/niryo_robot_user_interface/is_client_connected |
std_msgs/Bool | Detection of a pyniryo user |
/niryo_robot/learning_mode/state |
std_msgs/Bool | Detection of the free motion mode |
/niryo_robot_arm_commander/collision_detected |
std_msgs/Bool | Detection of collision |
/joint_states |
sensor_msgs/JointState | Get the joint state in order to detect an out of bounds |
/ping_pyniryo |
std_msgs/Bool | Detection of a pyniryo2 user |
Dependencies - Robot Status¶
Messages files - Robot Status¶
RobotStatus¶
int8 UPDATE=-7
int8 REBOOT=-6
int8 SHUTDOWN=-5
int8 FATAL_ERROR=-4 # Node crash
int8 MOTOR_ERROR=-3 # Electrical/overload or disconnected motor error
int8 COLLISION=-2
int8 USER_PROGRAM_ERROR=-1
int8 UNKNOWN=0
int8 BOOTING=1 # Robot is booting
int8 REBOOT_MOTOR=2
int8 CALIBRATION_NEEDED=3
int8 CALIBRATION_IN_PROGRESS=4
int8 LEARNING_MODE=5
int8 STANDBY=6 # Torque ON
int8 MOVING=7 # Moving with NiryoStudio interface or ros topics without user program
int8 RUNNING_AUTONOMOUS=8 # User program is running
int8 RUNNING_DEBUG=9 # Debug program is running
int8 PAUSE=10 # User program paused
int8 LEARNING_MODE_AUTONOMOUS=11 # User program is running + Learning mode activated
int8 LEARNING_TRAJECTORY = 12
int8 REBOOT_MOTOR=13
int8 robot_status
string robot_status_str
string robot_message
int8 FATAL=-3
int8 ERROR=-2
int8 WARN=-1
int8 NONE=0
int8 logs_status
string logs_status_str
string logs_message
bool out_of_bounds
bool rpi_overheating