Contents
ROS Software Maintainer: ROBOTIS
ROBOTIS e-Manual
ROS API
op_demo_node
Subscribed Topics
robotis/open_cr/button (std_msgs/String)- The message in this topic is used to process button control.
- change the mode of op3_demo(ready, soccer, vision, action)
- This message contains IMU data to detect when ROBOTIS-OP3 falls down.
- This message controls soccer demo
- This message contains location and size of the ball.
- This message acquires current head joint states and use them to calculate for goal joint states to look at the ball.
- This message controls vision demo
- This message contains face(s) information from the face_tracking node
- faceCoord[0] : fps
- faceCoord[1] : face size
- faceCoord[2] : image width
- faceCoord[3] : image height
- faceCoord[4] : face id
- faceCoord[5] : face detection length
- faceCoord[6] : face x position(top-left)
- faceCoord[7] : face y position(top-left)
- faceCoord[8] : face width
- faceCoord[9] : face height
- faceCoord[10~15] : information of the second face
- This message contains a face information that ROBOTIS-OP3 will be looking at
Published Topics
robotis/base/ini_pose (std_msgs/String)- The message in this topic is used for initial posture of ROBOTIS-OP3.
- This topic has a message to sync write data on ROBOTIS-OP3
ex) LED controls
- The message in this topic contains path of the voice file for verbal announcement.
- message to torque on of ROBOTIS-OP3
- This message configures joint control modules to operate ROBOTIS-OP3.
- This message configures control modules to operate ROBOTIS-OP3.
- This message transfers page number to action_module to initiate actions such as kicking, standing up.
- This message informs head_control_module about joint state offset to look at the ball that is detected in the image.
- This message commands OP3 to look around for searching a ball.
- This message commands walking module of OP3 to walk toward the ball.
- This message configures walking parameters in the walking module to follow the ball.
- This message commands face_tracking node to enable the tracking process or not.
Services Called
robotis/set_present_joint_ctrl_modules (robotis_controller_msgs/SetJointModule)- This service configures joint control modules to operate ROBOTIS-OP3.
- This service acquires walking parameters
- This service checks whether the action is running or not.
Parameters
gui_config (string, default: ~/op3_gui_demo/config/gui_config.yaml)- This yaml file saves joint names, available modules, list of module preset button.
- This yaml file contains list of action and audio file bundles.