Skip to content
Vinayak Jagtap edited this page Aug 1, 2019 · 21 revisions

logo

TOUGH library provides C++ API to humanoid robots supported by IHMC controllers. The code is tested on Valkyrie R5 (branch: ihmc-0.8.2), srcsim (tag: 0.1a), Atlas/Valkyrie in SCS simulator(0.11.0) and the Atlas robot(0.11.0). The branch kinetic-0.11.0 is in active development and may not work as expected. ihmc_msgs are different for different versions. Following table gives the corresponding tough tag/branch name for versions of ihmc repo

ihmc controller version tough
0.8.2 ihmc-0.8.2
0.9.x 0.1a
0.11 0.11.0

We are skipping 0.10 version of ihmc controllers more details here

Installation

Directory Structure

tough_bringup

Provides launch files to start up various components required for nodes that use TOUGH

tough_common

This package hosts the global constants available for use. The constants include frame names, joint names, joint limits, etc.

tough_control

This package contains interface classes for all the controllers. Each controller has a test_ file that provides an example usage of the controller.

tough_motion_planners

This package hosts a cartesian planner using trac-ik and move-it. To use this planner, move-it configs located here are required.

tough_navigation

If a 2D map is hosted on /map topic, this package can be used to plan footsteps from current location to any goal pose on the map. Multiple examples of how to use it programmatically are present in the src directory

tough_perception

Code developed during DARPA Robotics Challenge by the WPI-CMU team for perception was used as baseline for development of this package. It provides images and pointcloud from multisense sensor. Utilities included in this package are laser assembler, walkway filter, robot filter, and a periodic snapshotter of pointcloud.

Examples

Sending chest trajectory to the robot

In this example we will write a node to move chest based such that it's roll=0, pitch=10, and yaw=30 degrees in 5 seconds. To start, let's include the header file for ChestControllerInterface.

#include <tough_controller_interface/chest_control_interface.h>

Now that we have access to the functions to control chest, we should initialize a ChestControllerInterface object in a ros node to call those functions. This needs ros::NodeHandle as a constructor argument.

#include <tough_controller_interface/chest_control_interface.h>

int main(int argc, char **argv)
{
    // Initialize a ros node
    ros::init(argc, argv, "test_node");
    ros::NodeHandle nh;

    // Create an object of ChestControlInterface
    ChestControlInterface chestTraj(nh);

Now we can call the controlChest function to move the chest in required orientation

float roll = 0.0f * M_PI/180.0; // convert angles into radians before sending it to the robot
float pitch = 10.0f * M_PI/180.0;
float yaw = 30.0f * M_PI/180.0;
float duration = 5.0f; 

// change the chest orientation. This is a non-blocking call.
chestTraj.controlChest(roll, pitch, yaw, duration);

Putting it all together, we have the following code that moves the robot chest to the specified orientation.

#include <tough_controller_interface/chest_control_interface.h>

int main(int argc, char **argv)
{
    // Initialize a ros node
    ros::init(argc, argv, "test_node");
    ros::NodeHandle nh;

    // Create an object of ChestControlInterface
    ChestControlInterface chestTraj(nh);
    float roll = 0 * M_PI/180.0;
    float pitch = 10 * M_PI/180.0;
    float yaw = 30 * M_PI/180.0;
    float duration = 5.0f; 

    // change the chest orientation. This is a non-blocking call.
    chestTraj.controlChest(roll, pitch, yaw, duration);

    // wait for the robot to move
    ros::Duration(duration).sleep();
    ROS_INFO("Motion finished");
    return 0;
}

Sending Specified Height to Pelvis

In this example, we will write an example node that makes the robot's pelvis height change to its maximum height, 1.05 meters above the left foot frame.

We will start by including the header file of the Pelvis Interface, so that we can build Pelvis Control Interface objects.

#include <tough_controller_interface/pelvis_control_interface.h>

Now that we have the ability to create a PelvisControlInterface object in our example and we have access to the methods that will actually move our robot, we should create the object. The constructor of the PelvisControlInterface requires a parameter: a NodeHandle object. Therefore, we must declare a NodeHandle, and then initialize, like so:

int main(int argc, char **argv)
{
    // Initialize a ros node
    ros::init(argc, argv, "test_node");
    ros::NodeHandle nh;

    // Create an object of PelvisControlInterface - used for actually altering the height of the robot
    PelvisControlInterface pelvisInt(nh);

Now, once we have created the Interface object, we can change the height of the pelvis to 1.05 meters. The robot starts off at around 0.90 meters for pelvis height.

    float height = 1.05;

    // change the pelvis height. This is a non-blocking call.
    pelvisInt.controlPelvisHeight(height);

Once all of that code is put together, the final program should like the following:

#include <tough_controller_interface/pelvis_control_interface.h>

int main(int argc, char **argv)
{
    // Initialize a ros node
    ros::init(argc, argv, "test_node");
    ros::NodeHandle nh;

    // Create an object of PelvisControlInterface - used for actually altering the height of the robot
    PelvisControlInterface pelvisInt(nh);
    std::cout << pelvisInt.getPelvisHeight() << std::endl;
    float height = 1.05;

    // change the pelvis height. This is a non-blocking call.
    pelvisInt.controlPelvisHeight(height);

    // wait for the robot to move
    ros::Duration(2).sleep();
    ROS_INFO("Motion finished");
    return 0;
}

More Examples: