RobotState.msg
Features
Topic message of robot state.
Parameters
Parameter Name | Data Type | Default Value | Description |
---|---|---|---|
robot_state | int32 |
| Robot State : enum.ROBOT_STATE |
robot_state_str | string |
| Output robot status as string |
actual_mode | int8 |
| Robot Control Mode: enum.CONTROL_MODE |
actual_space | int8 |
| Robot Control Space: enum.ROBOT_SPACE |
current_posj | float64[6] |
| 6 current joint angle |
joint_abs | float64[6] |
| 6 current joint angle(Absolute Encorder) |
current_velj | float64[6] |
| 6 current joint velocity |
joint_err | float64[6] |
| 6 current joint error |
target_posj | float64[6] |
| 6 target joint angle |
target_velj | float64[6] |
| 6 target joint velocity |
current_posx | float64[6] |
| 6 current task position |
current_tool_posx | float64[6] |
| 6 current flange position |
current_velx | float64[6] |
| 6 current task velocity |
task_err | float64[6] |
| 6 current task error |
target_posx | float64[6] |
| 6 target task position |
target_velx | float64[6] |
| 6 target task velocity |
solution_space | int8 |
| solution space(0~7) |
rotation_matrix | std_msgs/Float64MultiArray[] |
| Rotation matrix: float[3][3] |
dynamic_tor | float64[6] |
| 6 dynamic torque |
actual_jts | float64[6] |
| 6 joint torque sensor data |
actual_ejt | float64[6] |
| 6 current joint axis external force |
actual_ett | float64[6] |
| 6 current Task-based external forces |
actual_w2b | float64[6] |
| Position deviation between 6 World and Base coordinate systems This argument is only available in M2.50 and higher versions. |
current_posw | std_msgs/Float64MultiArray[] |
| 6 current task position based on world coordinate system This argument is only available in M2.50 and higher versions. |
current_velw | float64[6] |
| 6 current task velocity based on world coordinate system This argument is only available in M2.50 and higher versions. |
world_ett | float64[6] |
| 6 external force based on world coordinate system This argument is only available in M2.50 and higher versions. |
target_posw | float64[6] |
| 6 target task position based on world coordinate system This argument is only available in M2.50 and higher versions. |
target_velw | float64[6] |
| 6 target task velocity based on world coordinate system This argument is only available in M2.50 and higher versions. |
rotation_matrix_world | std_msgs/Float64MultiArray[] |
| Rotation matrix based on world coordinate system: float[3][3] This argument is only available in M2.50 and higher versions. |
actual_UCN | int8 |
| User coordinate ID information(101 ~ 200) This argument is only available in M2.50 and higher versions. |
parent | int8 |
| Parent coordinate of current user coordinate system This argument is only available in M2.50 and higher versions. |
current_posu | float64[6] |
| 6 current task position based on user coordinate system This argument is only available in M2.50 and higher versions. |
current_velu | float64[6] |
| 6 current task velocity based on user coordinate system This argument is only available in M2.50 and higher versions. |
user_ett | float64[6] |
| 6 external force based on user coordinate system This argument is only available in M2.50 and higher versions. |
target_posu | float64[6] |
| 6 target task position based on user coordinate system This argument is only available in M2.50 and higher versions. |
target_velu | float64[6] |
| 6 target task velocity based on user coordinate system This argument is only available in M2.50 and higher versions. |
rotation_matrix_user | std_msgs/Float64MultiArray[] |
| Rotation matrix based on user coordinate system: float[3][3] This argument is only available in M2.50 and higher versions. |
sync_time | int8 |
| Internal clock count |
flange_digital_output | int8[6] |
| 6 flange digital output |
flange_digital_input | int8[6] |
| 6 Flange Digital Input |
actual_bk | int8[6] |
| 6 break state |
actual_bt | int8[5] |
| 5 robot button information |
actual_mc | float64[6] |
| Current consumption of 6 motors |
actual_mt | float64[6] |
| 6 inverter temperature information |
ctrlbox_digital_input | int8[6] |
| 16 control boxes digital intput information |
actual_ai | int8[2] |
| 2 Analog Input numeric information |
actual_sw | int8[3] |
| 3 switch state |
actual_si | int8[2] |
| 2 safety input state |
actual_at | int8[2] |
| 2 analog input type information This argument is only available in M2.50 and higher versions. |
ctrlbox_digital_output | int8[16] |
| 16 control box digital output information |
target_ao | float64[2] |
| 2 Analog Output numeric information |
target_at | int8[2] |
| 2 analog output type information This argument is only available in M2.50 and higher versions. |
actual_es | int8[2] |
| 2 Encorder state information This argument is only available in M2.50 and higher versions. |
actual_ed | int8[2] |
| 2 Encorder Raw data numerical information |
actual_er | int8[2] |
| 2 Encorder Reset status information This argument is only available in M2.50 and higher versions. |
modbus_state | ModbusState[] |
| Modbus State : See ModbusState.msg |
access_control | int32 |
| Control state: See enum.ACCESS_CONTROL |
homming_completed | bool |
| Whether the robot is homing |
tp_initialized | bool |
| TP initialization state |
mastering_need | int8 |
| Whether robot mastering is required |
drl_stopped | bool |
| DRL (Doosan Robot Language) standstill |
disconnected | bool |
| communication connection status |
enum.ROBOT_STATE
Num | Name | Description |
---|---|---|
0 | STATE_INITIALIZING | It is an initialization state for setting various parameters by automatically entering by TP application. |
1 | STATE_STANDBY | Operable Standby state. |
2 | STATE_MOVING | It is a command operation state that is automatically switched when the command is received after receiving the command in the command wait state. When the operation is completed, it is switched to the auto command waiting state. |
3 | STATE_SAFE_OFF | Robot stop mode due to function and operation error, Servo off state (motor and brake power are cut off after control stop) |
4 | STATE_TEACHING | Direct teaching state |
5 | STATE_SAFE_STOP | Robot stop mode due to function and operation error. Safe stop status (status in which only the control is stopped, program suspended status in the automatic mode) |
6 | STATE_EMERGENCY_STOP | Emergency stop state |
7 | STATE_HOMMING | Homing mode state (state in which robot is aligned in hardware). |
8 | STATE_RECOVERY | When the robot is stopped due to an error such as exceeding the robot driving range, it is in the recovery mode state to move within the driving range. |
9 | eSTATE_SAFE_STOP2 | Same as eSTATE_SAFE_STOP but a state that must be switched to recovery mode because the robot is out of range |
10 | STATE_SAFE_OFF2 | Same as eSTATE_SAFE_OFF state, but must be in recovery mode due to exceeding the robot drive range |
11 | STATE_RESERVED1 | reserved |
12 | STATE_RESERVED2 | reserved |
enum.CONTROL_MODE
Num | Name | Description |
---|---|---|
0 | CONTROL_MODE_POSITION | Position control mode |
1 | CONTROL_MODE_TORQUE | Torque control mode |
enum.ROBOT_STATE
Num | Name | Description |
---|---|---|
0 | ROBOT_SPACE_JOINT | Joint space |
1 | ROBOT_SPACE_TASK | Task Space |
enum.ACCESS_CONTROL
Num | Name | Description |
---|---|---|
0 | MANAGE_ACCESS_CONTROL_FORCE_REQUEEST | Control forced release message transmission |
1 | MANAGE_ACCESS_CONTROL_REQUEST | Send control request message |
2 | MANAGE_ACCESS_CONTROL_RESPONSE_YES | Send control authorization request acknowledge message |
3 | MANAGE_ACCESS_CONTROL_RESPONSE_NO | Send control permission request decline message |