Skip to content

Publishing the current state of the robot (Topic)

Publish robot state information to the /gbt_driver/feedback_states Topic. Includes connection status of the robotic arm, robot status, controller status, servo status, robotic arm soft mode status, robotic arm joint status, end-effector pose, robot alarm codes, and speed percentage. Subscribe to this topic to obtain real-time status information of the robotic arm. Topic message structure is as follows:

Message Structure

gbt_interface/msg/FeedbackState.msg

The following is the message structure for robotic arm status information:

yaml
std_msgs/Header header

# Connection Status
bool is_connected                            # Whether connected to the robot

# Robot Status
string robot_type                            # Robot type
RobotStatus robot_status                     # Robot Status
ControllerStatus controller_status           # Controller Status
ServoStatus servo_status                     # Servo Status
ArmSoftModeStatus arm_soft_mode_status       # Arm Soft Mode Status

# Robot joint 
sensor_msgs/JointState joint_states          # Robot joint states
geometry_msgs/PoseStamped flange_pose        # Robot flange pose
geometry_msgs/PoseStamped tool_pose          # Robot tool pose

# alarm code 
AlarmCode[]   alarm_code_list                # Robot alarm code

float32 overall_speed                        # Overall speed (%)


# IO
IOType[] io                                  # TODO: IO status

bool is_error                                # TODO: implement error detection
uint8 error_code                             # TODO: assign proper error codes on failures


# coordinate system
int32 actived_uf_id                          # Activated user coordinate system ID
int32 actived_tf_id                          # Activated tool coordinate system ID

User Guide

Set Robotic Arm IP Address

Modify the robotic arm's IP address in the gbt_driver/config/robot_config.yaml configuration file.

yaml
robot_ip_address: "10.27.1.254"  # Please fill in the robotic arm's IP address according to actual conditions

Start ROS2 Driver Node

Launch the gbt_driver node in the terminal:

bash
source install/setup.bash
ros2 launch gbt_driver gbt_feedback.launch.py

Obtain Robotic Arm Status Information

After starting the gbt_driver node, the driver will automatically connect to the robotic arm and begin publishing status information to the following Topic:

  • /gbt_driver/feedback_states

By subscribing to this topic, you can obtain the following information:

  • Robotic arm connection status
  • Robot status
  • Controller status
  • Servo status
  • Robotic arm soft mode status
  • Robotic arm joint status
  • End-effector pose
  • Robot alarm codes
  • Speed percentage
  • UF coordinate system ID
  • TF coordinate system ID

For example, you can use the following command to view the robotic arm's status information:

bash
source install/setup.bash
ros2 topic echo /gbt_driver/feedback_states