.. rubric:: Leg Control Mode

The following H1 modes are available via ROS2 services:

.. code-block:: bash

   - damp
   - stand_switch
   - increase_swing_height
   - decrease_swing_height
   - enable_ctrl

.. note::

   Pressing the **Tab** key on the keyboard will autocomplete the service request.

.. rubric:: Example of Activating a Mode

To activate a specific mode, use the following command:

.. code-block:: bash

   ROS_DOMAIN_ID=10 ros2 service call /h1/leg_modes h1_srvs/srv/H1Modes '{"request_data": "stand_switch"}'

.. rubric:: Arm Low-Level Control


The predefined arm positions do not include obstacle avoidance for either the robot or its environment.

.. Important::
    
   Ensure that the arms are straight down when powering on the robot. If the orientation is different, it will affect the ROS2 control operation. The arms will initialize and move so that the forearms are facing forward.

To set the arms to their default position, use the following command:

.. code-block:: bash

   h1_arm_default

.. list-table::
   :header-rows: 0
   :widths: 50 50

   * - .. figure:: media/gifs/arm_default.gif
          :width: 100%
          :align: center
          :alt: Executing arm default command

          Executing arm default command

     - .. figure:: media/gifs/arm_default_real.gif
          :width: 90%
          :align: center
          :alt: H1 arm moving to default position

          H1 arm moving to default position


.. Warning::

   Using the **h1_arm_zero** command brings the arms to a position that prevents backlash when 
   restarting the ROS2 control driver. This should be done before closing the ROS2 driver if you plan to run the driver again later.

To zero the arms, execute:

.. code-block:: bash

   h1_arm_zero

.. list-table::
   :header-rows: 0
   :widths: 50 50

   * - .. figure:: media/gifs/arm_zero.gif
          :width: 100%
          :align: center
          :alt: Executing arm zero command

          Executing arm zero command

     - .. figure:: media/gifs/arm_zero_real.gif
          :width: 90%
          :align: center
          :alt: H1 arm moving to zero position

          H1 arm moving to zero position

To set the arms to a T-pose, use:

.. code-block:: bash

   h1_arm_t

.. list-table::
   :header-rows: 0
   :widths: 50 50

   * - .. figure:: media/gifs/arm_t.gif
          :width: 100%
          :align: center
          :alt: Executing T-pose command

          Executing T-pose command

     - .. figure:: media/gifs/arm_t_real.gif
          :width: 90%
          :align: center
          :alt: H1 arm moving to T-pose

          H1 arm moving to T-pose

For a sample pose useful for picking objects, use:

.. code-block:: bash

   h1_arm_pick

.. list-table::
   :header-rows: 0
   :widths: 50 50

   * - .. figure:: media/gifs/arm_pick.gif
          :width: 100%
          :align: center
          :alt: Executing pick pose command

          Executing pick pose command

     - .. figure:: media/gifs/arm_pick_real.gif
          :width: 90%
          :align: center
          :alt: H1 arm moving to pick pose

          H1 arm moving to pick pose

.. rubric:: Examples of Trajectory Control

.. rubric:: Bring Left Arm to Zero Position


To bring the left arm to the zero position, run:

.. code-block:: bash

   ROS_DOMAIN_ID=10 ros2 action send_goal /left_arm_controller/follow_joint_trajectory control_msgs/action/FollowJointTrajectory -f "{
     trajectory: {
       joint_names: [left_shoulder_pitch_joint, 
       left_shoulder_roll_joint, left_shoulder_yaw_joint, 
       left_elbow_joint],
       points: [
         { positions: [0.0, 0.0, 0.0, 0.0], time_from_start: { sec: 2 } },
         { positions: [0.5, 0.0, 0.0, 0.1], time_from_start: { sec: 4 } },
       ]
     }
   }"

.. rubric:: Bring Right Arm to Zero Position

To bring the right arm to the zero position, run:

.. code-block:: bash

   ROS_DOMAIN_ID=10 ros2 action send_goal /right_arm_controller/follow_joint_trajectory control_msgs/action/FollowJointTrajectory -f "{
     trajectory: {
       joint_names: [right_shoulder_pitch_joint, 
       right_shoulder_roll_joint, right_shoulder_yaw_joint, 
       right_elbow_joint],
       points: [
         { positions: [0.0, 0.0, 0.0, 0.0], time_from_start: { sec: 2 } },
         { positions: [0.5, 0.0, 0.0, 0.1], time_from_start: { sec: 4 } },
       ]
     }
   }"

To perform a final power-off of the arms, use:

.. code-block:: bash

   h1_arm_zero

.. list-table::
   :header-rows: 0
   :widths: 50 50

   * - .. figure:: media/gifs/arm_goal.gif
          :width: 100%
          :align: center
          :alt: Executing trajectory control to zero position

          Executing trajectory control to zero position

     - .. figure:: media/gifs/arm_goal_real.gif
          :width: 85%
          :align: center
          :alt: H1 arm transitioning from T-pose to zero position

          H1 arm transitioning from T-pose to zero position


.. rubric:: MoveIt2 Integration


To launch the H1 MoveIt2 driver, run:

.. code-block:: bash

   ros2 launch h1_moveit system.launch.py

This will open MoveIt2, which can be used for various manipulation tasks. 
Be sure to set a planner, such as TRRT, before planning and executing a motion plan.
