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.
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]
$ sudo apt-get install libeigen3-dev
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
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
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:
-
Start the visualization nodes, launch rviz with the correct config and wait for robot messages using
roslaunch xpp_vis xpp.launch
. -
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.gxpp_hyq/urdf/monoped.urdf
must be uploaded to the ROS parameter server. -
Next a node must be created that transforms
xpp_msgs/RobotStateJoints.msg
into rviz TFs. If we also want to display Cartesian messagesxpp_msgs/RobotStateCartesian.msg
, Inverse Kinematics are neccessary for the specific robots. -
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 usingrosbag play [bagname]
. To see some examples of how to generate these bag files or messages, check outxpp_examples/src/monoped_bag_builder.cc
andxpp_examples/src/monoped_publisher.cc
. For a more sophisticated way we used to generate these bags files , see towr.
If you use this work in an academic context, please cite the currently released version as shown here.
Please report bugs and request features using the Issue Tracker.