Skip to content

Commit

Permalink
Add travis build (moveit#17)
Browse files Browse the repository at this point in the history
Fix broken links
  • Loading branch information
davetcoleman authored and v4hn committed Sep 29, 2016
1 parent d0e5f43 commit 87bc2bd
Show file tree
Hide file tree
Showing 27 changed files with 91 additions and 49 deletions.
41 changes: 41 additions & 0 deletions .travis.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
# Test build the MoveIt! tutorials. Author: Dave Coleman
sudo: required
dist: trusty
language: generic
python:
- "2.7"
compiler:
- gcc
before_install: # Use this to prepare the system to install prerequisites or dependencies
# Define some config vars
- export CI_SOURCE_PATH=$(pwd)
- export REPOSITORY_NAME=${PWD##*/}
- echo "Testing branch $TRAVIS_BRANCH of $REPOSITORY_NAME"
- sudo -E sh -c 'echo "deb http://packages.ros.org/ros/ubuntu `lsb_release -cs` main" > /etc/apt/sources.list.d/ros-latest.list'
- wget http://packages.ros.org/ros.key -O - | sudo apt-key add -
- sudo apt-get update -qq
- sudo apt-get install -qq -y python-rosdep python-wstool python-catkin-tools
# Setup rosdep
- sudo rosdep init
- rosdep update

install:
- sudo apt-get update
# Install newer version of ruby
- sudo apt-get -qq install software-properties-common
- sudo apt-add-repository -y ppa:brightbox/ruby-ng
- sudo apt-get update
- sudo apt-get -qq install ruby2.2-dev ruby2.2
# Install htmlpoofer
- sudo gem update
- sudo gem install pkg-config
- sudo gem install mini_portile2
- sudo gem install html-proofer
# Install ROS's version of sphinx
- sudo apt-get -qq install ros-indigo-rosdoc-lite
- source /opt/ros/indigo/setup.bash

script: # run tests
- rosdoc_lite -o build .
- ls -la
- htmlproofer ./build --only-4xx --check-html --file-ignore ./build/html/genindex.html,./build/html/search.html,./build/html/index-msg.html --alt-ignore '/.*/' --url-ignore '#'
6 changes: 6 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@

This repo is automatically built by the ROS build farm and its output is hosted here: http://docs.ros.org/indigo/api/moveit_tutorials/html/

## Travis Continuous Integration

[![Build Status](https://travis-ci.org/ros-planning/moveit_tutorials.svg?branch=master)](https://travis-ci.org/ros-planning/moveit_tutorials)

## ROS Buildfarm

[![Build Status](http://build.ros.org/buildStatus/icon?job=Idoc__moveit_tutorials__ubuntu_trusty_amd64&build=2)](http://build.ros.org/job/Idoc__moveit_tutorials__ubuntu_trusty_amd64/2/)

## Build
Expand Down
3 changes: 2 additions & 1 deletion conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,9 +53,10 @@
# Add any paths that contain custom themes here, relative to this directory.

# Links
extlinks = {'codedir': ('https://github.com/ros-planning/moveit_pr2/blob/hydro-devel/moveit_tutorials/%s', ''),
extlinks = {'codedir': ('https://github.com/ros-planning/moveit_tutorials/tree/master/doc/pr2_tutorials//%s', ''),
'moveit_core': ('http://docs.ros.org/indigo/api/moveit_core/html/classmoveit_1_1core_1_1%s.html', ''),
'planning_scene': ('http://docs.ros.org/indigo/api/moveit_core/html/classplanning__scene_1_1%s.html', ''),
'planning_scene_interface': ('http://docs.ros.org/indigo/api/moveit_ros_planning_interface/html/classmoveit_1_1planning__interface_1_1%s.html', ''),
'planning_scene_monitor': ('http://docs.ros.org/indigo/api/moveit_ros_planning/html/classplanning__scene__monitor_1_1%s.html', ''),
'collision_detection_struct': ('http://docs.ros.org/indigo/api/moveit_core/html/structcollision__detection_1_1%s.html', ''),
'collision_detection_class': ('http://docs.ros.org/indigo/api/moveit_core/html/classcollision__detection_1_1%s.html', ''),
Expand Down
3 changes: 2 additions & 1 deletion doc/ikfast_tutorial.rst
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,8 @@ Inside your catkin workspace ::

OpenRAVE Installation
----------------------
**Binary Install (only Indigo / Ubuntu 14.04) **

**Binary Install (only Indigo / Ubuntu 14.04)**

sudo apt-get install ros-indigo-openrave

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Acorn Pooley */

// This code goes with the Attached Body tutorial
// http://moveit.ros.org/wiki/index.php/Groovy/InteractiveRobot/AttachedBody
// http://picknik.io/moveit_wiki/index.php?title=InteractiveRobot/AttachedBody

#include <ros/ros.h>
#include "interactive_robot.h"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Acorn Pooley */

// This code goes with the Collision Contact Visualization tutorial
// http://moveit.ros.org/wiki/index.php/Groovy/InteractiveRobot/CollisionContact
// http://picknik.io/moveit_wiki/index.php?title=InteractiveRobot/CollisionContact

#include <ros/ros.h>
#include "interactive_robot.h"
Expand Down
2 changes: 1 addition & 1 deletion doc/pr2_tutorials/interactivity/src/imarker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Acorn Pooley */

// This code goes with the interactivity tutorial
// http://moveit.ros.org/wiki/index.php/Groovy/InteractiveRobot/InteractivityTutorial
// http://picknik.io/moveit_wiki/index.php?title=InteractiveRobot/InteractivityTutorial

#include "imarker.h"
#include "pose_string.h"
Expand Down
2 changes: 1 addition & 1 deletion doc/pr2_tutorials/interactivity/src/imarker.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Acorn Pooley */

// This code goes with the interactivity tutorial
// http://moveit.ros.org/wiki/index.php/Groovy/InteractiveRobot/InteractivityTutorial
// http://picknik.io/moveit_wiki/index.php?title=InteractiveRobot/InteractivityTutorial

#ifndef MOVEIT_TUTORIALS_INTERACTIVITY_SRC_IMARKER_H_
#define MOVEIT_TUTORIALS_INTERACTIVITY_SRC_IMARKER_H_
Expand Down
2 changes: 1 addition & 1 deletion doc/pr2_tutorials/interactivity/src/interactive_robot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Acorn Pooley */

// This code goes with the interactivity tutorial
// http://moveit.ros.org/wiki/index.php/Groovy/InteractiveRobot/InteractivityTutorial
// http://picknik.io/moveit_wiki/index.php?title=InteractiveRobot/InteractivityTutorial

#include "interactive_robot.h"
#include <eigen_conversions/eigen_msg.h>
Expand Down
2 changes: 1 addition & 1 deletion doc/pr2_tutorials/interactivity/src/interactive_robot.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Acorn Pooley */

// This code goes with the interactivity tutorial
// http://moveit.ros.org/wiki/index.php/Groovy/InteractiveRobot/InteractivityTutorial
// http://picknik.io/moveit_wiki/index.php?title=InteractiveRobot/InteractivityTutorial

#ifndef MOVEIT_TUTORIALS_INTERACTIVITY_SRC_INTERACTIVE_ROBOT_H_
#define MOVEIT_TUTORIALS_INTERACTIVITY_SRC_INTERACTIVE_ROBOT_H_
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Acorn Pooley */

// This code goes with the interactivity tutorial
// http://moveit.ros.org/wiki/index.php/Groovy/InteractiveRobot/InteractivityTutorial
// http://picknik.io/moveit_wiki/index.php?title=InteractiveRobot/InteractivityTutorial

#include <ros/ros.h>
#include "interactive_robot.h"
Expand Down
2 changes: 1 addition & 1 deletion doc/pr2_tutorials/interactivity/src/pose_string.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Acorn Pooley */

// This code goes with the interactivity tutorial
// http://moveit.ros.org/wiki/index.php/Groovy/InteractiveRobot/InteractivityTutorial
// http://picknik.io/moveit_wiki/index.php?title=InteractiveRobot/InteractivityTutorial

#include "pose_string.h"

Expand Down
2 changes: 1 addition & 1 deletion doc/pr2_tutorials/interactivity/src/pose_string.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@
/* Author: Acorn Pooley */

// This code goes with the interactivity tutorial
// http://moveit.ros.org/wiki/index.php/Groovy/InteractiveRobot/InteractivityTutorial
// http://picknik.io/moveit_wiki/index.php?title=InteractiveRobot/InteractivityTutorial

#ifndef MOVEIT_TUTORIALS_INTERACTIVITY_SRC_POSE_STRING_
#define MOVEIT_TUTORIALS_INTERACTIVITY_SRC_POSE_STRING_
Expand Down
5 changes: 0 additions & 5 deletions doc/pr2_tutorials/kinematics/src/doc/kinematics_tutorial.rst
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,3 @@ The expected output will be in the following form. The numbers will not match si
0 0.965189 0.229185 0.973042 -0.0665617 -0.991369 -0.0900434
0 0.261552 -0.845745 0.212168 -0.116995 0.12017 -0.91467
1 0 -0.48186 0.0904127 0.990899 -0.0524048 -0.394045

Additional Reading
^^^^^^^^^^^^^^^^^^

* `RobotState Display <http://moveit.ros.org/wiki/RobotStateDisplay/C%2B%2B_API>`_ - Visualization of the RobotState using Rviz
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
<arg name="config" value="true"/>
</include>

<node name="motion_planning_interface_tutorial" pkg="moveit_tutorials" type="motion_planning_api_tutorial" respawn="false" launch-prefix="$(arg launch_prefix)" output="screen">
<node name="motion_planning_api_tutorial" pkg="moveit_tutorials" type="motion_planning_api_tutorial" respawn="false" launch-prefix="$(arg launch_prefix)" output="screen">
<rosparam command="load" file="$(find pr2_moveit_config)/config/kinematics.yaml"/>
<param name="/planning_plugin" value="ompl_interface/OMPLPlanner"/>
<rosparam command="load" file="$(find pr2_moveit_config)/config/ompl_planning.yaml"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ The entire code can be seen :codedir:`here in the moveit_pr2 github project<plan
The launch file
^^^^^^^^^^^^^^^
The entire launch file is `here
<https://github.com/ros-planning/moveit_pr2/blob/hydro-devel/moveit_tutorials/planning/launch/move_group_python_interface_tutorial.launch>`_
<https://github.com/ros-planning/moveit_tutorials/tree/master/doc/pr2_tutorials/planning/launch/move_group_python_interface_tutorial.launch>`_
on github. All the code in this tutorial can be run from the
moveit_tutorials package that you have as part of your MoveIt! setup.

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ Follow the `instructions for compiling code from source <http://moveit.ros.org/i

The launch file
^^^^^^^^^^^^^^^
The entire launch file is `here <https://github.com/ros-planning/moveit_pr2/blob/hydro-devel/moveit_tutorials/planning/launch/motion_planning_interface_tutorial.launch>`_ on github. All the code in this tutorial can be compiled and run from the moveit_tutorials package
The entire launch file is `here <https://github.com/ros-planning/moveit_tutorials/tree/master/doc/pr2_tutorials/planning/launch/planning_pipeline_tutorial.launch>`_ on github. All the code in this tutorial can be compiled and run from the moveit_tutorials package
that you have as part of your MoveIt! setup.

Running the code
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ Follow the `instructions for compiling code from source <http://moveit.ros.org/i

The launch file
^^^^^^^^^^^^^^^
The entire launch file is `here <https://github.com/ros-planning/moveit_pr2/blob/hydro-devel/moveit_tutorials/planning/launch/move_group_interface_tutorial.launch>`_ on github. All the code in this tutorial can be compiled and run from the moveit_tutorials package
The entire launch file is `here <https://github.com/ros-planning/moveit_tutorials/tree/master/doc/pr2_tutorials/planning/launch/move_group_interface_tutorial.launch>`_ on github. All the code in this tutorial can be compiled and run from the moveit_tutorials package
that you have as part of your MoveIt! setup.

Running the code
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ In this section, we will walk through configuring the 3D sensors on your robot w
YAML Configuration file (Point Cloud)
-------------------------------------

We will have to generate a YAML configuration file for configuring the 3D sensors. An example file for processing point clouds can be found in the `moveit_pr2 github project <https://github.com/ros-planning/moveit_pr2/blob/hydro-devel/pr2_moveit_config/config/sensors_kinect.yaml>`_ ::
We will have to generate a YAML configuration file for configuring the 3D sensors. An example file for processing point clouds can be found in the `moveit_pr2 github project <https://github.com/ros-planning/moveit_pr2/blob/indigo-devel/pr2_moveit_config/config/sensors_kinect.yaml>`_ ::

sensors:
- sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater
Expand All @@ -34,7 +34,7 @@ Parameters specific to the Point cloud updater are:
YAML Configuration file (Depth Map)
-----------------------------------

We will have to generate a rgbd.yaml configuration file for configuring the 3D sensors. An example file for processing point clouds can be found in the `moveit_advanced github project <https://github.com/ros-planning/moveit_advanced/blob/hydro-devel/pr2_advanced_config/config/sensors_kinect.yaml>`_ ::
We will have to generate a rgbd.yaml configuration file for configuring the 3D sensors. An example file for processing point clouds can be found in the `moveit_advanced github project <https://github.com/ros-planning/moveit_advanced/blob/indigo-devel/pr2_advanced_config/config/sensors_kinect.yaml>`_ ::

sensors:
- sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,15 +21,14 @@ Follow the `instructions for compiling code from source <http://moveit.ros.org/i

The launch file
^^^^^^^^^^^^^^^
The entire launch file is `here <https://github.com/ros-planning/moveit_pr2/blob/hydro-devel/moveit_tutorials/planning/launch/motion_planning_interface_tutorial.launch>`_ on github. All the code in this tutorial can be compiled and run from the moveit_tutorials package
that you have as part of your MoveIt! setup.
The entire launch file is `here <https://github.com/ros-planning/moveit_tutorials/tree/master/doc/pr2_tutorials/planning/launch/planning_pipeline_tutorial.launch>`_ on github. All the code in this tutorial can be compiled and run from the moveit_tutorials package that you have as part of your MoveIt! setup.

Running the code
^^^^^^^^^^^^^^^^

Roslaunch the launch file to run the code directly from moveit_tutorials::

roslaunch moveit_tutorials motion_planning_interface_tutorial.launch
roslaunch moveit_tutorials motion_planning_api_tutorial.launch

Expected Output
^^^^^^^^^^^^^^^
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ Follow the `instructions for compiling code from source <http://moveit.ros.org/i

The launch file
^^^^^^^^^^^^^^^
The entire launch file is `here <https://github.com/ros-planning/moveit_pr2/blob/hydro-devel/moveit_tutorials/planning/launch/planning_scene_ros_api_tutorial.launch>`_ on github. All the code in this tutorial can be compiled and run from the moveit_tutorials package
The entire launch file is `here <https://github.com/ros-planning/moveit_tutorials/tree/master/doc/pr2_tutorials/planning/launch/planning_scene_ros_api_tutorial.launch>`_ on github. All the code in this tutorial can be compiled and run from the moveit_tutorials package
that you have as part of your MoveIt! setup.

Running the code
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ Follow the `instructions for compiling code from source <http://moveit.ros.org/i

The launch file
^^^^^^^^^^^^^^^
The entire launch file is `here <https://github.com/ros-planning/moveit_pr2/blob/hydro-devel/moveit_tutorials/planning/launch/planning_scene_tutorial.launch>`_ on github. All the code in this
The entire launch file is `here <https://github.com/ros-planning/moveit_tutorials/tree/master/doc/pr2_tutorials/planning/launch/planning_scene_tutorial.launch>`_ on github. All the code in this
tutorial can be compiled and run from the moveit_tutorials package
that you have as part of your MoveIt! setup.

Expand Down
27 changes: 13 additions & 14 deletions doc/pr2_tutorials/planning/src/planning_pipeline_tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,8 @@ int main(int argc, char **argv)
// BEGIN_TUTORIAL
// Start
// ^^^^^
// Setting up to start using a planning pipeline is pretty easy.
// Before we can load the planner, we need two objects, a RobotModel
// Setting up to start using a planning pipeline is pretty easy.
// Before we can load the planner, we need two objects, a RobotModel
// and a PlanningScene.
// We will start by instantiating a
// `RobotModelLoader`_
Expand All @@ -69,14 +69,13 @@ int main(int argc, char **argv)
robot_model::RobotModelPtr robot_model = robot_model_loader.getModel();

// Using the :moveit_core:`RobotModel`, we can construct a
// :planning_scene:`PlanningScene` that maintains the state of
// the world (including the robot).
// :planning_scene:`PlanningScene` that maintains the state of
// the world (including the robot).
planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model));

// We can now setup the
// `PlanningPipeline`_
// object, which will use the ROS param server
// to determine the set of request adapters and the
// We can now setup the PlanningPipeline
// object, which will use the ROS param server
// to determine the set of request adapters and the
// planning plugin to use
planning_pipeline::PlanningPipelinePtr planning_pipeline(new planning_pipeline::PlanningPipeline(robot_model, node_handle, "planning_plugin", "request_adapters"));

Expand All @@ -102,8 +101,8 @@ int main(int argc, char **argv)
std::vector<double> tolerance_pose(3, 0.01);
std::vector<double> tolerance_angle(3, 0.01);

// We will create the request as a constraint using a helper function available
// from the
// We will create the request as a constraint using a helper function available
// from the
// `kinematic_constraints`_
// package.
//
Expand Down Expand Up @@ -177,13 +176,13 @@ int main(int argc, char **argv)

// Using a Planning Request Adapter
// ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
// A planning request adapter allows us to specify a series of operations that
// should happen either before planning takes place or after the planning
// A planning request adapter allows us to specify a series of operations that
// should happen either before planning takes place or after the planning
// has been done on the resultant path

// First, let's purposefully set the initial state to be outside the
// First, let's purposefully set the initial state to be outside the
// joint limits and let the
// planning request adapter deal with it
// planning request adapter deal with it
/* First, set the state in the planning scene to the final state of the last plan */
robot_state = planning_scene->getCurrentStateNonConst();
planning_scene->setCurrentState(response.trajectory_start);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@


// This code is described in the RobotStateDisplay tutorial here:
// http://moveit.ros.org/wiki/index.php/Groovy/RobotStateDisplay/C%2B%2B_API
// http://picknik.io/moveit_wiki/index.php?title=RobotStateDisplay/C%2B%2B_API


int main(int argc, char **argv)
Expand Down
4 changes: 2 additions & 2 deletions doc/ros_visualization/visualization_tutorial.rst
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ Alternately, you can just install the pre-made MoveIt! configuration
for the PR2 in the pr2_moveit_config ROS package. To install it,
run::

sudo apt-get install ros-hydro-moveit-pr2
sudo apt-get install ros-indigo-moveit-pr2

This tutorial does **not** require you to actually have a PR2 robot,
it just needs a set of working robot model files.
Expand Down Expand Up @@ -156,5 +156,5 @@ What's Next
-------------

* `MoveIt! and a simulated robot
<http://moveit.ros.org/wiki/PR2/Gazebo/Quick_Start>`_ - You can now
<http://picknik.io/moveit_wiki/index.php?title=PR2/Gazebo/Quick_Start>`_ - You can now
start using MoveIt! with a simulated robot in Gazebo.
10 changes: 5 additions & 5 deletions doc/setup_assistant/setup_assistant_tutorial.rst
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ configuring any robot for use with MoveIt!. Its primary function is
generating a Semantic Robot Description Format (SRDF) file for your
robot. Additionally, it generates other necessary configuration files
for use with the MoveIt! pipeline. To learn more about the SRDF, you
can go through the `SRDF Overview <http://moveit.ros.org/wiki/SRDF>`_
can go through the `SRDF Overview <http://picknik.io/moveit_wiki/index.php?title=SRDF>`_
page.

Pre-requisites
Expand Down Expand Up @@ -37,9 +37,9 @@ Step 1: Start
.. image:: setup_assistant_start.png

* Click on the browse button and navigate to the *pr2.urdf.xacro* file
installed when you installed ros-hydro-moveit-full-pr2. (This file
installed when you installed ros-indigo-moveit-full-pr2. (This file
gets installed in
/opt/ros/hydro/share/pr2_description/robots/pr2.urdf.xacro on Ubuntu
/opt/ros/indigo/share/pr2_description/robots/pr2.urdf.xacro on Ubuntu
with ROS Hydro.) Choose that file and then click *Load Files*. The
Setup Assistant will load the files (this might take a few seconds)
and present you with this screen:
Expand Down Expand Up @@ -289,13 +289,13 @@ Additional Reading

The SRDF

* See the `SRDF <http://moveit.ros.org/wiki/SRDF>`_ page for more
* See the `SRDF <http://picknik.io/moveit_wiki/index.php?title=SRDF>`_ page for more
details on the components of the SRDF mentioned in this tutorial.

URDF

* The URDF is the native robot description format in ROS and allows
you to describe the kinematics, inertial, visual and sensing
properties of your robot. Read through the `URDF specific
documentation <http://moveit.ros.org/wiki/URDF>`_ to see how the
documentation <http://picknik.io/moveit_wiki/index.php?title=URDF>`_ to see how the
URDF is used with MoveIt!
Empty file added genindex.rst
Empty file.

0 comments on commit 87bc2bd

Please sign in to comment.