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.
robotis/mode_command (std_msgs/String)
  • change the mode of op3_demo(ready, soccer, vision, action)
robotis/open_cr/imu (sensor_msgs/Imu)
  • This message contains IMU data to detect when ROBOTIS-OP3 falls down.
ball_tracker/command (std_msgs/String)
  • This message controls soccer demo
ball_detector_node/circle_set (ball_detector/circleSetStamped)
  • This message contains location and size of the ball.
robotis/goal_joint_states (sensor_msgs/JointState)
  • This message acquires current head joint states and use them to calculate for goal joint states to look at the ball.
face_tracker/command (std_msgs/String)
  • This message controls vision demo
faceCoord (std_msgs/Int32MultiArray)
  • 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
face_position (geometry_msgs/Point)
  • 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.
robotis/sync_write_item (std_msgs/String)
  • This topic has a message to sync write data on ROBOTIS-OP3
    ex) LED controls
play_sound_file (std_msgs/String)
  • The message in this topic contains path of the voice file for verbal announcement.
robotis/dxl_torque (std_msgs/String)
  • message to torque on of ROBOTIS-OP3
robotis/set_joint_ctrl_modules (robotis_controller_msgs/JointCtrlModule)
  • This message configures joint control modules to operate ROBOTIS-OP3.
robotis/enable_ctrl_module (std_msgs/String)
  • This message configures control modules to operate ROBOTIS-OP3.
robotis/action/page_num (std_msgs/Int32)
  • This message transfers page number to action_module to initiate actions such as kicking, standing up.
robotis/head_control/set_joint_states_offset (sensor_msgs/JointState)
  • This message informs head_control_module about joint state offset to look at the ball that is detected in the image.
robotis/head_control/scan_command (std_msgs/String)
  • This message commands OP3 to look around for searching a ball.
robotis/walking/command (std_msgs/String)
  • This message commands walking module of OP3 to walk toward the ball.
robotis/walking/set_params (op3_walking_module_msgs/WalkingParam)
  • This message configures walking parameters in the walking module to follow the ball.
face_tracking/command (std_msgs/Bool)
  • 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.
robotis/walking/get_params (op3_walking_module_msgs/GetWalkingParam)
  • This service acquires walking parameters
robotis/action/is_running (op3_action_module_msgs/IsRunning)
  • 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.
action_script (string, default: ~/op3_demo/list/action_script.yaml)
  • This yaml file contains list of action and audio file bundles.

Wiki: op3_demo (last edited 2018-04-04 06:00:18 by Gilbert)