<> <> ''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_manager pub{ 0{ name= robotis/status type= robotis_controller_msgs/StatusMsg desc= Message that describes status of action_module. } 1{ name= robotis/base/ini_pose type= std_msgs/String desc= message to let ROBOTIS-OP3 go init pose. } } sub{ 0{ name= robotis/open_cr/button type= std_msgs/String desc= If the user button is pressed above 2 secs, ROBOTIS-OP3 will be torque on and go to init pose. } 1{ name= robotis/dxl_torque type= std_msgs/String desc= torque on command } } param{ 0{ name= gazebo type= bool default= false desc= Configure whether to run the program in gazebo mode. } 1{ name= gazebo_robot_name type= string default= "" desc= Configure the robot name for joint_state topic name when running in gazebo mode.<
> ex) If ''''op3'''' is the ''''gazebo_robot_name'''', ''''/op3/joint_states'''' will be subscribed. } 2{ name= offset_file_path type= string default= "" desc= This path indicates the location of the file that contains offset data of each joint and initial posture data for offset adjustment. } 3{ name= robot_file_path type= string default= "" desc= This path indicates the location of .robot file that contains robot description data. } 4{ name= init_file_path type= string default= "" desc= This path indicates the location of the file that contains initialization information of each joint. } 5{ name= device_name type= string default= "/dev/ttyUSB0" desc= This port name is used to open the communication port of OpenCR that manages Dynamixel power supply. } 6{ name= baud_rate type= int default= "2000000" desc= This baud rate is used to open the communication port of OpenCR that manages Dynamixel power supply. } } } }}} === Using Libraries === Each library has publishers and subcribers. Please refer to the information on the link. * [[http://wiki.ros.org/robotis_controller|robotis_controller]] * [[http://wiki.ros.org/op3_action_module|op3_action_module]] * [[http://wiki.ros.org/op3_base_module|op3_base_module]] * [[http://wiki.ros.org/op3_direct_control_module|op3_direct_control_module]] * [[http://wiki.ros.org/op3_head_control_module|op3_head_control_module]] * [[http://wiki.ros.org/op3_online_walking_module|op3_online_walking_module]] * [[http://wiki.ros.org/op3_walking_module|op3_walking_module]] * [[http://wiki.ros.org/open_cr_module|open_cr_module]]