<> <> ''ROS Software Maintainer: [[http://wiki.ros.org/ROBOTIS|ROBOTIS]]'' == ROBOTIS e-Manual == * [[http://emanual.robotis.com/docs/en/platform/op3/introduction/|ROBOTIS e-Manual for ROBOTIS-OP3]] == ROS API == {{{ #!clearsilver CS/NodeAPI node.0 { name=op3_gui_demo pub{ 0{ name= robotis/base/ini_pose type= std_msgs/String desc= This message will have ROBOTIS-OP3 to take the initial posture. } 1{ name= robotis/enable_ctrl_module type= std_msgs/String desc= This message notifies framework to activate a specific module for ROBOTIS-OP3. } 2{ name= robotis/sync_write_item type= std_msgs/String desc= This message contains data to be written to ROBOTIS-OP3 with the Sync Write command.<
>ex) LED control } 3{ name= robotis/head_control/set_joint_states type= sensor_msgs/JointState desc= This message controls head joints. } 4{ name= play_sound_file type= std_msgs/String desc= This message contains the path of voice files for speaking. } 5{ name= robotis/walking/command type= std_msgs/String desc= This message commands walking module of ROBOTIS-OP3. } 6{ name= robotis/walking/set_params type= op3_walking_module_msgs/WalkingParam desc= This message configures walking parameters of the walking module. } 7{ name= robotis/action/page_num type= std_msgs/Int32 desc= This message transfers page number to action_module to play actions. } 8{ name= robotis/online_walking/foot_step_command type= op3_online_walking_module_msgs/FootStepCommand desc= walking command for online walking, it contains a direction and some parameters(step time, step number, step length, step angle, leg to walk starting) } 9{ name= robotis/online_walking/walking_param type= op3_online_walking_module_msgs/WalkingParam desc= dsp ratio, limp height, foot height max, zmp offset } 10{ name= robotis/online_walking/footsteps_2d type= op3_online_walking_module_msgs/Step2DArray desc= footsteps for online walking } 11{ name= robotis/online_walking/body_offset type= geometry_msgs/Pose desc= body offset for walking init pose } 12{ name= robotis/online_walking/foot_distance type= std_msgs/Float64 desc= foot distance of walking init pose } 13{ name= robotis/online_walking/wholebody_balance_msg type= std_msgs/String desc= balance command for online walking (balance_on/balance_off) } 14{ name= robotis/online_walking/reset_body type= std_msgs/Bool desc= resets the position of the body to the origin. } 15{ name= robotis/online_walking/goal_joint_pose type= op3_online_walking_module_msgs/JointPose desc= joint pose message for online walking init pose. } 16{ name= robotis/demo/foot_step_marker type= visualization_msgs/MarkerArray desc= marker of footsteps for visualization } } sub{ 0{ name= robotis/status type= robotis_controller_msgs/StatusMsg desc= Message that describes status of action_module. } 1{ name= robotis/present_joint_ctrl_modules type= robotis_controller_msgs/JointCtrlModule desc= This message reports which module is currently in use for ROBOTIS-OP3. } 2{ name= robotis/head_control/present_joint_states type= sensor_msgs/JointState desc= This message reports present angles for each joint. } 3{ name= clicked_point type= geometry_msgs/PointStamped desc= position from rviz ui } } srv_called{ 0{ name= robotis/get_present_joint_ctrl_modules type= robotis_controller_msgs/GetJointModule desc= This is a service to get present module of each joint } 1{ name= plan_footsteps type= humanoid_nav_msgs/PlanFootsteps desc= service to get footsteps using [[http://wiki.ros.org/footstep_planner|footstep_planner]] } } param{ 0{ name= gui_config default= /op3_gui_demo/config/gui_config.yaml type= string desc= This yaml file saves joint names, available modules, list of module preset button. } } } }}}