Show EOL distros: 

xpp: xpp_examples | xpp_hyq | xpp_msgs | xpp_quadrotor | xpp_states | xpp_vis

Package Summary

Visualization of motion-plans for legged robots. It draws support areas, contact forces and motion trajectories in RVIZ and displays URDFs for specific robots, including a one-legged, a two-legged hopper and HyQ. Example motions were generated by towr.

xpp: xpp_examples | xpp_hyq | xpp_msgs | xpp_quadrotor | xpp_states | xpp_vis

Package Summary

Visualization of motion-plans for legged robots. It draws support areas, contact forces and motion trajectories in RVIZ and displays URDFs for specific robots, including a one-legged, a two-legged hopper and HyQ. Example motions were generated by towr.

xpp: xpp_examples | xpp_hyq | xpp_msgs | xpp_quadrotor | xpp_states | xpp_vis

Package Summary

Visualization of motion-plans for legged robots. It draws support areas, contact forces and motion trajectories in RVIZ and displays URDFs for specific robots, including a one-legged, a two-legged hopper and HyQ. Example motions were generated by towr.

xpp: xpp_examples | xpp_hyq | xpp_msgs | xpp_quadrotor | xpp_states | xpp_vis

Package Summary

Visualization of motion-plans for legged robots. It draws support areas, contact forces and motion trajectories in RVIZ and displays URDFs for specific robots, including a one-legged, a two-legged hopper and HyQ. Example motions were generated by towr.

xpp: xpp_examples | xpp_hyq | xpp_msgs | xpp_quadrotor | xpp_states | xpp_vis

Package Summary

Visualization of motion-plans for legged robots. It draws support areas, contact forces and motion trajectories in RVIZ and displays URDFs for specific robots, including a one-legged, a two-legged hopper and HyQ. Example motions were generated by towr.


https://i.imgur.com/ct8e7T4.png

Getting Started

Just download the precompiled debian for your ros distro (e.g. kinetic) and playback the bag files:

$ sudo apt-get install ros-kinetic-xpp
$ roslaunch xpp_examples hyq_bag.launch

Also you can always clone the repo into your catkin workspace and build from source, as described here.

anymal.gif

Generating messages

The more involved example trajectories shown have been generated with towr, an optimizer for legged robot motions. However, simple motion plans can also be generated by hand as shown below. This example is taken from xpp_examples/monoped_pub.cc. Run it using

$ roslaunch xpp_examples monoped_ex_generate.launch 

   1 #include <ros/ros.h>
   2 #include <xpp_msgs/RobotStateCartesian.h>
   3 #include <xpp_states/robot_state_cartesian.h>
   4 #include <xpp_states/convert.h>
   5 
   6 using namespace xpp;
   7 
   8 int main(int argc, char *argv[])
   9 {
  10   ros::init(argc, argv, "hopper_publisher");
  11   ros::NodeHandle n;
  12   ros::Publisher state_pub = n.advertise<xpp_msgs::RobotStateCartesian>("state", 1);
  13 
  14   // visualize the state of a one-legged hopper
  15   RobotStateCartesian hopper(1);
  16 
  17   // publishes a sequence of states for a total duration of T spaced 0.01s apart.
  18   double T = 2.0;
  19   double t = 0.0;
  20   double dt = 0.01;
  21   while (t < T)
  22   {
  23     // base and foot follow half a sine motion up and down
  24     hopper.base_.lin.p_.z()        = 0.7 - 0.05*sin(M_PI/T*t);
  25     hopper.ee_motion_.at(0).p_.z() = 0.1*sin(M_PI/T*t);
  26     hopper.ee_forces_.at(0).z()    = 100;  // Newtons
  27     hopper.ee_contact_.at(0)       = true; // leg in contact
  28 
  29     state_pub.publish(Convert::ToRos(hopper));
  30 
  31     ros::spinOnce();
  32     ros::Duration(dt).sleep(); // pause loop so visualization has correct speed.
  33     t += dt;
  34   }
  35 }

Plot the motions

The visualized trajectories in the rosbags can be easily plotted.

$ roscd xpp_examples/bags/
$ rqt_bag hyq.bag 

Then simply right-click on xpp/state_des and View -> Plot.

https://i.imgur.com/T79RxR6.png

Or load the rosbag in PlotJuggler

https://i.imgur.com/lUSAZDO.png

Visualize your own robot

To visualize your own URDF is very easy to setup. A minimal example to follow can be seen here:urdf_visualizer_hyq1.cc.

  • Upload your urdf to the ROS parameter server (example).

       1  <param name="name_of_your_urdf_model_given" 
       2    command="$(find xacro)/xacro '$(find xpp_your_robot)/urdf/your_robot.urdf'"/>
    
  • Instantiate your custom UrdfVisualizer() and run as ros node.

  • Send out the state of the robot using xpp_msgs/RobotStateJoint.

  • (optional) Send out xpp_msgs/RobotStateCartesian and supply inverse kinematics function to transform to xpp_msgs/RobotStateJoint.

  • Add the ROS parameter robot name (defined in step 1) of your urdf to rviz:

    rviz_add_robot2.png

Contribute

We would be happy to see a pull-request to add your robot. Apart from benefitting the open-source community, this also adds publicity and visibility to you / your lab. The ROS page you can then design for your robot could look similar to this: xpp_hyq.

Packages Overview

The core packages that this ROS stack offers are:

  • xpp_states: Classes to define robot states in cartesian and joint space.

  • xpp_msgs: ROS message representation of the above states.

  • xpp_vis: Visualization of states and robots through rviz.

Some optional packages include:

Publications

If you use this work in an academic context, please consider citing the code as

@misc{xpp_ros,
  author = {Alexander W. Winkler},
  title  = {{Xpp - A collection of ROS packages for the visualization of legged robots}},
  year   = {2017},
  doi    = {10.5281/zenodo.1037901},
  url    = {https://doi.org/10.5281/zenodo.1037901}
}

This software has been used in the following publications:

Questions

Please post any questions you have at ROS Answers using the tag xpp.

Wiki: xpp (last edited 2019-01-29 12:04:09 by AlexanderWinkler)