ROS Software Maintainer: ROBOTIS

ROBOTIS e-Manual

ROS API

op3_gui_demo

Subscribed Topics

robotis/status (robotis_controller_msgs/StatusMsg)
  • Message that describes status of action_module.
robotis/present_joint_ctrl_modules (robotis_controller_msgs/JointCtrlModule)
  • This message reports which module is currently in use for ROBOTIS-OP3.
robotis/head_control/present_joint_states (sensor_msgs/JointState)
  • This message reports present angles for each joint.
clicked_point (geometry_msgs/PointStamped)
  • position from rviz ui

Published Topics

robotis/base/ini_pose (std_msgs/String)
  • This message will have ROBOTIS-OP3 to take the initial posture.
robotis/enable_ctrl_module (std_msgs/String)
  • This message notifies framework to activate a specific module for ROBOTIS-OP3.
robotis/sync_write_item (std_msgs/String)
  • This message contains data to be written to ROBOTIS-OP3 with the Sync Write command.
    ex) LED control
robotis/head_control/set_joint_states (sensor_msgs/JointState)
  • This message controls head joints.
play_sound_file (std_msgs/String)
  • This message contains the path of voice files for speaking.
robotis/walking/command (std_msgs/String)
  • This message commands walking module of ROBOTIS-OP3.
robotis/walking/set_params (op3_walking_module_msgs/WalkingParam)
  • This message configures walking parameters of the walking module.
robotis/action/page_num (std_msgs/Int32)
  • This message transfers page number to action_module to play actions.
robotis/online_walking/foot_step_command (op3_online_walking_module_msgs/FootStepCommand)
  • walking command for online walking, it contains a direction and some parameters(step time, step number, step length, step angle, leg to walk starting)
robotis/online_walking/walking_param (op3_online_walking_module_msgs/WalkingParam)
  • dsp ratio, limp height, foot height max, zmp offset
robotis/online_walking/footsteps_2d (op3_online_walking_module_msgs/Step2DArray)
  • footsteps for online walking
robotis/online_walking/body_offset (geometry_msgs/Pose)
  • body offset for walking init pose
robotis/online_walking/foot_distance (std_msgs/Float64)
  • foot distance of walking init pose
robotis/online_walking/wholebody_balance_msg (std_msgs/String)
  • balance command for online walking (balance_on/balance_off)
robotis/online_walking/reset_body (std_msgs/Bool)
  • resets the position of the body to the origin.
robotis/online_walking/goal_joint_pose (op3_online_walking_module_msgs/JointPose)
  • joint pose message for online walking init pose.
robotis/demo/foot_step_marker (visualization_msgs/MarkerArray)
  • marker of footsteps for visualization

Services Called

robotis/get_present_joint_ctrl_modules (robotis_controller_msgs/GetJointModule)
  • This is a service to get present module of each joint
plan_footsteps (humanoid_nav_msgs/PlanFootsteps)

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.

Wiki: op3_gui_demo (last edited 2018-04-04 05:57:52 by Gilbert)