Skip to content
/ xpp Public
forked from leggedrobotics/xpp

Visualization of Motion Plans for Legged Robots in rviz.

License

Notifications You must be signed in to change notification settings

Sreevis/xpp

 
 

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

Build Status DOI

Xpp is a collection of ROS-packages (http://wiki.ros.org/xpp) for the visualization of motion plans for floating-base robots. Apart from drawing support areas, contact forces and motion trajectories in RVIZ, it also displays these plans for specific robots. Current robots include a one-legged, a two-legged hopper, HyQ and a quadrotor.

Author/Maintainer: Alexander W. Winkler

               

This code was mostly developed at the Agile and Dexterous Robotics Lab, ETH Zurich. It is currently maintained by the Robotics Systems Lab, ETH Zurich. See AUTHORS.md for more information on development and contributors.

Dependencies

ROS
Packages: catkin, roscpp, tf, kdl_parser, robot_state_publisher, message_runtime, message_generation, std_msgs, geometry_msgs, sensor_msgs, rviz, rosbag

$ sudo apt-get install ros-[ros_distro_name]-[pkg_name]

Eigen

$ sudo apt-get install libeigen3-dev

Building

To build from source, clone the latest version from this repository into your catkin workspace and compile the package using

$ cd catkin_workspace/src
$ git clone https://github.com/leggedrobotics/xpp.git
$ cd ..
$ catkin_make -DCMAKE_BUILD_TYPE=Release
$ source ./devel/setup.bash

Unit Tests

Make sure everything installed correctly by running the unit tests through

$ catkin_make run_tests

or if you are using catkin tools.

$ catkin build xpp_vis --no-deps --verbose --catkin-make-args run_tests

Usage

A few examples for different robots are provided in the xpp_examples package. For starters, run

$ roslaunch xpp_examples hyq_bag.launch  // or any other launch file in this package

These scripts actually executes the following steps:

  1. Start the visualization nodes, launch rviz with the correct config and wait for robot messages using roslaunch xpp_vis xpp.launch.

  2. Now robot messages of type xpp_msgs/RobotStateCartesian.msg can be sent and visualized. Since we also want to display the URDF of a specific robot, the URDF file of the robot (e.g xpp_hyq/urdf/monoped.urdf must be uploaded to the ROS parameter server.

  3. Next a node must be created that transforms xpp_msgs/RobotStateJoints.msg into rviz TFs. If we also want to display Cartesian messages xpp_msgs/RobotStateCartesian.msg, Inverse Kinematics are neccessary for the specific robots.

  4. Finally, motions plans must be published for the specific robots. Rosbags of sample motions plans can be found at xpp_examples/bags/ and can be run using rosbag play [bagname]. To see some examples of how to generate these bag files or messages, check out xpp_examples/src/monoped_bag_builder.cc and xpp_examples/src/monoped_publisher.cc. For a more sophisticated way we used to generate these bags files , see towr.

Citation

If you use this work in an academic context, please cite the currently released version DOI as shown here.

Bugs & Feature Requests

Please report bugs and request features using the Issue Tracker.

About

Visualization of Motion Plans for Legged Robots in rviz.

Resources

License

Stars

Watchers

Forks

Packages

No packages published

Languages

  • C++ 94.5%
  • CMake 5.5%