(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Programming Hiro / NEXTAGE OPEN (ROS)

Description: Out of 3 levels of ROS APIs introduced, ROS_Client, the dedicated ROS interface for HiroNXO, is mainly explained.

Tutorial Level: INTERMEDIATE

Next Tutorial: Programming Hiro/NEXTAGE OPEN through GUI

NOTE: All the tutorials available under the URL http://wiki.ros.org/rtmros_nextage/Tutorials are applicable to the multiple products of Kawada Industries; Hiro (only with the one that opensource software is installed) and NEXTAGE OPEN. To simplify the notation in the rest of the tutorials, we use HiroNXO to appoint the aforementioned robots.

Introduction

Now we're ready to operate the robot in a programmatic way. In this page, first we overview two recommended programming interfaces. Then using simulation mode, we'll actually operate robot from commandline.

We'll use interactive console in this page. Writing and "saving them into files" style of programming will be covered in later tutorial pages.

Two types of programming interfaces

When programming HiroNXO, use either one of the following interfaces:

  • ROS_Client unless you have specific requirement.

  • HIRONX (hrpsys-based python interface that provides more functionalities but less standardized).

Program the robot

Don't forget to run "ros_bridge" when you use ROS

Let's program the robot. First and once again before using ROS for HiroNXO, make sure RTM-ROS-bridge is running.

Programming from commandline (via ipython)

In this page, we'll use commandline / terminal, using ipython interactive console, to show how to program the robot.

NOTE: The feature in this section requires hironx_ros_bridge package version 1.0.24 or greter.

Let's run the ROS client via a python script, just as we did for RTM client in the previous tutorial.

  • $ ipython -i `rospack find hironx_ros_bridge`/scripts/hironx.py

    Actually, you're running the same script hironx.py from the previous tutorial to run ROS client; it launches both RTM and ROS clients.

    :
    [hrpsys.py]  initialized successfully
    [INFO] [WallTime: 1410918126.749067] [206.795000] Joint names; Torso: ['CHEST_JOINT0']
            Head: ['HEAD_JOINT0', 'HEAD_JOINT1']
            L-Arm: ['LARM_JOINT0', 'LARM_JOINT1', 'LARM_JOINT2', 'LARM_JOINT3', 'LARM_JOINT4', 'LARM_JOINT5']
            R-Arm: ['RARM_JOINT0', 'RARM_JOINT1', 'RARM_JOINT2', 'RARM_JOINT3', 'RARM_JOINT4', 'RARM_JOINT5']
    [ERROR] [1410918130.900627643, 210.289999999]: Robot semantic description not found. Did you forget to define or remap '/robot_description_semantic'?
    [ INFO] [1410918130.900757547, 210.289999999]: Loading robot model 'HiroNX'...
    [ INFO] [1410918130.900794422, 210.289999999]: No root joint specified. Assuming fixed joint
    [FATAL] [1410918131.991522557, 211.249999999]: Group 'left_arm' was not found.
    [ERROR] [WallTime: 1410918132.006310] [211.285000] Group 'left_arm' was not found.
    Make sure you've launched MoveGroup (e.g. by launching moveit_planning_execution.launch)

    If you see the errors like above, that means you are not running MoveIt! service. Go back to the earlier tutorial and launch it. OR, if you know you won't need MoveIt!, just leave it; some methods in ROS client still works without MoveIt!. Now, check what commands are available.

    In [1]: ros.
    ros.Joint                        ros.get_joint                    ros.go_init
    ros.Link                         ros.get_joint_names              ros.go_offpose
    ros.get_current_state            ros.get_link                     ros.has_group
    ros.get_current_variable_values  ros.get_link_names               ros.set_joint_angles_deg
    ros.get_default_owner_group      ros.get_planning_frame           ros.set_joint_angles_rad
    ros.get_group                    ros.get_root_link                ros.set_pose
    ros.get_group_names              ros.goInitial             

    ROS_Client via this script is available by ros object. Because ROS_Client inherits RobotCommander from MoveIt! as already noted, you're seeing many methods from the derived class. In addition to them, a few methods are implemented specifically for ROS_Client such as goInitial, go_init, go_offpose and set_pose, all of which are intended as equivalent to those in RTM version of python interface HIRONX. With the following command, all joints move to the location that as a whole make robot's initial pose.

    In [1]: ros.go_init()
    [INFO] [WallTime: 1410918153.591171] [226.790000] *** go_init begins ***
    [INFO] [WallTime: 1410918165.419528] [233.825000] wait_for_result for the joint group rarm = True
    [INFO] [WallTime: 1410918165.423372] [233.825000] [positions: [0.010471975511965976, 0.0, -1.7453292519943295, -0.26529004630313807, 0.16406094968746698, -0.05585053606381855]
    velocities: []
    accelerations: []
    effort: []
    time_from_start: 
      secs: 7
      nsecs: 0]

    Likewise, using ipython's feature, you can take a look at each command's api document.

    In [2]: ros.go_init?
    Type:       instancemethod
    Base Class: <type 'instancemethod'>
    String Form:<bound method ROS_Client.go_init of <hironx_ros_bridge.ros_client.ROS_Client object at 0x49b7210>>
    Namespace:  Interactive
    File:       /home/rosnoodle/cws_hiro_nxo/src/start-jsk/rtmros_hironx/hironx_ros_bridge/src/hironx_ros_bridge/ros_client.py
    Definition: ros.go_init(self, task_duration=7.0)
    Docstring:
    Init positions are taken from HIRONX.
    TODO: Need to add factory position too that's so convenient when
          working with the manufacturer.
    @type task_duration: float

    For compatibility with RTM python interface (HIRONX) where the name of an equivalent method is different (`goInitial`), a method with the same name is available too.

    IN [3]: ros.goInitial?
    Type:       instancemethod
    String Form:<bound method ROS_Client.goInitial of <hironx_ros_bridge.ros_client.ROS_Client object at 0x7f23458f0c50>>
    File:       /home/n130s/link/ROS/indigo_trusty/cws_hironxo/src/start-jsk/rtmros_hironx/hironx_ros_bridge/src/hironx_ros_bridge/ros_client.py
    Definition: ros.goInitial(self, init_pose_type=0, task_duration=7.0)
    Docstring:
    This method internally calls self.go_init.
    
    This method exists solely because of compatibility purpose with
    hironx_ros_bridge.hironx_client.HIRONX.goInitial, which
    holds a method "goInitial".
    
    @param init_pose_type:
           0: default init pose (specified as _InitialPose)
           1: factory init pose (specified as _InitialPose_Factory)

(Option) Level of APIs

This section is "good to read", but not required. You can skip to the next tutorial if you don't feel like.

As dipicted in a previous tutorial, HiroNXO systems runs on 2 different robotics framework for historical reasons. That's why we have 2 programming interfaces.

RTM-ROS-bridge allows you to send status and control signals via ROS to the robot, in particular over joint_state_publisher, trajectory_msgs. Based on these pipelines, higher level apps, e.g. MoveIt! can work without any restriction. Also, those lower level APIs are made to allow maximum flexibility, meaning that they are not necessarilly simple to use. ROS_Client is a dedicated client class right for the HiroNXO users to mine the gap.

  • https://docs.google.com/drawings/d/1H1GLYfBmZ7JRnBhKubCrptav34fCfZzn3W9PEO_5pgI/pub?w=960&h=720 Fig. List of the API revisited. "Lower level APIs" mentioned earlier corresponds to Joint Trajectory Action in this diagram.

:D New since version 1.1.4: ROS_Client now inherits moveit_commander.robot.RobotCommander. You can directly operate MoveGroupCommander through that class.

In fact you can most likely not work only with ROS I/F and you mix with RTM I/F. See the rationale here for more background. In this tutorial we only assume the tasks manageable by ROS client.

Wiki: rtmros_nextage/Tutorials/Programming_Hiro_NEXTAGE_OPEN_ROS (last edited 2016-07-12 23:54:11 by IsaacSaito)